1use super::chain::*;
20use super::joint::*;
21use super::link::*;
22use super::node::*;
23use na::{Isometry3, Matrix3, RealField};
24use nalgebra as na;
25use simba::scalar::SubsetOf;
26use std::collections::HashMap;
27use std::path::Path;
28use tracing::*;
29
30pub const ROOT_JOINT_NAME: &str = "root";
31
32impl<T> From<&urdf_rs::Color> for Color<T>
33where
34 T: RealField,
35{
36 fn from(urdf_color: &urdf_rs::Color) -> Self {
37 Color {
38 r: na::convert(urdf_color.rgba[0]),
39 g: na::convert(urdf_color.rgba[1]),
40 b: na::convert(urdf_color.rgba[2]),
41 a: na::convert(urdf_color.rgba[3]),
42 }
43 }
44}
45
46impl<T> From<urdf_rs::Color> for Color<T>
47where
48 T: RealField,
49{
50 fn from(urdf_color: urdf_rs::Color) -> Self {
51 (&urdf_color).into()
52 }
53}
54
55impl From<urdf_rs::Texture> for Texture {
56 fn from(urdf_texture: urdf_rs::Texture) -> Self {
57 Texture {
58 filename: urdf_texture.filename,
59 }
60 }
61}
62
63impl<T> From<urdf_rs::Material> for Material<T>
64where
65 T: RealField,
66{
67 fn from(urdf_material: urdf_rs::Material) -> Self {
68 Material {
69 name: urdf_material.name,
70 color: urdf_material.color.unwrap_or_default().into(),
71 texture: urdf_material.texture.unwrap_or_default().into(),
72 }
73 }
74}
75
76pub fn isometry_from<T: RealField>(origin_element: &urdf_rs::Pose) -> Isometry3<T> {
77 Isometry3::from_parts(
78 translation_from(&origin_element.xyz),
79 quaternion_from(&origin_element.rpy),
80 )
81}
82
83impl<T> From<urdf_rs::Inertial> for Inertial<T>
84where
85 T: RealField,
86{
87 fn from(urdf_inertial: urdf_rs::Inertial) -> Self {
88 let i = urdf_inertial.inertia;
89 Inertial::new(
90 isometry_from(&urdf_inertial.origin),
91 na::convert(urdf_inertial.mass.value),
92 Matrix3::new(
93 na::convert(i.ixx),
94 na::convert(i.ixy),
95 na::convert(i.ixz),
96 na::convert(i.ixy),
97 na::convert(i.iyy),
98 na::convert(i.iyz),
99 na::convert(i.ixz),
100 na::convert(i.iyz),
101 na::convert(i.izz),
102 ),
103 )
104 }
105}
106
107impl<T> From<urdf_rs::Visual> for Visual<T>
108where
109 T: RealField,
110{
111 fn from(urdf_visual: urdf_rs::Visual) -> Self {
112 Visual::new(
113 urdf_visual.name.unwrap_or_default(),
114 isometry_from(&urdf_visual.origin),
115 urdf_visual.geometry.into(),
116 urdf_visual.material.unwrap_or_default().into(),
117 )
118 }
119}
120
121impl<T> From<urdf_rs::Collision> for Collision<T>
122where
123 T: RealField,
124{
125 fn from(urdf_collision: urdf_rs::Collision) -> Self {
126 Collision::new(
127 urdf_collision.name.unwrap_or_default(),
128 isometry_from(&urdf_collision.origin),
129 urdf_collision.geometry.into(),
130 )
131 }
132}
133
134impl<T> From<urdf_rs::Geometry> for Geometry<T>
135where
136 T: RealField,
137{
138 fn from(urdf_geometry: urdf_rs::Geometry) -> Self {
139 match urdf_geometry {
140 urdf_rs::Geometry::Box { size } => Geometry::Box {
141 depth: na::convert(size[0]),
142 width: na::convert(size[1]),
143 height: na::convert(size[2]),
144 },
145 urdf_rs::Geometry::Cylinder { radius, length } => Geometry::Cylinder {
146 radius: na::convert(radius),
147 length: na::convert(length),
148 },
149 urdf_rs::Geometry::Capsule { radius, length } => Geometry::Capsule {
150 radius: na::convert(radius),
151 length: na::convert(length),
152 },
153 urdf_rs::Geometry::Sphere { radius } => Geometry::Sphere {
154 radius: na::convert(radius),
155 },
156 urdf_rs::Geometry::Mesh { filename, scale } => {
157 let scale = scale.unwrap_or(urdf_rs::Vec3(DEFAULT_MESH_SCALE));
158 Geometry::Mesh {
159 filename,
160 scale: na::Vector3::new(
161 na::convert(scale[0]),
162 na::convert(scale[1]),
163 na::convert(scale[2]),
164 ),
165 }
166 }
167 }
168 }
169}
170
171impl<T> From<urdf_rs::Link> for Link<T>
172where
173 T: RealField,
174{
175 fn from(urdf_link: urdf_rs::Link) -> Self {
176 Link {
177 name: urdf_link.name,
178 inertial: urdf_link.inertial.into(),
179 visuals: urdf_link.visual.into_iter().map(|v| v.into()).collect(),
180 collisions: urdf_link.collision.into_iter().map(|v| v.into()).collect(),
181 }
182 }
183}
184
185impl<T> From<&urdf_rs::Mimic> for Mimic<T>
186where
187 T: RealField,
188{
189 fn from(urdf_mimic: &urdf_rs::Mimic) -> Self {
190 Mimic::new(
191 na::convert(urdf_mimic.multiplier.unwrap_or(1.0)),
193 na::convert(urdf_mimic.offset.unwrap_or_default()),
194 )
195 }
196}
197
198fn axis_from<T>(array3: [f64; 3]) -> na::Unit<na::Vector3<T>>
200where
201 T: RealField,
202{
203 na::Unit::<_>::new_normalize(na::Vector3::new(
204 na::convert(array3[0]),
205 na::convert(array3[1]),
206 na::convert(array3[2]),
207 ))
208}
209
210pub fn quaternion_from<T>(array3: &[f64; 3]) -> na::UnitQuaternion<T>
212where
213 T: RealField,
214{
215 na::convert(na::UnitQuaternion::from_euler_angles(
216 array3[0], array3[1], array3[2],
217 ))
218}
219
220pub fn translation_from<T>(array3: &[f64; 3]) -> na::Translation3<T>
222where
223 T: RealField,
224{
225 na::convert(na::Translation3::new(array3[0], array3[1], array3[2]))
226}
227
228impl<T> From<&urdf_rs::Joint> for Joint<T>
229where
230 T: RealField + SubsetOf<f64>,
231{
232 fn from(joint: &urdf_rs::Joint) -> Joint<T> {
233 let limit = if (joint.limit.upper - joint.limit.lower) == 0.0 {
234 None
235 } else {
236 Some(Range::new(
237 na::convert(joint.limit.lower),
238 na::convert(joint.limit.upper),
239 ))
240 };
241 NodeBuilder::<T>::new()
242 .name(&joint.name)
243 .joint_type(match joint.joint_type {
244 urdf_rs::JointType::Revolute | urdf_rs::JointType::Continuous => {
245 JointType::Rotational {
246 axis: axis_from(*joint.axis.xyz),
247 }
248 }
249 urdf_rs::JointType::Prismatic => JointType::Linear {
250 axis: axis_from(*joint.axis.xyz),
251 },
252 _ => JointType::Fixed,
253 })
254 .limits(limit)
255 .rotation(quaternion_from(&joint.origin.rpy))
256 .translation(translation_from(&joint.origin.xyz))
257 .finalize()
258 }
259}
260
261impl<T> From<&urdf_rs::Robot> for Chain<T>
262where
263 T: RealField + SubsetOf<f64>,
264{
265 fn from(robot: &urdf_rs::Robot) -> Self {
266 let mut ref_nodes = Vec::new();
267 let mut child_link_name_to_node = HashMap::new();
268 let mut joint_name_to_node = HashMap::new();
269 let mut parent_link_name_to_node = HashMap::<&String, Vec<Node<T>>>::new();
270 let root_node = NodeBuilder::<T>::new().name(ROOT_JOINT_NAME).into_node();
271 for j in &robot.joints {
272 let node = Node::<T>::new(j.into());
273 child_link_name_to_node.insert(&j.child.link, node.clone());
274 if parent_link_name_to_node.contains_key(&j.parent.link) {
275 parent_link_name_to_node
276 .get_mut(&j.parent.link)
277 .unwrap()
278 .push(node.clone());
279 } else {
280 parent_link_name_to_node.insert(&j.parent.link, vec![node.clone()]);
281 }
282 ref_nodes.push(node.clone());
283 joint_name_to_node.insert(j.name.clone(), node);
284 }
285 for l in &robot.links {
286 info!("link={}", l.name);
287 if let Some(parent_node) = child_link_name_to_node.get_mut(&l.name) {
288 if let Some(child_nodes) = parent_link_name_to_node.get(&l.name) {
289 for child_node in child_nodes.iter() {
290 info!("set parent = {parent_node}, child = {child_node}");
291 child_node.set_parent(parent_node);
292 }
293 }
294 parent_node.set_link(Some(l.clone().into()));
295 } else {
296 info!("root={}", l.name);
297 root_node.set_link(Some(l.clone().into()));
298 }
299 }
300 for j in &robot.joints {
302 if let Some(mimic) = &j.mimic {
303 debug!("mimic found for {}", mimic.joint);
304 let child = joint_name_to_node[&j.name].clone();
305 let parent = joint_name_to_node
306 .get(&mimic.joint)
307 .unwrap_or_else(|| panic!("{} not found, mimic not found", &mimic.joint));
308 child.set_mimic_parent(parent, mimic.into());
309 }
310 }
311 let root_nodes = ref_nodes
313 .iter()
314 .filter(|ref_node| ref_node.parent().is_none());
315 for rjn in root_nodes {
316 info!("set parent = {root_node}, child = {rjn}");
317 rjn.set_parent(&root_node);
318 }
319 Chain::from_root(root_node)
320 }
321}
322
323impl<T> From<urdf_rs::Robot> for Chain<T>
324where
325 T: RealField + SubsetOf<f64>,
326{
327 fn from(robot: urdf_rs::Robot) -> Self {
328 Self::from(&robot)
329 }
330}
331
332impl<T> Chain<T>
333where
334 T: RealField + SubsetOf<f64>,
335{
336 pub fn from_urdf_file<P>(path: P) -> Result<Self, urdf_rs::UrdfError>
337 where
338 P: AsRef<Path>,
339 {
340 Ok(urdf_rs::utils::read_urdf_or_xacro(path)?.into())
341 }
342}
343
344pub fn link_to_joint_map(urdf_robot: &urdf_rs::Robot) -> HashMap<String, String> {
360 let mut map = HashMap::new();
361 for j in &urdf_robot.joints {
362 map.insert(j.child.link.to_owned(), j.name.to_owned());
363 }
364 for l in &urdf_robot.links {
365 if !map.contains_key(&l.name) {
366 map.insert(l.name.to_owned(), ROOT_JOINT_NAME.to_owned());
367 }
368 }
369 map
370}
371
372pub fn joint_to_link_map(urdf_robot: &urdf_rs::Robot) -> HashMap<String, String> {
373 let mut map = HashMap::new();
374 for j in &urdf_robot.joints {
375 map.insert(j.name.to_owned(), j.child.link.to_owned());
376 }
377 for l in &urdf_robot.links {
378 if !map.contains_key(&l.name) {
379 map.insert(ROOT_JOINT_NAME.to_owned(), l.name.to_owned());
380 }
381 }
382 map
383}
384
385const DEFAULT_MESH_SCALE: [f64; 3] = [1.0f64; 3];
387
388#[cfg(test)]
389mod tests {
390 use super::*;
391 #[cfg(target_family = "wasm")]
392 use wasm_bindgen_test::wasm_bindgen_test as test;
393
394 #[cfg(target_family = "wasm")]
395 wasm_bindgen_test::wasm_bindgen_test_configure!(run_in_browser);
396
397 #[test]
398 fn test_tree() {
399 let robot = urdf_rs::read_from_string(include_str!("../urdf/sample.urdf")).unwrap();
400 assert_eq!(robot.name, "robot");
401 assert_eq!(robot.links.len(), 1 + 6 + 6);
402
403 let tree = Chain::<f32>::from(&robot);
404 assert_eq!(tree.iter().count(), 13);
405 }
406
407 #[test]
408 fn test_tree_from_file() {
409 #[cfg(not(target_family = "wasm"))]
410 let tree = Chain::<f32>::from_urdf_file("urdf/sample.urdf").unwrap();
411 #[cfg(target_family = "wasm")]
412 let tree = Chain::<f32>::from(
413 urdf_rs::read_from_string(include_str!("../urdf/sample.urdf")).unwrap(),
414 );
415 assert_eq!(tree.dof(), 12);
416 let names = tree
417 .iter()
418 .map(|joint| joint.joint().name.clone())
419 .collect::<Vec<_>>();
420 assert_eq!(names.len(), 13);
421 println!("{}", names[0]);
422 assert_eq!(names[0], "root");
423 assert_eq!(names[1], "l_shoulder_yaw");
424 }
425}