robot_description_builder/chained/
chained_linkbuilder.rs

1use std::sync::Weak;
2
3use nalgebra::Matrix3;
4
5use super::{ChainableBuilder, Chained};
6use crate::{
7	cluster_objects::{kinematic_data_tree::KinematicDataTree, KinematicInterface},
8	joint::Joint,
9	link::{
10		builder::{BuildLink, LinkBuilder},
11		Link,
12	},
13	transform::{Mirror, MirrorAxis},
14	utils::{ArcLock, WeakLock},
15};
16
17impl Chained<LinkBuilder> {
18	/// TODO: More tests
19	/// TODO: DOC
20	pub fn mirror(&self, axis: MirrorAxis) -> Chained<LinkBuilder> {
21		let mirror_matrix: Matrix3<_> = axis.into();
22		Chained(self.0.mirrored(&mirror_matrix))
23	}
24}
25
26impl ChainableBuilder for LinkBuilder {
27	fn has_chain(&self) -> bool {
28		!self.joints.is_empty()
29	}
30}
31
32impl BuildLink for Chained<LinkBuilder> {
33	fn build(self, _tree: &Weak<KinematicDataTree>) -> ArcLock<Link> {
34		unimplemented!("build should not be able to be called?")
35	}
36
37	fn start_building_chain(self, tree: &Weak<KinematicDataTree>) -> ArcLock<Link> {
38		self.0.start_building_chain(tree)
39	}
40
41	fn build_chain(
42		self,
43		_tree: &Weak<KinematicDataTree>,
44		_parent_joint: &WeakLock<Joint>,
45	) -> ArcLock<Link> {
46		unimplemented!("build_chain should not be able to be called?")
47	}
48
49	fn get_shape_data(&self) -> crate::link::LinkShapeData {
50		unimplemented!("get_shape_data should not be able to be called?")
51	}
52}
53
54/// Since Link's can end a chain, a `LinkBuilder` can always be converted to a `Chained<LinkBuilder>`.
55impl From<LinkBuilder> for Chained<LinkBuilder> {
56	fn from(value: LinkBuilder) -> Self {
57		Self(value)
58	}
59}
60
61impl From<Chained<LinkBuilder>> for LinkBuilder {
62	fn from(value: Chained<LinkBuilder>) -> Self {
63		value.0
64	}
65}
66
67impl<KI> From<KI> for Chained<LinkBuilder>
68where
69	KI: KinematicInterface,
70{
71	fn from(value: KI) -> Self {
72		value.yank_root().unwrap() // This might not be Ok
73	}
74}
75
76#[cfg(test)]
77mod tests {
78	use std::f32::consts::FRAC_PI_2;
79
80	use test_log::test;
81
82	use crate::{
83		cluster_objects::KinematicInterface,
84		joint::JointTransformMode,
85		link::{
86			link_data::{
87				geometry::{BoxGeometry, CylinderGeometry},
88				Collision, Visual,
89			},
90			Link,
91		},
92		linkbuilding::{CollisionBuilder, LinkBuilder, VisualBuilder},
93		material::MaterialDescriptor,
94		transform::MirrorAxis,
95		Chained, JointBuilder, JointType, SmartJointBuilder, Transform,
96	};
97
98	#[test]
99	fn mirror_simple_1() {
100		let material_l1 = MaterialDescriptor::new_rgb(1., 0., 0.).named("Leg_l1");
101		let material_l2 = MaterialDescriptor::new_rgb(0., 1., 0.).named("Leg_l2");
102		let geom_leg_l1 = BoxGeometry::new(2., 3., 1.);
103		let geom_leg_l2 = CylinderGeometry::new(1., 10.);
104
105		let left_leg_1_tree = Link::builder("Leg_[L1]_l1")
106			.add_visual(
107				Visual::builder(geom_leg_l1.clone())
108					.transformed(Transform::new_translation(0., 1.5, 0.))
109					.named("Leg_[L1]_l1_vis_1")
110					.materialized(material_l1.clone()),
111			)
112			.add_collider(
113				Collision::builder(geom_leg_l1.clone())
114					.transformed(Transform::new_translation(0., 1.5, 0.))
115					.named("Leg_[L1]_l1_col_1"),
116			)
117			.build_tree();
118
119		left_leg_1_tree
120			.get_root_link()
121			.try_write()
122			.unwrap()
123			.try_attach_child(
124				SmartJointBuilder::new_fixed("Leg_[L1]_j1")
125					.add_transform(Transform::new((0., 3., 0.), (0., 0., FRAC_PI_2))),
126				Link::builder("Leg_[L1]_l2")
127					.add_visual(
128						Visual::builder(geom_leg_l2.clone())
129							.transformed(Transform::new((0., 5., 0.), (FRAC_PI_2, 0., 0.)))
130							.named("Leg_[L1]_l2_vis_1")
131							.materialized(material_l2.clone()),
132					)
133					.add_collider(
134						Collision::builder(geom_leg_l2.clone())
135							.transformed(Transform::new((0., 5., 0.), (FRAC_PI_2, 0., 0.)))
136							.named("Leg_[L1]_l2_col_1"),
137					),
138			)
139			.unwrap();
140
141		let left_leg_builder = left_leg_1_tree.yank_link("Leg_[L1]_l1").unwrap();
142		let right_leg_builder_x = left_leg_builder.mirror(MirrorAxis::X);
143
144		assert_eq!(
145			right_leg_builder_x,
146			Chained(LinkBuilder {
147				name: "Leg_[L1]_l1".into(),
148				visuals: vec![VisualBuilder {
149					name: Some("Leg_[L1]_l1_vis_1".into()),
150					transform: Some(Transform {
151						translation: Some((0., 1.5, 0.)),
152						rotation: None
153					}),
154					geometry: BoxGeometry::new(2., 3., 1.).into(),
155					material_description: Some(material_l1.clone())
156				}],
157				colliders: vec![CollisionBuilder {
158					name: Some("Leg_[L1]_l1_col_1".into()),
159					transform: Some(Transform {
160						translation: Some((0., 1.5, 0.)),
161						rotation: None
162					}),
163					geometry: BoxGeometry::new(2., 3., 1.).into(),
164				}],
165				joints: vec![JointBuilder {
166					name: "Leg_[L1]_j1".into(),
167					joint_type: JointType::Fixed,
168					transform: JointTransformMode::Direct(Transform {
169						translation: Some((0., 3., 0.)),
170						rotation: Some((0., 0., FRAC_PI_2))
171					}),
172					child: Some(LinkBuilder {
173						name: "Leg_[L1]_l2".into(),
174						visuals: vec![VisualBuilder {
175							name: Some("Leg_[L1]_l2_vis_1".into()),
176							transform: Some(Transform {
177								translation: Some((0., -5., 0.)),
178								rotation: Some((FRAC_PI_2, 0., 0.))
179							}),
180							geometry: CylinderGeometry::new(1., 10.).into(),
181							material_description: Some(material_l2.clone())
182						}],
183						colliders: vec![CollisionBuilder {
184							name: Some("Leg_[L1]_l2_col_1".into()),
185							transform: Some(Transform {
186								translation: Some((0., -5., 0.)),
187								rotation: Some((FRAC_PI_2, 0., 0.))
188							}),
189							geometry: CylinderGeometry::new(1., 10.).into(),
190						}],
191						..Default::default()
192					}),
193					..Default::default()
194				},],
195				..Default::default()
196			})
197		);
198
199		assert_eq!(left_leg_builder, right_leg_builder_x.mirror(MirrorAxis::X));
200
201		let right_leg_builder_y = left_leg_builder.mirror(MirrorAxis::Y);
202
203		assert_eq!(
204			right_leg_builder_y,
205			Chained(LinkBuilder {
206				name: "Leg_[L1]_l1".into(),
207				visuals: vec![VisualBuilder {
208					name: Some("Leg_[L1]_l1_vis_1".into()),
209					transform: Some(Transform {
210						translation: Some((0., -1.5, 0.)),
211						rotation: None
212					}),
213					geometry: BoxGeometry::new(2., 3., 1.).into(),
214					material_description: Some(material_l1.clone())
215				}],
216				colliders: vec![CollisionBuilder {
217					name: Some("Leg_[L1]_l1_col_1".into()),
218					transform: Some(Transform {
219						translation: Some((0., -1.5, 0.)),
220						rotation: None
221					}),
222					geometry: BoxGeometry::new(2., 3., 1.).into(),
223				}],
224				joints: vec![JointBuilder {
225					name: "Leg_[L1]_j1".into(),
226					joint_type: JointType::Fixed,
227					transform: JointTransformMode::Direct(Transform {
228						translation: Some((0., -3., 0.)),
229						rotation: Some((0., 0., FRAC_PI_2))
230					}),
231					child: Some(LinkBuilder {
232						name: "Leg_[L1]_l2".into(),
233						visuals: vec![VisualBuilder {
234							name: Some("Leg_[L1]_l2_vis_1".into()),
235							transform: Some(Transform {
236								translation: Some((0., 5., 0.)),
237								rotation: Some((FRAC_PI_2, 0., 0.))
238							}),
239							geometry: CylinderGeometry::new(1., 10.).into(),
240							material_description: Some(material_l2.clone())
241						}],
242						colliders: vec![CollisionBuilder {
243							name: Some("Leg_[L1]_l2_col_1".into()),
244							transform: Some(Transform {
245								translation: Some((0., 5., 0.)),
246								rotation: Some((FRAC_PI_2, 0., 0.))
247							}),
248							geometry: CylinderGeometry::new(1., 10.).into(),
249						}],
250						..Default::default()
251					}),
252					..Default::default()
253				},],
254				..Default::default()
255			})
256		);
257
258		assert_eq!(left_leg_builder, right_leg_builder_y.mirror(MirrorAxis::Y));
259
260		let right_leg_builder_z = left_leg_builder.mirror(MirrorAxis::Z);
261
262		assert_eq!(
263			right_leg_builder_z,
264			Chained(LinkBuilder {
265				name: "Leg_[L1]_l1".into(),
266				visuals: vec![VisualBuilder {
267					name: Some("Leg_[L1]_l1_vis_1".into()),
268					transform: Some(Transform {
269						translation: Some((0., 1.5, 0.)),
270						rotation: None
271					}),
272					geometry: BoxGeometry::new(2., 3., 1.).into(),
273					material_description: Some(material_l1.clone())
274				}],
275				colliders: vec![CollisionBuilder {
276					name: Some("Leg_[L1]_l1_col_1".into()),
277					transform: Some(Transform {
278						translation: Some((0., 1.5, 0.)),
279						rotation: None
280					}),
281					geometry: BoxGeometry::new(2., 3., 1.).into(),
282				}],
283				joints: vec![JointBuilder {
284					name: "Leg_[L1]_j1".into(),
285					joint_type: JointType::Fixed,
286					transform: JointTransformMode::Direct(Transform {
287						translation: Some((0., 3., 0.)),
288						rotation: Some((0., 0., FRAC_PI_2))
289					}),
290					child: Some(LinkBuilder {
291						name: "Leg_[L1]_l2".into(),
292						visuals: vec![VisualBuilder {
293							name: Some("Leg_[L1]_l2_vis_1".into()),
294							transform: Some(Transform {
295								translation: Some((0., 5., 0.)),
296								rotation: Some((FRAC_PI_2, 0., 0.))
297							}),
298							geometry: CylinderGeometry::new(1., 10.).into(),
299							material_description: Some(material_l2.clone())
300						}],
301						colliders: vec![CollisionBuilder {
302							name: Some("Leg_[L1]_l2_col_1".into()),
303							transform: Some(Transform {
304								translation: Some((0., 5., 0.)),
305								rotation: Some((FRAC_PI_2, 0., 0.))
306							}),
307							geometry: CylinderGeometry::new(1., 10.).into(),
308						}],
309						..Default::default()
310					}),
311					..Default::default()
312				},],
313				..Default::default()
314			})
315		);
316
317		assert_eq!(left_leg_builder, right_leg_builder_z.mirror(MirrorAxis::Z));
318	}
319}