robot_description_builder/chained/
chained_jointbuilder.rs

1use std::sync::Weak;
2
3use nalgebra::Matrix3;
4
5use super::{ChainableBuilder, Chained};
6use crate::{
7	cluster_objects::kinematic_data_tree::KinematicDataTree,
8	joint::{BuildJointChain, Joint, JointBuilder},
9	link::{builder::LinkBuilder, Link, LinkShapeData},
10	transform::{Mirror, MirrorAxis},
11	utils::{ArcLock, WeakLock},
12};
13
14impl Chained<JointBuilder> {
15	/// TODO: TEST
16	/// TODO: DOC
17	pub fn mirror(&self, axis: MirrorAxis) -> Chained<JointBuilder> {
18		let mirror_matrix: Matrix3<_> = axis.into();
19		Chained(self.0.mirrored(&mirror_matrix))
20	}
21}
22
23impl ChainableBuilder for JointBuilder {
24	fn has_chain(&self) -> bool {
25		self.child.is_some()
26	}
27}
28
29impl BuildJointChain for Chained<JointBuilder> {
30	fn build_chain(
31		self,
32		tree: &Weak<KinematicDataTree>,
33		parent_link: &WeakLock<Link>,
34		parent_link_size_data: LinkShapeData,
35	) -> ArcLock<Joint> {
36		self.0.build_chain(tree, parent_link, parent_link_size_data)
37	}
38}
39
40impl<JointB, LinkB> From<(JointB, LinkB)> for Chained<JointBuilder>
41where
42	JointB: Into<JointBuilder>,
43	LinkB: Into<LinkBuilder>,
44{
45	fn from(value: (JointB, LinkB)) -> Self {
46		Chained(JointBuilder {
47			child: Some(value.1.into()),
48			..value.0.into()
49		})
50	}
51}
52
53#[cfg(test)]
54mod tests {
55	use super::{Chained, JointBuilder};
56	use std::f32::consts::FRAC_PI_2;
57	use test_log::test;
58
59	use crate::{
60		cluster_objects::KinematicInterface,
61		joint::{joint_data::LimitData, JointTransformMode, JointType, SmartJointBuilder},
62		link::{
63			link_data::{
64				geometry::{BoxGeometry, CylinderGeometry},
65				Collision, Visual,
66			},
67			Link,
68		},
69		linkbuilding::{CollisionBuilder, LinkBuilder, VisualBuilder},
70		material::MaterialDescriptor,
71		transform::{MirrorAxis, Transform},
72	};
73
74	#[test]
75	fn mirror_simple_1() {
76		let material_l1 = MaterialDescriptor::new_rgb(1., 0., 0.).named("Leg_l1");
77		let material_l2 = MaterialDescriptor::new_rgb(0., 1., 0.).named("Leg_l2");
78		let geom_leg_l1 = BoxGeometry::new(2., 3., 1.);
79		let geom_leg_l2 = CylinderGeometry::new(1., 10.);
80
81		let left_leg_1_tree = Link::builder("root").build_tree();
82
83		left_leg_1_tree
84			.get_root_link()
85			.write()
86			.unwrap()
87			.try_attach_child(
88				SmartJointBuilder::new_revolute("Leg_[L1]_j0")
89					.add_transform(Transform::new_translation(1., 2., 3.))
90					.with_axis((0., 1., 0.))
91					.with_limit(0.1, 100.)
92					.set_lower_limit(-0.5)
93					.set_upper_limit(900.),
94				{
95					let tree = Link::builder("Leg_[L1]_l1")
96						.add_visual(
97							Visual::builder(geom_leg_l1.clone())
98								.transformed(Transform::new_translation(0., 1.5, 0.))
99								.named("Leg_[L1]_l1_vis_1")
100								.materialized(material_l1.clone()),
101						)
102						.add_collider(
103							Collision::builder(geom_leg_l1.clone())
104								.transformed(Transform::new_translation(0., 1.5, 0.))
105								.named("Leg_[L1]_l1_col_1"),
106						)
107						.build_tree();
108
109					tree.get_root_link()
110						.try_write()
111						.unwrap()
112						.try_attach_child(
113							SmartJointBuilder::new_fixed("Leg_[L1]_j1")
114								.add_transform(Transform::new((0., 3., 0.), (0., 0., FRAC_PI_2))),
115							Link::builder("Leg_[L1]_l2")
116								.add_visual(
117									Visual::builder(geom_leg_l2.clone())
118										.transformed(Transform::new(
119											(0., 5., 0.),
120											(FRAC_PI_2, 0., 0.),
121										))
122										.named("Leg_[L1]_l2_vis_1")
123										.materialized(material_l2.clone()),
124								)
125								.add_collider(
126									Collision::builder(geom_leg_l2.clone())
127										.transformed(Transform::new(
128											(0., 5., 0.),
129											(FRAC_PI_2, 0., 0.),
130										))
131										.named("Leg_[L1]_l2_col_1"),
132								),
133						)
134						.unwrap();
135					tree.yank_link("Leg_[L1]_l1").unwrap()
136				},
137			)
138			.unwrap();
139
140		let left_leg_builder = left_leg_1_tree.yank_joint("Leg_[L1]_j0").unwrap();
141		let right_leg_builder_x = left_leg_builder.mirror(MirrorAxis::X);
142
143		assert_eq!(
144			right_leg_builder_x,
145			Chained(JointBuilder {
146				name: "Leg_[L1]_j0".into(),
147				joint_type: JointType::Revolute,
148				transform: JointTransformMode::Direct(Transform::new_translation(-1., 2., 3.)),
149				limit: Some(LimitData {
150					lower: Some(-0.5),
151					upper: Some(900.),
152					effort: 0.1,
153					velocity: 100.
154				}),
155				axis: Some((0., -1., 0.)),
156				child: Some(LinkBuilder {
157					name: "Leg_[L1]_l1".into(),
158					visuals: vec![VisualBuilder {
159						name: Some("Leg_[L1]_l1_vis_1".into()),
160						transform: Some(Transform {
161							translation: Some((0., 1.5, 0.)),
162							rotation: None
163						}),
164						geometry: BoxGeometry::new(2., 3., 1.).into(),
165						material_description: Some(material_l1.clone())
166					}],
167					colliders: vec![CollisionBuilder {
168						name: Some("Leg_[L1]_l1_col_1".into()),
169						transform: Some(Transform {
170							translation: Some((0., 1.5, 0.)),
171							rotation: None
172						}),
173						geometry: BoxGeometry::new(2., 3., 1.).into(),
174					}],
175					joints: vec![JointBuilder {
176						name: "Leg_[L1]_j1".into(),
177						joint_type: JointType::Fixed,
178						transform: JointTransformMode::Direct(Transform {
179							translation: Some((0., 3., 0.)),
180							rotation: Some((0., 0., FRAC_PI_2))
181						}),
182						child: Some(LinkBuilder {
183							name: "Leg_[L1]_l2".into(),
184							visuals: vec![VisualBuilder {
185								name: Some("Leg_[L1]_l2_vis_1".into()),
186								transform: Some(Transform {
187									translation: Some((0., -5., 0.)),
188									rotation: Some((FRAC_PI_2, 0., 0.))
189								}),
190								geometry: CylinderGeometry::new(1., 10.).into(),
191								material_description: Some(material_l2.clone())
192							}],
193							colliders: vec![CollisionBuilder {
194								name: Some("Leg_[L1]_l2_col_1".into()),
195								transform: Some(Transform {
196									translation: Some((0., -5., 0.)),
197									rotation: Some((FRAC_PI_2, 0., 0.))
198								}),
199								geometry: CylinderGeometry::new(1., 10.).into(),
200							}],
201							..Default::default()
202						}),
203						..Default::default()
204					},],
205					..Default::default()
206				}),
207				..Default::default()
208			})
209		);
210
211		assert_eq!(left_leg_builder, right_leg_builder_x.mirror(MirrorAxis::X));
212
213		let right_leg_builder_y = left_leg_builder.mirror(MirrorAxis::Y);
214
215		assert_eq!(
216			right_leg_builder_y,
217			Chained(JointBuilder {
218				name: "Leg_[L1]_j0".into(),
219				joint_type: JointType::Revolute,
220				transform: JointTransformMode::Direct(Transform::new_translation(1., -2., 3.)),
221				limit: Some(LimitData {
222					lower: Some(-0.5),
223					upper: Some(900.),
224					effort: 0.1,
225					velocity: 100.
226				}),
227				axis: Some((0., 1., 0.)),
228				child: Some(LinkBuilder {
229					name: "Leg_[L1]_l1".into(),
230					visuals: vec![VisualBuilder {
231						name: Some("Leg_[L1]_l1_vis_1".into()),
232						transform: Some(Transform {
233							translation: Some((0., -1.5, 0.)),
234							rotation: None
235						}),
236						geometry: BoxGeometry::new(2., 3., 1.).into(),
237						material_description: Some(material_l1.clone())
238					}],
239					colliders: vec![CollisionBuilder {
240						name: Some("Leg_[L1]_l1_col_1".into()),
241						transform: Some(Transform {
242							translation: Some((0., -1.5, 0.)),
243							rotation: None
244						}),
245						geometry: BoxGeometry::new(2., 3., 1.).into(),
246					}],
247					joints: vec![JointBuilder {
248						name: "Leg_[L1]_j1".into(),
249						joint_type: JointType::Fixed,
250						transform: JointTransformMode::Direct(Transform {
251							translation: Some((0., -3., 0.)),
252							rotation: Some((0., 0., FRAC_PI_2))
253						}),
254						child: Some(LinkBuilder {
255							name: "Leg_[L1]_l2".into(),
256							visuals: vec![VisualBuilder {
257								name: Some("Leg_[L1]_l2_vis_1".into()),
258								transform: Some(Transform {
259									translation: Some((0., 5., 0.)),
260									rotation: Some((FRAC_PI_2, 0., 0.))
261								}),
262								geometry: CylinderGeometry::new(1., 10.).into(),
263								material_description: Some(material_l2.clone())
264							}],
265							colliders: vec![CollisionBuilder {
266								name: Some("Leg_[L1]_l2_col_1".into()),
267								transform: Some(Transform {
268									translation: Some((0., 5., 0.)),
269									rotation: Some((FRAC_PI_2, 0., 0.))
270								}),
271								geometry: CylinderGeometry::new(1., 10.).into(),
272							}],
273							..Default::default()
274						}),
275						..Default::default()
276					},],
277					..Default::default()
278				}),
279				..Default::default()
280			})
281		);
282
283		assert_eq!(left_leg_builder, right_leg_builder_y.mirror(MirrorAxis::Y));
284
285		let right_leg_builder_z = left_leg_builder.mirror(MirrorAxis::Z);
286
287		assert_eq!(
288			right_leg_builder_z,
289			Chained(JointBuilder {
290				name: "Leg_[L1]_j0".into(),
291				joint_type: JointType::Revolute,
292				transform: JointTransformMode::Direct(Transform::new_translation(1., 2., -3.)),
293				limit: Some(LimitData {
294					lower: Some(-0.5),
295					upper: Some(900.),
296					effort: 0.1,
297					velocity: 100.
298				}),
299				axis: Some((0., -1., 0.)),
300				child: Some(LinkBuilder {
301					name: "Leg_[L1]_l1".into(),
302					visuals: vec![VisualBuilder {
303						name: Some("Leg_[L1]_l1_vis_1".into()),
304						transform: Some(Transform {
305							translation: Some((0., 1.5, 0.)),
306							rotation: None
307						}),
308						geometry: BoxGeometry::new(2., 3., 1.).into(),
309						material_description: Some(material_l1.clone())
310					}],
311					colliders: vec![CollisionBuilder {
312						name: Some("Leg_[L1]_l1_col_1".into()),
313						transform: Some(Transform {
314							translation: Some((0., 1.5, 0.)),
315							rotation: None
316						}),
317						geometry: BoxGeometry::new(2., 3., 1.).into(),
318					}],
319					joints: vec![JointBuilder {
320						name: "Leg_[L1]_j1".into(),
321						joint_type: JointType::Fixed,
322						transform: JointTransformMode::Direct(Transform {
323							translation: Some((0., 3., 0.)),
324							rotation: Some((0., 0., FRAC_PI_2))
325						}),
326						child: Some(LinkBuilder {
327							name: "Leg_[L1]_l2".into(),
328							visuals: vec![VisualBuilder {
329								name: Some("Leg_[L1]_l2_vis_1".into()),
330								transform: Some(Transform {
331									translation: Some((0., 5., 0.)),
332									rotation: Some((FRAC_PI_2, 0., 0.))
333								}),
334								geometry: CylinderGeometry::new(1., 10.).into(),
335								material_description: Some(material_l2.clone())
336							}],
337							colliders: vec![CollisionBuilder {
338								name: Some("Leg_[L1]_l2_col_1".into()),
339								transform: Some(Transform {
340									translation: Some((0., 5., 0.)),
341									rotation: Some((FRAC_PI_2, 0., 0.))
342								}),
343								geometry: CylinderGeometry::new(1., 10.).into(),
344							}],
345							..Default::default()
346						}),
347						..Default::default()
348					},],
349					..Default::default()
350				}),
351				..Default::default()
352			})
353		);
354
355		assert_eq!(left_leg_builder, right_leg_builder_z.mirror(MirrorAxis::Z));
356	}
357
358	// #[test]
359	// fn chained_escaping() {
360	// 	let tree = Link::builder("root-link").build_tree();
361
362	// 	tree.get_root_link()
363	// 		.try_write()
364	// 		.unwrap()
365	// 		.try_attach_child(
366	// 			Link::builder("child-link")
367	// 				.add_visual(Visual::builder(BoxGeometry::new(3., 4., 5.))),
368	// 			SmartJointBuilder::new_continuous("jointy"),
369	// 		)
370	// 		.unwrap();
371
372	// 	let mut builder = tree.yank_root();
373
374	// 	builder.add_visual(Visual::builder(BoxGeometry::new(2.,3.,4.)));
375	// }
376}