Fix line ends in q2d.urdf.
authorWalter Fetter Lages <w.fetter@ieee.org>
Mon, 20 Mar 2023 17:27:04 +0000 (14:27 -0300)
committerWalter Fetter Lages <w.fetter@ieee.org>
Mon, 20 Mar 2023 17:27:04 +0000 (14:27 -0300)
q2d_description/urdf/q2d.urdf

index a50ca36..88837c5 100644 (file)
-<?xml version="1.0"?>\r
-<robot name="q2d" xmlns:xacro="http://www.ros.org/wiki/xacro">\r
-\r
-       <xacro:arg name="ignition" default="false"/>\r
-       \r
-       <link name="world"/>\r
-       \r
-       <link name="origin_link"/>\r
-       \r
-       <joint name="world_joint" type="fixed">\r
-               <parent link="world"/>\r
-               <child link="origin_link"/>\r
-       </joint>\r
-\r
-       <link name="base_link">\r
-               <inertial>\r
-                       <origin xyz="0.074571214 -0.00008502114 0.039600060500000"/>\r
-                       <mass value="6.9621272394"/>\r
-                       <inertia ixx="0.12983348950453222" ixy="0.00004414079177225"\r
-                               ixz="-0.03019200341025967" iyy="0.17857934382693791"\r
-                               iyz="0.00000393635720902" izz="0.25812143874621400" />\r
-               </inertial>\r
-\r
-               <visual>\r
-                       <geometry>\r
-                               <mesh filename="package://q2d_description/meshes/base.STL"/>\r
-                       </geometry>\r
-                       <material name="base_material">\r
-                               <color rgba="0.55 0.45 0.45 1.0"/>\r
-                       </material>\r
-               </visual>\r
-\r
-               <collision>\r
-                       <geometry>\r
-                               <mesh filename="package://q2d_description/meshes/base.STL"/>\r
-                       </geometry>\r
-               </collision>\r
-       </link>\r
-\r
-       <joint name="origin_joint" type="fixed">\r
-               <parent link="origin_link"/>\r
-               <child link="base_link"/>\r
-       </joint>\r
-\r
-       <link name="shoulder_active_link">\r
-               <inertial>\r
-                       <origin xyz="0.0252456823 -0.00000002723 0.06470401873"/>\r
-                       <mass value="0.19730261508"/>\r
-                       <inertia ixx="0.00038685518702305" ixy="0.00000000055222416"\r
-                               ixz="-0.00000031340718614" iyy="0.00010241438913870"\r
-                               iyz="-0.00000000015426019" izz="0.00047879093657893" />\r
-               </inertial>\r
-\r
-               <visual>\r
-                       <geometry>\r
-                               <mesh filename="package://q2d_description/meshes/shoulder_active.STL"/>\r
-                       </geometry>\r
-                       <material name="shoulder_active_material">\r
-                               <color rgba="0.55 0.55 0.45 1.0"/>\r
-                       </material>\r
-               </visual>\r
-\r
-               <collision>\r
-                       <geometry>\r
-                               <mesh filename="package://q2d_description/meshes/collision/shoulder_active.STL"/>\r
-                       </geometry>\r
-               </collision>\r
-       </link>\r
-\r
-       <joint name="shoulder_active_joint" type="revolute">\r
-               <parent link="base_link"/>\r
-               <child link="shoulder_active_link"/>\r
-               <origin xyz="0 0 0.1477"/>\r
-               <axis xyz="0 0 1"/>\r
-               <limit lower="-1.570796326794897" upper="1.570796326794897"\r
-                       velocity="2.27" effort="27.94" />                       \r
-               <dynamics damping="29.7914" />\r
-       </joint>\r
-\r
-       <link name="shoulder_passive_link">\r
-               <inertial>\r
-                       <mass value="1.26475817816"/>\r
-                       <origin xyz="0.16516344805 -0.00048428845 -0.00016382412"/>\r
-                       <inertia ixx="0.00346199967740929" ixy="-0.00010902049981923"\r
-                               ixz="-0.00401182173261703" iyy="0.03314904030482527"\r
-                               iyz="0.00005087359051462" izz="0.03113579694057124" />\r
-               </inertial>\r
-\r
-               <visual>\r
-                       <geometry>\r
-                               <mesh filename="package://q2d_description/meshes/shoulder_passive.STL"/>\r
-                       </geometry>\r
-                       <material name="shoulder_passive_material">\r
-                               <color rgba="0.45 0.55 0.45 1.0"/>\r
-                       </material>\r
-               </visual>\r
-\r
-               <collision>\r
-                       <geometry>\r
-                               <mesh filename="package://q2d_description/meshes/collision/shoulder_passive.STL"/>\r
-                       </geometry>\r
-               </collision>\r
-       </link>\r
-\r
-       <joint name="shoulder_passive_joint" type="fixed">\r
-               <parent link="shoulder_active_link"/>\r
-               <child link="shoulder_passive_link"/>\r
-       </joint>\r
-\r
-       <link name="elbow_active_link">\r
-               <inertial>\r
-                       <mass value="0.19712951877"/>\r
-                       <origin xyz="0.02548273493 -0.00000002263 0.05254513577"/>\r
-                       <inertia ixx="0.00038850510800265" ixy="0.00000000052121416"\r
-                               ixz="0.00000404728675587" iyy="0.00010146693248154"\r
-                               iyz="0.00000000002789435" izz="0.00048091942023028" />\r
-               </inertial>\r
-\r
-               <visual>\r
-                       <geometry>\r
-                               <mesh filename="package://q2d_description/meshes/elbow_active.STL"/>\r
-                       </geometry>\r
-                       <material name="elbow_active_material">\r
-                               <color rgba="0.45 0.55 0.55 1.0"/>\r
-                       </material>\r
-               </visual>\r
-\r
-               <collision>\r
-                       <geometry>\r
-                               <mesh filename="package://q2d_description/meshes/collision/elbow_active.STL"/>\r
-                       </geometry>\r
-               </collision>\r
-       </link>\r
-\r
-       <joint name="elbow_active_joint" type="revolute">\r
-               <parent link="shoulder_passive_link"/>\r
-               <child link="elbow_active_link"/>\r
-               <origin xyz="0.343 0 0"/>\r
-               <axis xyz="0 0 1"/>\r
-               <limit lower="-1.570796326794897" upper="1.570796326794897"\r
-                       velocity="23.08" effort="13.62" />\r
-               <dynamics damping="2.6404" />\r
-       </joint>\r
-\r
-       <link name="elbow_passive_link">\r
-               <inertial>\r
-                       <mass value="0.67529215765"/>\r
-                       <origin xyz="0.06204831581 0.00000013809 0.01489882531"/>\r
-                       <inertia ixx="0.00132247071698947" ixy="-0.00000000605403474"\r
-                               ixz="-0.00090893541574333" iyy="0.00774007102253750"\r
-                               iyz="0.00000000624688369" izz="0.00751638349361413" />\r
-               </inertial>\r
-\r
-               <visual>\r
-                       <geometry>\r
-                               <mesh filename="package://q2d_description/meshes/elbow_passive.STL"/>\r
-                       </geometry>\r
-                       <material name="elbow_passive_material">\r
-                               <color rgba="0.45 0.45 0.55 1.0"/>\r
-                       </material>\r
-               </visual>\r
-\r
-               <collision>\r
-                       <geometry>\r
-                               <mesh filename="package://q2d_description/meshes/collision/elbow_passive.STL"/>\r
-                       </geometry>\r
-               </collision>\r
-       </link>\r
-\r
-       <joint name="elbow_passive_joint" type="fixed">\r
-               <parent link="elbow_active_link"/>\r
-               <child link="elbow_passive_link"/>\r
-       </joint>\r
-\r
-       <link name="tool_link"/>\r
-\r
-       <joint name="end_joint" type="fixed">\r
-               <parent link="elbow_passive_link"/>\r
-               <child link="tool_link"/>\r
-               <origin xyz="0.267 0 0"/>\r
-       </joint>\r
-\r
-       <transmission name="shoulder_active_transmission">\r
-               <type>transmission_interface/SimpleTransmission</type>\r
-               <joint name="shoulder_active_joint">\r
-                       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>\r
-               </joint>\r
-               <actuator name="shoulder_motor">\r
-                       <mechanicalReduction>1</mechanicalReduction>\r
-               </actuator>\r
-       </transmission>\r
-\r
-       <transmission name="elbow_active_transmission">\r
-               <type>transmission_interface/SimpleTransmission</type>\r
-               <joint name="elbow_active_joint">\r
-                       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>\r
-               </joint>\r
-               <actuator name="elbow_motor">\r
-                       <mechanicalReduction>1</mechanicalReduction>\r
-               </actuator>\r
-       </transmission>\r
-\r
+<?xml version="1.0"?>
+<robot name="q2d" xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+       <xacro:arg name="ignition" default="false"/>
+
+       <link name="world"/>
+
+       <link name="origin_link"/>
+
+       <joint name="world_joint" type="fixed">
+               <parent link="world"/>
+               <child link="origin_link"/>
+       </joint>
+
+       <link name="base_link">
+               <inertial>
+                       <origin xyz="0.074571214 -0.00008502114 0.039600060500000"/>
+                       <mass value="6.9621272394"/>
+                       <inertia ixx="0.12983348950453222" ixy="0.00004414079177225"
+                               ixz="-0.03019200341025967" iyy="0.17857934382693791"
+                               iyz="0.00000393635720902" izz="0.25812143874621400" />
+               </inertial>
+
+               <visual>
+                       <geometry>
+                               <mesh filename="package://q2d_description/meshes/base.STL"/>
+                       </geometry>
+                       <material name="base_material">
+                               <color rgba="0.55 0.45 0.45 1.0"/>
+                       </material>
+               </visual>
+
+               <collision>
+                       <geometry>
+                               <mesh filename="package://q2d_description/meshes/base.STL"/>
+                       </geometry>
+               </collision>
+       </link>
+
+       <joint name="origin_joint" type="fixed">
+               <parent link="origin_link"/>
+               <child link="base_link"/>
+       </joint>
+
+       <link name="shoulder_active_link">
+               <inertial>
+                       <origin xyz="0.0252456823 -0.00000002723 0.06470401873"/>
+                       <mass value="0.19730261508"/>
+                       <inertia ixx="0.00038685518702305" ixy="0.00000000055222416"
+                               ixz="-0.00000031340718614" iyy="0.00010241438913870"
+                               iyz="-0.00000000015426019" izz="0.00047879093657893" />
+               </inertial>
+
+               <visual>
+                       <geometry>
+                               <mesh filename="package://q2d_description/meshes/shoulder_active.STL"/>
+                       </geometry>
+                       <material name="shoulder_active_material">
+                               <color rgba="0.55 0.55 0.45 1.0"/>
+                       </material>
+               </visual>
+
+               <collision>
+                       <geometry>
+                               <mesh filename="package://q2d_description/meshes/collision/shoulder_active.STL"/>
+                       </geometry>
+               </collision>
+       </link>
+
+       <joint name="shoulder_active_joint" type="revolute">
+               <parent link="base_link"/>
+               <child link="shoulder_active_link"/>
+               <origin xyz="0 0 0.1477"/>
+               <axis xyz="0 0 1"/>
+               <limit lower="-1.570796326794897" upper="1.570796326794897"
+                       velocity="2.27" effort="27.94" />
+               <dynamics damping="29.7914" />
+       </joint>
+
+       <link name="shoulder_passive_link">
+               <inertial>
+                       <mass value="1.26475817816"/>
+                       <origin xyz="0.16516344805 -0.00048428845 -0.00016382412"/>
+                       <inertia ixx="0.00346199967740929" ixy="-0.00010902049981923"
+                               ixz="-0.00401182173261703" iyy="0.03314904030482527"
+                               iyz="0.00005087359051462" izz="0.03113579694057124" />
+               </inertial>
+
+               <visual>
+                       <geometry>
+                               <mesh filename="package://q2d_description/meshes/shoulder_passive.STL"/>
+                       </geometry>
+                       <material name="shoulder_passive_material">
+                               <color rgba="0.45 0.55 0.45 1.0"/>
+                       </material>
+               </visual>
+
+               <collision>
+                       <geometry>
+                               <mesh filename="package://q2d_description/meshes/collision/shoulder_passive.STL"/>
+                       </geometry>
+               </collision>
+       </link>
+
+       <joint name="shoulder_passive_joint" type="fixed">
+               <parent link="shoulder_active_link"/>
+               <child link="shoulder_passive_link"/>
+       </joint>
+
+       <link name="elbow_active_link">
+               <inertial>
+                       <mass value="0.19712951877"/>
+                       <origin xyz="0.02548273493 -0.00000002263 0.05254513577"/>
+                       <inertia ixx="0.00038850510800265" ixy="0.00000000052121416"
+                               ixz="0.00000404728675587" iyy="0.00010146693248154"
+                               iyz="0.00000000002789435" izz="0.00048091942023028" />
+               </inertial>
+
+               <visual>
+                       <geometry>
+                               <mesh filename="package://q2d_description/meshes/elbow_active.STL"/>
+                       </geometry>
+                       <material name="elbow_active_material">
+                               <color rgba="0.45 0.55 0.55 1.0"/>
+                       </material>
+               </visual>
+
+               <collision>
+                       <geometry>
+                               <mesh filename="package://q2d_description/meshes/collision/elbow_active.STL"/>
+                       </geometry>
+               </collision>
+       </link>
+
+       <joint name="elbow_active_joint" type="revolute">
+               <parent link="shoulder_passive_link"/>
+               <child link="elbow_active_link"/>
+               <origin xyz="0.343 0 0"/>
+               <axis xyz="0 0 1"/>
+               <limit lower="-1.570796326794897" upper="1.570796326794897"
+                       velocity="23.08" effort="13.62" />
+               <dynamics damping="2.6404" />
+       </joint>
+
+       <link name="elbow_passive_link">
+               <inertial>
+                       <mass value="0.67529215765"/>
+                       <origin xyz="0.06204831581 0.00000013809 0.01489882531"/>
+                       <inertia ixx="0.00132247071698947" ixy="-0.00000000605403474"
+                               ixz="-0.00090893541574333" iyy="0.00774007102253750"
+                               iyz="0.00000000624688369" izz="0.00751638349361413" />
+               </inertial>
+
+               <visual>
+                       <geometry>
+                               <mesh filename="package://q2d_description/meshes/elbow_passive.STL"/>
+                       </geometry>
+                       <material name="elbow_passive_material">
+                               <color rgba="0.45 0.45 0.55 1.0"/>
+                       </material>
+               </visual>
+
+               <collision>
+                       <geometry>
+                               <mesh filename="package://q2d_description/meshes/collision/elbow_passive.STL"/>
+                       </geometry>
+               </collision>
+       </link>
+
+       <joint name="elbow_passive_joint" type="fixed">
+               <parent link="elbow_active_link"/>
+               <child link="elbow_passive_link"/>
+       </joint>
+
+       <link name="tool_link"/>
+
+       <joint name="end_joint" type="fixed">
+               <parent link="elbow_passive_link"/>
+               <child link="tool_link"/>
+               <origin xyz="0.267 0 0"/>
+       </joint>
+
+       <transmission name="shoulder_active_transmission">
+               <type>transmission_interface/SimpleTransmission</type>
+               <joint name="shoulder_active_joint">
+                       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+               </joint>
+               <actuator name="shoulder_motor">
+                       <mechanicalReduction>1</mechanicalReduction>
+               </actuator>
+       </transmission>
+
+       <transmission name="elbow_active_transmission">
+               <type>transmission_interface/SimpleTransmission</type>
+               <joint name="elbow_active_joint">
+                       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+               </joint>
+               <actuator name="elbow_motor">
+                       <mechanicalReduction>1</mechanicalReduction>
+               </actuator>
+       </transmission>
+
        <gazebo reference="base_link">
                <visual>
                        <material>
                                <emissive>0.0 0.0 0.0 0.0</emissive>
                        </material>
                </visual>
-       </gazebo>\r
-\r
+       </gazebo>
+
        <gazebo reference="shoulder_active_link">
                <visual>
                        <material>
                                <emissive>0.0 0.0 0.0 0.0</emissive>
                        </material>
                </visual>
-       </gazebo>\r
-\r
+       </gazebo>
+
        <gazebo reference="shoulder_passive_link">
                <visual>
                        <material>
                        </material>
                </visual>
        </gazebo>
-\r
+
        <gazebo reference="elbow_active_link">
                <visual>
                        <material>
                                <emissive>0.0 0.0 0.0 0.0</emissive>
                        </material>
                </visual>
-       </gazebo>\r
-\r
+       </gazebo>
+
        <gazebo reference="elbow_passive_link">
                <visual>
                        <material>
                                <emissive>0.0 0.0 0.0 0.0</emissive>
                        </material>
                </visual>
-       </gazebo>\r
-\r
-       <ros2_control name="GazeboSystem" type="system">\r
-               <xacro:unless value="$(arg ignition)">\r
-                       <!-- Gazebo Classic -->\r
-                       <hardware>\r
-                               <plugin>gazebo_ros2_control/GazeboSystem</plugin>\r
-                       </hardware>\r
-               </xacro:unless>\r
-               <xacro:if value="$(arg ignition)">\r
-                       <!-- Gazebo Ignition -->\r
+       </gazebo>
+
+       <ros2_control name="GazeboSystem" type="system">
+               <xacro:unless value="$(arg ignition)">
+                       <!-- Gazebo Classic -->
+                       <hardware>
+                               <plugin>gazebo_ros2_control/GazeboSystem</plugin>
+                       </hardware>
+               </xacro:unless>
+               <xacro:if value="$(arg ignition)">
+                       <!-- Gazebo Ignition -->
                        <hardware>
                                <plugin>ign_ros2_control/IgnitionSystem</plugin>
-                       </hardware>\r
-               </xacro:if>\r
-               \r
-               <joint name="shoulder_active_joint">\r
-                       <command_interface name="effort">\r
-                               <param name="min">-27.94</param>\r
-                               <param name="max">27.94</param>\r
-                       </command_interface>\r
-                       <state_interface name="position"/>\r
-                       <state_interface name="velocity"/>\r
-                       <state_interface name="effort"/>\r
-               </joint>\r
-      \r
-               <joint name="elbow_active_joint">\r
-                       <command_interface name="effort">\r
-                               <param name="min">-13.62</param>\r
-                               <param name="max">13.62</param>\r
-                       </command_interface>\r
-                       <state_interface name="position"/>\r
-                       <state_interface name="velocity"/>\r
-                       <state_interface name="effort"/>\r
-               </joint>\r
-       </ros2_control>\r
-\r
-       <gazebo>\r
-               <xacro:unless value="$(arg ignition)">\r
-                       <!-- Gazebo Classic -->\r
-                       <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">\r
-                               <robot_param>robot_description</robot_param>\r
-                               <robot_param_node>robot_state_publisher</robot_param_node>\r
-                               <parameters>$(find q2d_description)/config/controller_manager.yaml</parameters>\r
-                       </plugin>\r
-               </xacro:unless>\r
-               <xacro:if value="$(arg ignition)">\r
+                       </hardware>
+               </xacro:if>
+
+               <joint name="shoulder_active_joint">
+                       <command_interface name="effort">
+                               <param name="min">-27.94</param>
+                               <param name="max">27.94</param>
+                       </command_interface>
+                       <state_interface name="position"/>
+                       <state_interface name="velocity"/>
+                       <state_interface name="effort"/>
+               </joint>
+
+               <joint name="elbow_active_joint">
+                       <command_interface name="effort">
+                               <param name="min">-13.62</param>
+                               <param name="max">13.62</param>
+                       </command_interface>
+                       <state_interface name="position"/>
+                       <state_interface name="velocity"/>
+                       <state_interface name="effort"/>
+               </joint>
+       </ros2_control>
+
+       <gazebo>
+               <xacro:unless value="$(arg ignition)">
+                       <!-- Gazebo Classic -->
+                       <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
+                               <robot_param>robot_description</robot_param>
+                               <robot_param_node>robot_state_publisher</robot_param_node>
+                               <parameters>$(find q2d_description)/config/controller_manager.yaml</parameters>
+                       </plugin>
+               </xacro:unless>
+               <xacro:if value="$(arg ignition)">
                        <!-- Gazebo Ignition -->
                        <plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin">
                                <robot_param>robot_description</robot_param>
                                <robot_param_node>robot_state_publisher</robot_param_node>
                                <parameters>$(find q2d_description)/config/controller_manager.yaml</parameters>
-                       </plugin>\r
+                       </plugin>
                </xacro:if>
        </gazebo>
-\r
-</robot>\r
+
+</robot>