Skip to main content

dynamics_parse/
urdf.rs

1//! Parser for the URDF (Unified Robot Description Format) file format.
2//!
3//! ## Overview
4//! This module provides functionality to parse URDF files and build corresponding [`Model`] and [`GeometryModel`] objects.
5//! The parser is implemented from scratch, and does not rely on any existing URDF parsing library.
6//! Is uses `roxmltree` for XML parsing, the extraction of parameters being done manually.
7//!
8//! ## Joints
9//! The following joint types are supported:
10//! - Fixed
11//! - Revolute
12//! - Continuous
13//! - Prismatic
14//!
15//! ## Meshes
16//! The parser supports mesh geometries in any format. The visualizers used might have limitations on the supported formats.
17//! Mesh paths can be resolved in three ways:
18//! - using absolute paths;
19//! - using ROS's `package://` (or `package:///`) syntax, as long as the package name is present in the environment variable `ROS_PACKAGE_PATH`;
20//! - using a user-provided package directory, passed as an argument to the parsing function.
21//!
22//! ## Tested models
23//! The parser has been tested at least on all models from [example-robot-data](https://github.com/Gepetto/example-robot-data/).
24//! However, some URDF features are still missing, hence some other models might not be parsed correctly yet.
25
26#![allow(clippy::too_many_arguments)] // TODO: refactor functions
27
28use crate::errors::ParseError;
29use collider_rs::mesh::Mesh;
30use collider_rs::shape::Cuboid;
31use collider_rs::shape::{Cylinder, ShapeWrapper, Sphere};
32use dynamics_inertia::inertia::Inertia;
33use dynamics_joint::continuous::JointModelContinuous;
34use dynamics_joint::joint::JointWrapper;
35use dynamics_joint::prismatic::JointModelPrismatic;
36use dynamics_joint::revolute::JointModelRevolute;
37use dynamics_model::frame::{Frame, FrameType};
38use dynamics_model::model::Model;
39use dynamics_model::{
40    geometry_model::GeometryModel, geometry_object::GeometryObject, model::WORLD_ID,
41};
42use dynamics_spatial::color::Color;
43use dynamics_spatial::motion::SpatialRotation;
44use dynamics_spatial::se3::SE3;
45use dynamics_spatial::symmetric3::Symmetric3;
46use dynamics_spatial::vector3d::Vector3D;
47use nalgebra::Vector3;
48use roxmltree::{Document, Node};
49use std::collections::HashSet;
50use std::path::Path;
51use std::{collections::HashMap, fs, str::FromStr};
52
53#[derive(Debug, Clone, Copy, PartialEq, Eq)]
54/// Type of geometry being parsed.
55enum GeometryType {
56    Collision,
57    Visual,
58}
59
60/// Parses a URDF file and builds the corresponding [`Model`] and [`GeometryModel`].
61///
62/// # Arguments
63///
64/// * `filepath` - The path to the URDF file.
65/// * `package_dir` - The path to the folder containing the mesh files referenced in the URDF.
66///
67/// # Returns
68///
69/// A 3-tuple containing the [`Model`], a collision [`GeometryModel`], and a visualization [`GeometryModel`] objects if successful.
70///
71/// Returns a [`ParseError`] if there is an error during parsing.
72pub fn build_models_from_urdf(
73    filepath: &str,
74    package_dir: Option<&str>,
75) -> Result<(Model, GeometryModel, GeometryModel), ParseError> {
76    let contents =
77        fs::read_to_string(filepath).map_err(|e| ParseError::IoError(e, filepath.to_string()))?;
78    let doc = Document::parse(&contents).map_err(ParseError::XmlError)?;
79
80    // identify the robot node
81    let robot_node = doc
82        .descendants()
83        .find(|n| n.tag_name().name() == "robot")
84        .ok_or(ParseError::NoRobotTag)?;
85    let robot_name = robot_node.attribute("name").unwrap_or("").to_string();
86
87    // elements will sequentially be added to the models
88    let mut model = Model::new(robot_name);
89    let mut coll_model = GeometryModel::new();
90    let mut viz_model = GeometryModel::new();
91
92    // start by parsing materials at the root
93    let mut materials = parse_root_materials(&robot_node)?;
94
95    // find root nodes (links without parents)
96    let root_nodes = find_root_nodes(&robot_node)?;
97
98    // sort root nodes in alphabetical order
99    let mut root_nodes: Vec<Node> = root_nodes.into_iter().collect();
100    root_nodes.sort_by_key(|n| n.attribute("name").unwrap_or(""));
101
102    // recursively parse from the root nodes
103    for node in root_nodes {
104        parse_node(
105            &robot_node,
106            node,
107            &robot_node,
108            WORLD_ID,
109            true,
110            &mut model,
111            &mut coll_model,
112            &mut viz_model,
113            &mut materials,
114            package_dir,
115        )?;
116    }
117
118    Ok((model, coll_model, viz_model))
119}
120
121/// Parse the given node and call itself recursively on its children.
122///
123/// The steps are:
124/// - Depending on the type of node (link or joint), call the corresponding parse function.
125/// - Find all children nodes (joints for links, child links for joints).
126/// - Sort the children nodes in alphabetical order.
127/// - Recursively call `parse_node` on each child node.
128///
129/// # Arguments:
130/// - `robot_node`: The root robot node containing all links and joints.
131/// - `node`: The current node to parse.
132/// - `parent_node`: The parent node of the current node.
133/// - `parent_joint_id`: The ID of the parent joint in the model.
134/// - `is_root`: Whether the current node is a root node.
135/// - `model`: The model being built.
136/// - `coll_model`: The collision geometry model being built.
137/// - `viz_model`: The visualization geometry model being built.
138/// - `materials`: The map of materials defined in the robot.
139/// - `package_dir`: The path to the folder containing the mesh files referenced in the URDF.
140///
141/// # Returns:
142/// - `Result<(), ParseError>`: `Ok` if successful, or a [`ParseError`] if an error occurs.
143fn parse_node(
144    robot_node: &Node,
145    node: Node,
146    parent_node: &Node,
147    parent_joint_id: usize,
148    is_root: bool,
149    model: &mut Model,
150    coll_model: &mut GeometryModel,
151    viz_model: &mut GeometryModel,
152    materials: &mut HashMap<String, Color>,
153    package_dir: Option<&str>,
154) -> Result<(), ParseError> {
155    let node_name = node.attribute("name").unwrap_or("");
156    let mut new_parent_joint_id = parent_joint_id;
157
158    // parse the current node and extract its children
159    let children = match node.tag_name().name() {
160        "link" => {
161            parse_link(
162                robot_node,
163                node,
164                parent_node,
165                parent_joint_id,
166                is_root,
167                model,
168                coll_model,
169                viz_model,
170                materials,
171                package_dir,
172            )?;
173
174            // find all joints that have this link as parent
175            let mut children = Vec::new();
176
177            for joint_node in robot_node.children().filter(|n| n.has_tag_name("joint")) {
178                // if this joint:
179                // - has a parent tag
180                // - which is a link
181                // - and this link matches the current node name
182                if let Some(parent_node) = joint_node.children().find(|n| n.has_tag_name("parent"))
183                    && let Ok(parent_link_name) = extract_parameter::<String>("link", &parent_node)
184                    && parent_link_name == node_name
185                {
186                    // then add this joint node to the children to be parsed next
187                    children.push(joint_node);
188                }
189            }
190            children
191        }
192
193        // parse joints
194        "joint" => {
195            new_parent_joint_id =
196                parse_joint(robot_node, node, parent_node, parent_joint_id, model)?;
197
198            // add the eventual child link to the children to be parsed next
199            if let Some(child_node) = node.children().find(|n| n.has_tag_name("child")) {
200                // find the name of the child link
201                let child_link_name = extract_parameter::<String>("link", &child_node)?;
202
203                // find the link node in the robot node
204                if let Some(link_node) = robot_node.children().find(|n| {
205                    n.has_tag_name("link") && n.attribute("name").unwrap_or("") == child_link_name
206                }) {
207                    vec![link_node]
208                } else {
209                    // child link not found in the robot description
210                    return Err(ParseError::UnknownLinkName(child_link_name));
211                }
212            } else {
213                vec![]
214            }
215        }
216
217        // we ignore empty lines and tags not used in simulation
218        "" | "gazebo" | "transmission" => {
219            vec![]
220        }
221
222        // unknown tag
223        _ => {
224            return Err(ParseError::UnknownTag(node.tag_name().name().to_string()));
225        }
226    };
227
228    // sort the children in alphabetical order
229    let mut children: Vec<Node> = children.into_iter().collect();
230    children.sort_by_key(|n| n.attribute("name").unwrap_or(""));
231
232    // recursively parse children
233    for child_node in children {
234        parse_node(
235            robot_node,
236            child_node,
237            &node,
238            new_parent_joint_id,
239            false,
240            model,
241            coll_model,
242            viz_model,
243            materials,
244            package_dir,
245        )?;
246    }
247    Ok(())
248}
249
250/// Finds the root nodes (links without parents) in the robot node.
251///
252/// It starts by collecting all link nodes, then removes those that are children of joints.
253///
254/// # Arguments:
255/// - `robot_node`: The root robot node containing all links and joints.
256///
257/// # Returns:
258/// - `Result<HashSet<Node>, ParseError>`: A set of root link nodes if successful, or a [`ParseError`] if an error occurs.
259fn find_root_nodes<'a>(robot_node: &'a Node) -> Result<HashSet<Node<'a, 'a>>, ParseError> {
260    // collect all link nodes
261    let mut parent_links: HashSet<Node> = robot_node
262        .children()
263        .filter(|n| n.has_tag_name("link"))
264        .collect();
265
266    // remove all links that are children of joints
267    for joint_node in robot_node.children().filter(|n| n.has_tag_name("joint")) {
268        // find the parent link
269        if let Some(child_node) = joint_node.children().find(|n| n.has_tag_name("child")) {
270            let child_link_name = extract_parameter::<String>("link", &child_node)?;
271            // remove the parent link from the set
272            parent_links.retain(|link_node| {
273                let link_name = link_node.attribute("name").unwrap_or("");
274                link_name != child_link_name
275            });
276        }
277    }
278
279    Ok(parent_links)
280}
281
282/// Parses a joint from the URDF file and adds it to the model.
283///
284/// It extracts the joint name, type, origin, axis, and limits, and creates the corresponding joint model.
285/// If the joint is fixed, no joint model is created, only a fixed frame is added.
286/// In any case, a frame (of type either fixed or joint) is added for the joint.
287///
288/// # Arguments:
289/// - `robot_node`: The root robot node containing all links and joints.
290/// - `joint_node`: The joint node to parse.
291/// - `parent_node`: The parent node of the joint.
292/// - `parent_joint_id`: The ID of the parent joint in the model.
293/// - `model`: The model being built.
294///
295/// # Returns:
296/// - `Result<usize, ParseError>`: The ID of the newly added joint if successful, or a [`ParseError`] if an error occurs.
297fn parse_joint(
298    robot_node: &Node,
299    joint_node: Node,
300    parent_node: &Node,
301    parent_joint_id: usize,
302    model: &mut Model,
303) -> Result<usize, ParseError> {
304    // extract the name and type of joint
305    let joint_name = joint_node
306        .attribute("name")
307        .ok_or(ParseError::NameMissing(format!("{joint_node:#?}")))?
308        .to_string();
309    let joint_type = joint_node
310        .attribute("type")
311        .ok_or(ParseError::MissingParameter("type".to_string()))?;
312
313    // get the parent frame
314    let parent_frame_id = get_parent_frame(parent_node, robot_node, model)?;
315    let parent_frame = &model.frames[parent_frame_id];
316
317    // compute the placement of the joint
318    let link_origin = parse_origin(&joint_node)?;
319    let placement = parent_frame.placement * link_origin;
320
321    let new_joint_id = match joint_type {
322        // if the joint is fixed, we create a fixed frame
323        "fixed" => {
324            let frame = Frame::new(
325                joint_name.clone(),
326                parent_joint_id,
327                parent_frame_id,
328                placement,
329                FrameType::Fixed,
330                Inertia::zeros(),
331            );
332            let _ = model.add_frame(frame, false);
333
334            // we return the parent joint id as there is no new joint
335            Ok(parent_joint_id)
336        }
337
338        // if the joint is continuous, we create a revolute joint without limits
339        "continuous" => {
340            let axis = parse_axis(joint_node)?;
341            let mut joint_model = JointModelContinuous::new(axis);
342
343            // we extract the limit of the joint
344            if let Some(limit_node) = joint_node.children().find(|n| n.has_tag_name("limit")) {
345                let effort = extract_parameter::<f64>("effort", &limit_node)?;
346                joint_model.limits.effort[0] = effort;
347
348                let velocity = extract_parameter::<f64>("velocity", &limit_node)?;
349                joint_model.limits.velocity[0] = velocity;
350            }
351
352            model.add_joint(
353                parent_joint_id,
354                JointWrapper::continuous(joint_model),
355                placement,
356                joint_name.clone(),
357            )
358        }
359
360        // if the joint is revolute, we create a revolute joint
361        "revolute" => {
362            let axis = parse_axis(joint_node)?;
363
364            // we extract the limit of the joint
365            let limit_node = joint_node
366                .children()
367                .find(|n| n.has_tag_name("limit"))
368                .ok_or(ParseError::MissingParameter("limit".to_string()))?;
369
370            // TODO: extract dynamics (damping, ...)
371
372            let mut joint_model = JointModelRevolute::new(axis);
373
374            // optional parameters
375            if let Ok(lower) = extract_parameter::<f64>("lower", &limit_node) {
376                joint_model.limits.min_configuration[0] = lower;
377            }
378            if let Ok(upper) = extract_parameter::<f64>("upper", &limit_node) {
379                joint_model.limits.max_configuration[0] = upper;
380            }
381
382            // required parameters
383            let effort = extract_parameter::<f64>("effort", &limit_node)?;
384            joint_model.limits.effort[0] = effort;
385
386            let velocity = extract_parameter::<f64>("velocity", &limit_node)?;
387            joint_model.limits.velocity[0] = velocity;
388
389            model.add_joint(
390                parent_joint_id,
391                JointWrapper::revolute(joint_model),
392                placement,
393                joint_name.clone(),
394            )
395        }
396
397        "prismatic" => {
398            let axis = parse_axis(joint_node)?;
399
400            // we extract the limit of the joint
401            let limit_node = joint_node
402                .children()
403                .find(|n| n.has_tag_name("limit"))
404                .ok_or(ParseError::MissingParameter("limit".to_string()))?;
405
406            // TODO: extract dynamics (damping, ...)
407
408            let mut joint_model = JointModelPrismatic::new(axis);
409
410            // optional parameters
411            if let Ok(lower) = extract_parameter::<f64>("lower", &limit_node) {
412                joint_model.limits.min_configuration[0] = lower;
413            }
414            if let Ok(upper) = extract_parameter::<f64>("upper", &limit_node) {
415                joint_model.limits.max_configuration[0] = upper;
416            }
417
418            // required parameters
419            let effort = extract_parameter::<f64>("effort", &limit_node)?;
420            joint_model.limits.effort[0] = effort;
421
422            let velocity = extract_parameter::<f64>("velocity", &limit_node)?;
423            joint_model.limits.velocity[0] = velocity;
424
425            model.add_joint(
426                parent_joint_id,
427                JointWrapper::prismatic(joint_model),
428                placement,
429                joint_name.clone(),
430            )
431        }
432
433        _ => return Err(ParseError::UnknownJointType(joint_type.to_string())),
434    }
435    .map_err(ParseError::ModelError)?;
436
437    // if the joint is not fixed, we also add a frame
438    if joint_type != "fixed" {
439        let frame = Frame::new(
440            joint_name,
441            new_joint_id,
442            parent_frame_id,
443            SE3::identity(),
444            FrameType::Joint,
445            Inertia::zeros(),
446        );
447        model
448            .add_frame(frame, true)
449            .map_err(ParseError::ModelError)?;
450    }
451
452    Ok(new_joint_id)
453}
454
455/// Parses an axis defined in the URDF file, given a joint node.
456///
457/// # Arguments:
458/// - `joint_node`: The joint node containing the axis definition.
459///
460/// # Returns:
461/// - `Result<Vector3D, ParseError>`: The parsed axis as a `Vector3D` if successful, or a [`ParseError`] if an error occurs.
462fn parse_axis(joint_node: Node) -> Result<Vector3D, ParseError> {
463    if let Some(axis_node) = joint_node.children().find(|n| n.has_tag_name("axis")) {
464        let axis_values = extract_parameter_list::<f64>("xyz", &axis_node, Some(3))?;
465        Ok(Vector3D::new(
466            axis_values[0],
467            axis_values[1],
468            axis_values[2],
469        ))
470    } else {
471        // default axis if not specified
472        Ok(Vector3D::new(1.0, 0.0, 0.0))
473    }
474}
475
476/// Parses all materials defined at the root of the robot node.
477///
478/// # Arguments:
479/// - `robot_node`: The root robot node containing material definitions.
480///
481/// # Returns:
482/// - A map from material names to their corresponding `Color` objects if successful, or a [`ParseError`] if an error occurs.
483fn parse_root_materials(robot_node: &Node) -> Result<HashMap<String, Color>, ParseError> {
484    let mut materials = HashMap::new();
485    for material_node in robot_node.children().filter(|n| n.has_tag_name("material")) {
486        parse_material(material_node, &mut materials)?;
487    }
488    Ok(materials)
489}
490
491/// Parses a link node.
492///
493/// This functions extracts the link's inertia, adds a frame for the link, and parses its collision and visual geometries.
494/// The geometries are added to the provided collision and visualization geometry models.
495/// To each link is associated exactly one frame in the model.
496///
497/// # Arguments:
498/// - `robot_node`: The root robot node containing all links and joints.
499/// - `node`: The link node to parse.
500/// - `parent_node`: The XML parent node of the link.
501/// - `parent_joint_id`: The ID of the parent joint in the model.
502/// - `is_root`: Whether the link is a root link.
503/// - `model`: The model being built.
504/// - `coll_model`: The collision geometry model being built.
505/// - `viz_model`: The visualization geometry model being built.
506/// - `materials`: The map of materials defined in the robot.
507/// - `package_dir`: The path to the folder containing the mesh files referenced in the URDF.
508///
509/// # Returns:
510/// - `Result<(), ParseError>`: `Ok` if successful, or a [`ParseError`] if an error occurs.
511fn parse_link(
512    robot_node: &Node,
513    node: Node,
514    parent_node: &Node,
515    parent_joint_id: usize,
516    is_root: bool,
517    model: &mut Model,
518    coll_model: &mut GeometryModel,
519    viz_model: &mut GeometryModel,
520    materials: &mut HashMap<String, Color>,
521    package_dir: Option<&str>,
522) -> Result<(), ParseError> {
523    let link_name = node.attribute("name").unwrap_or("").to_string();
524    let parent_frame_id = get_parent_frame(parent_node, robot_node, model)?;
525
526    // parse the inertial node
527    let link_inertia = parse_inertia(node, &link_name)?;
528
529    // inertia associated with the new frame
530    // if this is the root link, we put the inertia in the frame
531    // otherwise, we associate the inertia to the joint (in model.inertias)
532    let frame_inertia = if is_root {
533        link_inertia
534    }
535    // if the parent joint type is fixed, we put the inertia in the parent's frame
536    else {
537        if let Some(parent_joint_type) = parent_node.attribute("type")
538            && parent_joint_type == "fixed"
539        {
540            model.frames[parent_frame_id].inertia += &link_inertia;
541        }
542        model
543            .append_body_to_joint(
544                parent_joint_id,
545                &link_inertia,
546                model.frames[parent_frame_id].placement,
547            )
548            .map_err(ParseError::ModelError)?;
549        Inertia::zeros()
550    };
551
552    // compute the placement of the link frame
553    let parent_frame = &model.frames[parent_frame_id];
554    let link_placement = parent_frame.placement * parse_origin(&node)?;
555
556    // add a frame for the link
557    let frame = Frame::new(
558        link_name.clone(),
559        parent_joint_id,
560        parent_frame_id,
561        link_placement,
562        FrameType::Body,
563        frame_inertia,
564    );
565    let new_frame_id = model
566        .add_frame(frame, true)
567        .map_err(ParseError::ModelError)?;
568
569    // parse the collision node
570    for (i, collision_node) in node
571        .children()
572        .filter(|n| n.has_tag_name("collision"))
573        .enumerate()
574    {
575        let geom_obj = parse_geometry(
576            format!("{link_name}_{i}"),
577            &collision_node,
578            parent_joint_id,
579            new_frame_id,
580            model,
581            materials,
582            package_dir,
583            GeometryType::Collision,
584        )?;
585        coll_model.add_geometry_object(geom_obj);
586    }
587
588    // parse the visual node
589    for (i, visual_node) in node
590        .children()
591        .filter(|n| n.has_tag_name("visual"))
592        .enumerate()
593    {
594        let geom_obj = parse_geometry(
595            format!("{link_name}_{i}"),
596            &visual_node,
597            parent_joint_id,
598            new_frame_id,
599            model,
600            materials,
601            package_dir,
602            GeometryType::Visual,
603        )?;
604        viz_model.add_geometry_object(geom_obj);
605    }
606
607    Ok(())
608}
609
610/// Retrieves the parent frame index from the parent node.
611fn get_parent_frame(
612    parent_node: &Node,
613    robot_node: &Node,
614    model: &Model,
615) -> Result<usize, ParseError> {
616    // extract the name of the parent link
617    let parent_name = parent_node
618        .attribute("name")
619        .ok_or(ParseError::NameMissing(format!("{parent_node:#?}")))?;
620    let robot_name = robot_node
621        .attribute("name")
622        .ok_or(ParseError::NameMissing(format!("{robot_node:#?}")))?;
623
624    // check if the parent is the world frame
625    if parent_name == robot_name {
626        Ok(WORLD_ID)
627    }
628    // else, retrieve the frame id from the model
629    else {
630        // compute the type of the parent node
631        let parent_type = parent_node.attribute("type").unwrap_or("");
632        let frame_type = match parent_type {
633            "fixed" => FrameType::Fixed,
634            "revolute" | "continuous" | "prismatic" => FrameType::Joint,
635            _ => FrameType::Body,
636        };
637        model
638            .get_frame_id(parent_name, Some(&frame_type))
639            .ok_or(ParseError::UnknownParent(parent_name.to_string()))
640    }
641}
642
643/// Parses a material from the URDF file.
644///
645/// # Arguments:
646/// - `node`: The material node to parse.
647/// - `materials`: The map of materials to update.
648///
649/// # Returns:
650/// - If successful, updates the `materials` map with the parsed material.
651/// - Otherwise, returns a [`ParseError`].
652fn parse_material(node: Node, materials: &mut HashMap<String, Color>) -> Result<(), ParseError> {
653    // extract name
654    let material_name = node
655        .attribute("name")
656        .ok_or(ParseError::NameMissing(format!("{node:#?}")))?
657        .to_string();
658
659    // extract and convert color
660    let color_node = node
661        .children()
662        .find(|n| n.has_tag_name("color"))
663        .ok_or(ParseError::MaterialWithoutColor(material_name.clone()))?;
664    let rgba = extract_parameter_list::<f64>("rgba", &color_node, Some(4))?;
665    let color = Color::new(rgba[0], rgba[1], rgba[2], rgba[3]);
666
667    // TODO: handle texture
668
669    materials.insert(material_name, color);
670    Ok(())
671}
672
673/// Parses the inertia of a link from the URDF file.
674///
675/// # Arguments:
676/// - `node`: The link node to parse.
677/// - `link_name`: The name of the link (for error reporting).
678///
679/// # Returns:
680/// - The parsed [`Inertia`] if successful.
681/// - A [`ParseError`] if an error occurs.
682fn parse_inertia(node: Node, link_name: &str) -> Result<Inertia, ParseError> {
683    if let Some(inertial_node) = node.children().find(|n| n.has_tag_name("inertial")) {
684        let mass_node = inertial_node
685            .children()
686            .find(|n| n.has_tag_name("mass"))
687            .ok_or(ParseError::InertialWithoutMass(link_name.to_string()))?;
688        let mass = extract_parameter::<f64>("value", &mass_node)?;
689
690        let inertia_node = inertial_node
691            .children()
692            .find(|n| n.has_tag_name("inertia"))
693            .ok_or(ParseError::InertialWithoutInertia(link_name.to_string()))?;
694
695        let ixx = extract_parameter::<f64>("ixx", &inertia_node)?;
696        let ixy = extract_parameter::<f64>("ixy", &inertia_node)?;
697        let ixz = extract_parameter::<f64>("ixz", &inertia_node)?;
698        let iyy = extract_parameter::<f64>("iyy", &inertia_node)?;
699        let iyz = extract_parameter::<f64>("iyz", &inertia_node)?;
700        let izz = extract_parameter::<f64>("izz", &inertia_node)?;
701        let inertia_mat = Symmetric3::new(ixx, iyy, izz, ixy, ixz, iyz);
702
703        let inertial_origin = if let Some(origin_node) =
704            inertial_node.children().find(|n| n.has_tag_name("origin"))
705        {
706            // extract rpy and xyz (default to zeros if not specified)
707            let rpy =
708                extract_parameter_list::<f64>("rpy", &origin_node, Some(3)).unwrap_or(vec![0.0; 3]);
709            let xyz =
710                extract_parameter_list::<f64>("xyz", &origin_node, Some(3)).unwrap_or(vec![0.0; 3]);
711
712            // construct the rotation and translation
713            let rotation = SpatialRotation::from_euler_angles(rpy[0], rpy[1], rpy[2]);
714            let translation = Vector3D::new(xyz[0], xyz[1], xyz[2]);
715
716            SE3::from_parts(translation, rotation)
717        } else {
718            // defaults to identity if no origin is specified
719            SE3::identity()
720        };
721
722        Ok(Inertia::new(
723            mass,
724            inertial_origin.translation(),
725            inertia_mat.rotate(&inertial_origin.rotation()),
726        ))
727    } else {
728        Ok(Inertia::zeros())
729    }
730}
731
732/// Parses the geometry of a link from the URDF file.
733/// Extracts the geometry shape and its parameters.
734///
735/// # Arguments:
736/// - `link_name`: The name of the link (for error reporting).
737/// - `node`: The geometry node to parse.
738/// - `parent_joint_id`: The ID of the parent joint in the model.
739/// - `parent_frame_id`: The ID of the parent frame in the model.
740/// - `model`: The model being built.
741/// - `materials`: The map of materials defined in the robot.
742/// - `package_dir`: The path to the folder containing the mesh files referenced in the URDF.
743/// - `geometry_type`: The type of geometry being parsed (collision or visual).
744///
745/// # Returns:
746/// - The parsed [`GeometryObject`] if successful.
747/// - A [`ParseError`] if an error occurs.
748fn parse_geometry(
749    link_name: String,
750    node: &Node,
751    parent_joint_id: usize,
752    parent_frame_id: usize,
753    model: &Model,
754    materials: &mut HashMap<String, Color>,
755    package_dir: Option<&str>,
756    geometry_type: GeometryType,
757) -> Result<GeometryObject, ParseError> {
758    let geometry_node = node
759        .children()
760        .find(|n| n.has_tag_name("geometry"))
761        .ok_or(ParseError::VisualWithoutGeometry(link_name.clone()))?;
762
763    // extract the shape from the geometry node
764    let shape: ShapeWrapper = if let Some(shape_node) =
765        geometry_node.children().find(|n| n.has_tag_name("box"))
766    {
767        let size = extract_parameter_list::<f32>("size", &shape_node, Some(3))?;
768        let half_extents = Vector3::new(size[0] / 2.0, size[1] / 2.0, size[2] / 2.0);
769        Box::new(Cuboid::new(half_extents))
770    } else if let Some(shape_node) = geometry_node
771        .children()
772        .find(|n| n.has_tag_name("cylinder"))
773    {
774        let radius = extract_parameter::<f32>("radius", &shape_node)?;
775        let length = extract_parameter::<f32>("length", &shape_node)?;
776        Box::new(Cylinder::new(radius, length / 2.0))
777    } else if let Some(shape_node) = geometry_node.children().find(|n| n.has_tag_name("sphere")) {
778        let radius = extract_parameter::<f32>("radius", &shape_node)?;
779        Box::new(Sphere::new(radius))
780    } else if let Some(mesh_node) = geometry_node.children().find(|n| n.has_tag_name("mesh")) {
781        let filename = mesh_node
782            .attribute("filename")
783            .ok_or(ParseError::MissingParameter("filename".to_string()))?;
784
785        let absolute_path = if let Some(filename) = filename.strip_prefix("package://") {
786            // if the filename starts with "package:///", we remove the first slash
787            let filename = filename.strip_prefix('/').unwrap_or(filename);
788
789            // retrieve the package path in between "package://" and the first "/"
790            let path_parts: Vec<&str> = filename.splitn(2, '/').collect();
791            if path_parts.len() != 2 {
792                return Err(ParseError::InvalidFilePath(format!(
793                    "Invalid package path: {filename}"
794                )));
795            }
796            let package_name = path_parts[0];
797            let relative_path = path_parts[1];
798
799            // retrieve the package path from the 'ROS_PACKAGE_PATH' environment variable
800            let ros_package_path = std::env::var("ROS_PACKAGE_PATH").map_err(|_| ParseError::InvalidFilePath(
801                "'package://' was used but the ROS_PACKAGE_PATH environment variable is not set".to_string(),
802            ))?;
803            let package_paths: Vec<&str> = ros_package_path
804                .split(':')
805                .filter(|s| !s.is_empty())
806                .collect();
807
808            // search for the package in the package paths
809            let mut package_path = None;
810            for path in package_paths {
811                // extract the last folder name in the path
812                let path_obj = Path::new(path);
813
814                // check if the folder name matches the package name
815                if let Some(folder_name) = path_obj.file_name().and_then(|s| s.to_str())
816                    && folder_name == package_name
817                {
818                    package_path = Some(path_obj.to_path_buf());
819                    break;
820                }
821            }
822
823            let package_path = package_path.ok_or(ParseError::InvalidFilePath(format!(
824                "Package '{package_name}' not found in ROS_PACKAGE_PATH",
825            )))?;
826
827            // construct the absolute path with the mesh relative path
828            package_path
829                .join(relative_path)
830                .to_str()
831                .ok_or(ParseError::InvalidFilePath(format!(
832                    "Invalide path: {}",
833                    package_path.join(relative_path).display()
834                )))?
835                .to_string()
836        } else if filename.starts_with('/') {
837            filename.to_string()
838        } else {
839            // treat path as relative path from package_dir
840            let package_dir = package_dir.ok_or(ParseError::InvalidFilePath(
841                "'package_dir' must be provided to resolve mesh file paths".to_string(),
842            ))?;
843            let package_dir = Path::new(package_dir);
844            package_dir
845                .join(filename)
846                .to_str()
847                .ok_or(ParseError::InvalidFilePath(format!(
848                    "Invalide path: {}",
849                    package_dir.join(filename).display()
850                )))?
851                .to_string()
852        };
853
854        // check if the file exists
855        if !std::path::Path::new(&absolute_path).exists() {
856            return Err(ParseError::InvalidFilePath(format!(
857                "Mesh file does not exist: {absolute_path}"
858            )));
859        }
860
861        Box::new(Mesh::new(absolute_path))
862    } else {
863        return Err(ParseError::GeometryWithoutShape(link_name.clone()));
864    };
865
866    // extract the origin from the visual node
867    let parent_frame = &model.frames[parent_frame_id];
868    let placement = parent_frame.placement * parse_origin(node)?;
869
870    // extract the material color
871    let mut color = Color::new(0.9, 0.9, 0.9, 1.0);
872    if geometry_type != GeometryType::Visual {
873        // default color for collision geometries (see above)
874    }
875    // if there is a material node
876    else if let Some(material_node) = node.children().find(|n| n.has_tag_name("material")) {
877        // if this material node has a name
878        // and this material was already defined in the robot node
879        if let Some(material_name) = material_node.attribute("name")
880            && let Some(material_color) = materials.get(material_name)
881        {
882            color = *material_color;
883        }
884        // else, check if it has a color node
885        else if let Some(color_node) = material_node.children().find(|n| n.has_tag_name("color"))
886            && let Ok(rgba) = extract_parameter_list::<f64>("rgba", &color_node, Some(4))
887        {
888            color = Color::new(rgba[0], rgba[1], rgba[2], rgba[3]);
889
890            // if the material has a name, we add it to the materials map
891            if let Some(material_name) = material_node.attribute("name")
892                && !material_name.is_empty()
893            {
894                materials.insert(material_name.to_string(), color);
895            }
896        }
897    }
898
899    let geom_obj = GeometryObject::new(
900        link_name,
901        parent_joint_id,
902        parent_frame_id,
903        shape,
904        color,
905        placement,
906    );
907    Ok(geom_obj)
908}
909
910/// Extracts a parameter from the XML node with the given name and converts it to the specified type.
911/// Returns an error if the parameter is missing or cannot be parsed.
912fn extract_parameter<T: FromStr>(name: &str, node: &roxmltree::Node) -> Result<T, ParseError> {
913    node.attribute(name)
914        .ok_or_else(|| ParseError::MissingParameter(name.to_string()))?
915        .parse::<T>()
916        .map_err(|_| ParseError::InvalidParameter(name.to_string()))
917}
918
919/// Extracts a list of parameters from the XML node with the given name and converts them to the specified type.
920/// Returns an error if the parameter is missing or any value cannot be parsed.
921fn extract_parameter_list<T: FromStr>(
922    name: &str,
923    node: &roxmltree::Node,
924    expected_length: Option<usize>,
925) -> Result<Vec<T>, ParseError> {
926    let vector = node
927        .attribute(name)
928        .ok_or_else(|| ParseError::MissingParameter(name.to_string()))?
929        .split_whitespace()
930        .map(|s| {
931            s.parse::<T>()
932                .map_err(|_| ParseError::InvalidParameter(name.to_string()))
933        })
934        .collect::<Result<Vec<T>, ParseError>>()?;
935    if let Some(expected_length) = expected_length
936        && vector.len() != expected_length
937    {
938        return Err(ParseError::InvalidParameter(name.to_string()));
939    }
940    Ok(vector)
941}
942
943fn parse_origin(node: &roxmltree::Node) -> Result<SE3, ParseError> {
944    let isometry = if let Some(origin_node) = node.children().find(|n| n.has_tag_name("origin")) {
945        let xyz = extract_parameter_list::<f64>("xyz", &origin_node, Some(3))?;
946        let rotation = match extract_parameter_list::<f64>("rpy", &origin_node, Some(3)) {
947            Ok(rpy) => SpatialRotation::from_euler_angles(rpy[0], rpy[1], rpy[2]),
948            Err(ParseError::MissingParameter(_)) => SpatialRotation::identity(),
949            Err(e) => return Err(e),
950        };
951        let translation = Vector3D::new(xyz[0], xyz[1], xyz[2]);
952
953        SE3::from_parts(translation, rotation)
954    } else {
955        SE3::identity()
956    };
957    Ok(isometry)
958}