Function urdf_rs::read_from_string

source ·
pub fn read_from_string(string: &str) -> Result<Robot>
Expand description

Read from string instead of file.

§Examples

let s = r#"
    <robot name="robot">
        <link name="shoulder1">
            <inertial>
                <origin xyz="0 0 0.5" rpy="0 0 0"/>
                <mass value="1"/>
                <inertia ixx="100"  ixy="0"  ixz="0" iyy="100" iyz="0" izz="100" />
            </inertial>
            <visual>
                <origin xyz="0.1 0.2 0.3" rpy="-0.1 -0.2  -0.3" />
                <geometry>
                    <box size="1.0 2.0 3.0" />
                </geometry>
                <material name="Cyan">
                    <color rgba="0 1.0 1.0 1.0"/>
                </material>
            </visual>
            <collision>
                <origin xyz="0 0 0" rpy="0 0 0"/>
                <geometry>
                    <cylinder radius="1" length="0.5"/>
                </geometry>
            </collision>
        </link>
        <link name="elbow1" />
        <link name="wrist1" />
        <joint name="shoulder_pitch" type="revolute">
            <origin xyz="0.0 0.0 0.1" />
            <parent link="shoulder1" />
            <child link="elbow1" />
            <axis xyz="0 1 -1" />
            <limit lower="-1" upper="1.0" effort="0" velocity="1.0"/>
        </joint>
        <joint name="shoulder_pitch" type="revolute">
            <origin xyz="0.0 0.0 0.0" />
            <parent link="elbow1" />
            <child link="wrist1" />
            <axis xyz="0 1 0" />
            <limit lower="-2" upper="1.0" effort="0" velocity="1.0"/>
        </joint>
    </robot>
   "#;
let urdf_robot = urdf_rs::read_from_string(s).unwrap();
println!("{:?}", urdf_robot.links[0].visual[0].origin.xyz);