123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201 |
- <?xml version="1.0" ?>
- <!-- =================================================================================== -->
- <!-- | This document was autogenerated by xacro from /home/michal/ros2_ws/src/rosbot_xl_description/urdf/rosbot_xl.urdf.xacro | -->
- <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
- <!-- =================================================================================== -->
- <robot name="rosbot_xl">
- <link name="base_link"/>
- <joint name="base_to_body_joint" type="fixed">
- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.048"/>
- <parent link="base_link"/>
- <child link="body_link"/>
- </joint>
- <link name="body_link">
- <visual>
- <geometry>
- <mesh filename="meshes/body.fbx" scale="1 1 1"/>
- </geometry>
- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
- </visual>
- <collision>
- <geometry>
- <mesh filename="meshes/body_colision.stl" scale="1 1 1"/>
- </geometry>
- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
- </collision>
- <inertial>
- <mass value="3.5"/>
- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0358"/>
- <inertia ixx="0.01393" ixy="-0.000020968097" ixz="0.000010399694" iyy="0.01081" iyz="0.000059372953" izz="0.02048"/>
- </inertial>
- </link>
- <joint name="body_to_cover_joint" type="fixed">
- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.08345"/>
- <parent link="body_link"/>
- <child link="cover_link"/>
- </joint>
- <link name="cover_link"/>
- <joint name="body_to_imu_joint" type="fixed">
- <origin rpy="3.14159 0.0 0.0" xyz="-0.1369 -0.0419 0.0370"/>
- <parent link="body_link"/>
- <child link="imu_link"/>
- </joint>
- <link name="imu_link"/>
- <joint name="fl_wheel_joint" type="continuous">
- <parent link="body_link"/>
- <child link="fl_wheel_link"/>
- <origin rpy="0.0 0.0 0.0" xyz="0.085 0.124 0.0"/>
- <axis xyz="0.0 1.0 0.0"/>
- <limit effort="1.27" velocity="21.0"/>
- <dynamics damping="0.001" friction="0.001"/>
- </joint>
- <link name="fl_wheel_link">
- <visual>
- <geometry>
- <mesh filename="meshes/wheel_b.dae" scale="1 1 1"/>
- </geometry>
- <origin rpy="0.0 0.0 3.141592653589793" xyz="0.0 0.0 0.0"/>
- </visual>
- <collision>
- <geometry>
- <cylinder length="0.036" radius="0.048"/>
- </geometry>
- <origin rpy="1.5707963267948966 0.0 0.0" xyz="0.0 0.0 0.0"/>
- </collision>
- <inertial>
- <mass value="0.051"/>
- <inertia ixx="5.0587413e-05" ixy="0.0" ixz="0.0" iyy="8.5933192e-05" iyz="0.0" izz="5.0587829e-05"/>
- </inertial>
- </link>
- <joint name="fr_wheel_joint" type="continuous">
- <parent link="body_link"/>
- <child link="fr_wheel_link"/>
- <origin rpy="0.0 0.0 0.0" xyz="0.085 -0.124 0.0"/>
- <axis xyz="0.0 1.0 0.0"/>
- <limit effort="1.27" velocity="21.0"/>
- <dynamics damping="0.001" friction="0.001"/>
- </joint>
- <link name="fr_wheel_link">
- <visual>
- <geometry>
- <mesh filename="meshes/wheel_a.dae" scale="1 1 1"/>
- </geometry>
- <origin rpy="0.0 0.0 3.141592653589793" xyz="0.0 0.0 0.0"/>
- </visual>
- <collision>
- <geometry>
- <cylinder length="0.036" radius="0.048"/>
- </geometry>
- <origin rpy="1.5707963267948966 0.0 0.0" xyz="0.0 0.0 0.0"/>
- </collision>
- <inertial>
- <mass value="0.051"/>
- <inertia ixx="5.0587413e-05" ixy="0.0" ixz="0.0" iyy="8.5933192e-05" iyz="0.0" izz="5.0587829e-05"/>
- </inertial>
- </link>
- <joint name="rl_wheel_joint" type="continuous">
- <parent link="body_link"/>
- <child link="rl_wheel_link"/>
- <origin rpy="0.0 0.0 0.0" xyz="-0.085 0.124 0.0"/>
- <axis xyz="0.0 1.0 0.0"/>
- <limit effort="1.27" velocity="21.0"/>
- <dynamics damping="0.001" friction="0.001"/>
- </joint>
- <link name="rl_wheel_link">
- <visual>
- <geometry>
- <mesh filename="meshes/wheel_a.dae" scale="1 1 1"/>
- </geometry>
- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
- </visual>
- <collision>
- <geometry>
- <cylinder length="0.036" radius="0.048"/>
- </geometry>
- <origin rpy="1.5707963267948966 0.0 0.0" xyz="0.0 0.0 0.0"/>
- </collision>
- <inertial>
- <mass value="0.051"/>
- <inertia ixx="5.0587413e-05" ixy="0.0" ixz="0.0" iyy="8.5933192e-05" iyz="0.0" izz="5.0587829e-05"/>
- </inertial>
- </link>
- <joint name="rr_wheel_joint" type="continuous">
- <parent link="body_link"/>
- <child link="rr_wheel_link"/>
- <origin rpy="0.0 0.0 0.0" xyz="-0.085 -0.124 0.0"/>
- <axis xyz="0.0 1.0 0.0"/>
- <limit effort="1.27" velocity="21.0"/>
- <dynamics damping="0.001" friction="0.001"/>
- </joint>
- <link name="rr_wheel_link">
- <visual>
- <geometry>
- <mesh filename="meshes/wheel_b.dae" scale="1 1 1"/>
- </geometry>
- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
- </visual>
- <collision>
- <geometry>
- <cylinder length="0.036" radius="0.048"/>
- </geometry>
- <origin rpy="1.5707963267948966 0.0 0.0" xyz="0.0 0.0 0.0"/>
- </collision>
- <inertial>
- <mass value="0.051"/>
- <inertia ixx="5.0587413e-05" ixy="0.0" ixz="0.0" iyy="8.5933192e-05" iyz="0.0" izz="5.0587829e-05"/>
- </inertial>
- </link>
- <ros2_control name="imu" type="sensor">
- <hardware>
- <plugin>rosbot_hardware_interfaces/RosbotImuSensor</plugin>
- <param name="connection_timeout_ms">120000</param>
- <param name="connection_check_period_ms">500</param>
- </hardware>
- <sensor name="imu">
- <state_interface name="orientation.x"/>
- <state_interface name="orientation.y"/>
- <state_interface name="orientation.z"/>
- <state_interface name="orientation.w"/>
- <state_interface name="angular_velocity.x"/>
- <state_interface name="angular_velocity.y"/>
- <state_interface name="angular_velocity.z"/>
- <state_interface name="linear_acceleration.x"/>
- <state_interface name="linear_acceleration.y"/>
- <state_interface name="linear_acceleration.z"/>
- </sensor>
- </ros2_control>
- <ros2_control name="wheels" type="system">
- <hardware>
- <plugin>rosbot_hardware_interfaces/RosbotSystem</plugin>
- <param name="connection_timeout_ms">120000</param>
- <param name="connection_check_period_ms">500</param>
- <!-- order of velocity commands to be published in motors_cmd Float32MultiArray msg -->
- <param name="velocity_command_joint_order">
- rr_wheel_joint,
- rl_wheel_joint,
- fr_wheel_joint,
- fl_wheel_joint
- </param>
- </hardware>
- <joint name="fl_wheel_joint">
- <command_interface name="velocity"/>
- <state_interface name="position"/>
- <state_interface name="velocity"/>
- </joint>
- <joint name="fr_wheel_joint">
- <command_interface name="velocity"/>
- <state_interface name="position"/>
- <state_interface name="velocity"/>
- </joint>
- <joint name="rl_wheel_joint">
- <command_interface name="velocity"/>
- <state_interface name="position"/>
- <state_interface name="velocity"/>
- </joint>
- <joint name="rr_wheel_joint">
- <command_interface name="velocity"/>
- <state_interface name="position"/>
- <state_interface name="velocity"/>
- </joint>
- </ros2_control>
- </robot>
|