<?xml version="1.0" encoding="utf-8"?> <!-- =================================================================================== --> <!-- | This document was autogenerated by xacro from last_mile_robot.xacro | --> <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> <!-- =================================================================================== --> <!-- Last Mile Delivery Robot - JKU --> <robot name="Last_Mile_Robot"> <material name="black"> <color rgba="0.0 0.0 0.0 1.0"/> </material> <material name="blue"> <color rgba="0.0 0.0 0.8 1.0"/> </material> <material name="green"> <color rgba="0.0 0.8 0.0 1.0"/> </material> <material name="gray"> <color rgba="0.7 0.7 0.7 1.0"/> </material> <material name="darkgray"> <color rgba="0.3 0.3 0.3 1.0"/> </material> <material name="red"> <color rgba="0.8 0.0 0.0 1.0"/> </material> <material name="brown"> <color rgba="0.59 0.29 0 1.0"/> </material> <material name="white"> <color rgba="1.0 1.0 1.0 1.0"/> </material> <material name="yellow"> <color rgba="0.8 0.8 0.0 1.0"/> </material> <!-- Colours --> <gazebo reference="chassis"> <material>Gazebo/Wood</material> </gazebo> <gazebo reference="front_right"> <material>Gazebo/Grey</material> </gazebo> <gazebo reference="front_left"> <material>Gazebo/Grey</material> </gazebo> <gazebo reference="rear_right"> <material>Gazebo/Grey</material> </gazebo> <gazebo reference="rear_left"> <material>Gazebo/Grey</material> </gazebo> <gazebo reference="front_right_ext"> <material>Gazebo/Grey</material> </gazebo> <gazebo reference="front_left_ext"> <material>Gazebo/Grey</material> </gazebo> <gazebo reference="rear_right_ext"> <material>Gazebo/Grey</material> </gazebo> <gazebo reference="rear_left_ext"> <material>Gazebo/Grey</material> </gazebo> <gazebo reference="front_right_ext2"> <material>Gazebo/Yellow</material> </gazebo> <gazebo reference="front_left_ext2"> <material>Gazebo/Yellow</material> </gazebo> <gazebo reference="rear_right_ext2"> <material>Gazebo/Yellow</material> </gazebo> <gazebo reference="rear_left_ext2"> <material>Gazebo/Yellow</material> </gazebo> <gazebo reference="front_right_wheel"> <material>Gazebo/FlatBlack</material> </gazebo> <gazebo reference="front_left_wheel"> <material>Gazebo/FlatBlack</material> </gazebo> <gazebo reference="rear_right_wheel"> <material>Gazebo/FlatBlack</material> </gazebo> <gazebo reference="rear_left_wheel"> <material>Gazebo/FlatBlack</material> </gazebo> <!-- Controllers --> <gazebo> <plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control"/> </gazebo> <gazebo> <plugin filename="libgazebo_ros_synchronous_drive.so" name="synchronous_drive_controller"> <rosDebugLevel>Debug</rosDebugLevel> <tfPrefix/> <velocityTopic>cmd_vel</velocityTopic> <odometryTopic>odom</odometryTopic> <odometryFrame>odom</odometryFrame> <robotBaseFrame>base_link</robotBaseFrame> <updateRate>20.0</updateRate> <wheelSeparation>1.237</wheelSeparation> <wheelDiameter>0.42</wheelDiameter> <wheelTorque>200</wheelTorque> <wheelAcceleration>200</wheelAcceleration> <publishWheelTF>true</publishWheelTF> <publishOdomTF>true</publishOdomTF> <publishWheelJointState>true</publishWheelJointState> <odometrySource>world</odometrySource> <!-- world or encoder --> <leftFrontJoint>front_left_wheel_hinge</leftFrontJoint> <rightFrontJoint>front_right_wheel_hinge</rightFrontJoint> <leftRearJoint>rear_left_wheel_hinge</leftRearJoint> <rightRearJoint>rear_right_wheel_hinge</rightRearJoint> <turnTorque>200</turnTorque> <leftFrontTurnJoint>front_left_hinge</leftFrontTurnJoint> <rightFrontTurnJoint>front_right_hinge</rightFrontTurnJoint> <leftRearTurnJoint>rear_left_hinge</leftRearTurnJoint> <rightRearTurnJoint>rear_right_hinge</rightRearTurnJoint> <publishTf>1</publishTf> </plugin> </gazebo> <link name="base_link"/> <link name="chassis"> <collision> <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/> <geometry> <box size=".65 .65 .05"/> </geometry> </collision> <visual> <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/> <geometry> <box size=".65 .65 .05"/> </geometry> <material name="brown"/> </visual> <inertial> <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/> <mass value="150"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="chassis_joint" type="fixed"> <origin xyz="0.0 0.0 0.75"/> <parent link="base_link"/> <child link="chassis"/> </joint> <!-- bis hier ists ok --> <link name="front_right"> <collision> <geometry> <cylinder length="0.55" radius="0.05"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.55" radius="0.05"/> </geometry> <material name="gray"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="front_right_hinge" type="continuous"> <!--continuous--> <parent link="chassis"/> <child link="front_right"/> <axis xyz="0 0 1"/> <origin rpy="0.0 0.0 0.0" xyz="0.325 -0.325 -0.30"/> <limit effort="0.1" velocity="0.1"/> </joint> <link name="front_left"> <collision> <geometry> <cylinder length="0.55" radius="0.05"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.55" radius="0.05"/> </geometry> <material name="gray"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="front_left_hinge" type="continuous"> <!--continuous--> <parent link="chassis"/> <child link="front_left"/> <axis xyz="0 0 1"/> <origin xyz="0.325 0.325 -0.30"/> <limit effort="0.1" velocity="0.1"/> </joint> <link name="rear_right"> <collision> <geometry> <cylinder length="0.55" radius="0.05"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.55" radius="0.05"/> </geometry> <material name="gray"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="rear_right_hinge" type="fixed"> <!--continuous--> <parent link="chassis"/> <child link="rear_right"/> <axis xyz="0 0 1"/> <origin xyz="-0.325 -0.325 -0.30"/> </joint> <link name="rear_left"> <collision> <geometry> <cylinder length="0.55" radius="0.05"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.55" radius="0.05"/> </geometry> <material name="gray"/> </visual> <inertial> <mass value="1"/> <inertia ixx="10.0" ixy="0.0" ixz="0.0" iyy="10.0" iyz="0.0" izz="10.0"/> </inertial> </link> <joint name="rear_left_hinge" type="fixed"> <!--continuous--> <parent link="chassis"/> <child link="rear_left"/> <axis xyz="0 0 1"/> <origin xyz="-0.325 0.325 -0.30"/> </joint> <link name="front_right_tilt"/> <joint name="front_right_tilt_joint" type="fixed"> <origin rpy="0.785398163397 1.57079632679 0.0" xyz="0.0 0.0 0.0"/> <parent link="front_right"/> <child link="front_right_tilt"/> </joint> <link name="front_right_ext"> <collision name="front_right_ext_collision"> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> <material name="gray"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="front_right_ext_hinge" type="fixed"> <origin rpy="0 -0.314159265359 0" xyz="0.0 0.0 0.225 "/> <parent link="front_right_tilt"/> <child link="front_right_ext"/> <axis xyz="0 0 0"/> </joint> <link name="front_right_tilt2"/> <joint name="front_right_tilt2_joint" type="fixed"> <origin rpy="0 -1.25663706144 0.0" xyz="0.0 0.0 0.2"/> <parent link="front_right_ext"/> <child link="front_right_tilt2"/> </joint> <link name="front_right_ext2"> <collision name="front_right_ext2_collision"> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> <material name="yellow"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="front_right_ext2_joint" type="fixed"> <origin rpy="0 0 0.785398163397" xyz="0.0 0.0 -0.16"/> <parent link="front_right_tilt2"/> <child link="front_right_ext2"/> <axis xyz="0 0 1"/> </joint> <link name="front_right_wheel"> <collision name="front_right_wheel_collision"> <geometry> <cylinder length="0.15" radius="0.21"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.15" radius="0.21"/> </geometry> <material name="black"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="front_right_wheel_hinge" type="continuous"> <origin rpy="1.57079632679 0 0" xyz="0 0.1 -0.2"/> <parent link="front_right_ext2"/> <child link="front_right_wheel"/> <axis xyz="0 0 1"/> </joint> <link name="front_left_tilt"/> <joint name="front_left_tilt_joint" type="fixed"> <origin rpy="-0.785398163397 1.57079632679 0.0" xyz="0.0 0.0 0.0"/> <parent link="front_left"/> <child link="front_left_tilt"/> </joint> <link name="front_left_ext"> <collision name="front_left_ext_collision"> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> <material name="gray"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="front_left_ext_hinge" type="fixed"> <origin rpy="0 -0.314159265359 0" xyz="0.0 0.0 0.225"/> <parent link="front_left_tilt"/> <child link="front_left_ext"/> <axis xyz="0 0 0"/> </joint> <link name="front_left_tilt2"/> <joint name="front_left_tilt2_joint" type="fixed"> <origin rpy="0 -1.25663706144 0.0" xyz="0.0 0.0 0.2"/> <parent link="front_left_ext"/> <child link="front_left_tilt2"/> </joint> <link name="front_left_ext2"> <collision name="front_left_ext2_collision"> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> <material name="yellow"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="front_left_ext2_joint" type="fixed"> <origin rpy="0 0 -0.785398163397" xyz="0.0 0.0 -0.16"/> <parent link="front_left_tilt2"/> <child link="front_left_ext2"/> <axis xyz="0 0 1"/> </joint> <link name="front_left_wheel"> <collision name="front_left_wheel_collision"> <geometry> <cylinder length="0.15" radius="0.21"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.15" radius="0.21"/> </geometry> <material name="black"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="front_left_wheel_hinge" type="continuous"> <origin rpy="1.57079632679 0 0" xyz="0 0.1 -0.2"/> <parent link="front_left_ext2"/> <child link="front_left_wheel"/> <axis xyz="0 0 1"/> </joint> <link name="rear_right_tilt"/> <joint name="rear_right_tilt_joint" type="fixed"> <origin rpy="2.35619449019 1.57079632679 0.0" xyz="0.0 0.0 0.0"/> <parent link="rear_right"/> <child link="rear_right_tilt"/> </joint> <link name="rear_right_ext"> <collision name="rear_right_ext_collision"> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> <material name="gray"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="rear_right_ext_hinge" type="fixed"> <origin rpy="0 -0.314159265359 0" xyz="0.0 0.0 0.225"/> <parent link="rear_right_tilt"/> <child link="rear_right_ext"/> <axis xyz="0 0 0"/> </joint> <link name="rear_right_tilt2"/> <joint name="rear_right_tilt2_joint" type="fixed"> <origin rpy="0 -1.25663706144 0.0" xyz="0.0 0.0 0.2"/> <parent link="rear_right_ext"/> <child link="rear_right_tilt2"/> </joint> <link name="rear_right_ext2"> <collision name="rear_right_ext2_collision"> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> <material name="yellow"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="rear_right_ext2_joint" type="fixed"> <origin rpy="0 0 2.35619449019" xyz="0.0 0.0 -0.16"/> <parent link="rear_right_tilt2"/> <child link="rear_right_ext2"/> <axis xyz="0 0 1"/> </joint> <link name="rear_right_wheel"> <collision name="rear_right_wheel_collision"> <geometry> <cylinder length="0.15" radius="0.21"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.15" radius="0.21"/> </geometry> <material name="black"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="rear_right_wheel_hinge" type="continuous"> <origin rpy="1.57079632679 0 0" xyz="0 0.1 -0.2"/> <parent link="rear_right_ext2"/> <child link="rear_right_wheel"/> <axis xyz="0 0 1"/> </joint> <link name="rear_left_tilt"/> <joint name="rear_left_tilt_joint" type="fixed"> <origin rpy="-2.35619449019 1.57079632679 0.0" xyz="0.0 0.0 0.0"/> <parent link="rear_left"/> <child link="rear_left_tilt"/> </joint> <link name="rear_left_ext"> <collision name="rear_left_ext_collision"> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> <material name="gray"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="rear_left_ext_hinge" type="fixed"> <origin rpy="0 -0.314159265359 0" xyz="0.0 0.0 0.225"/> <parent link="rear_left_tilt"/> <child link="rear_left_ext"/> <axis xyz="0 0 0"/> </joint> <link name="rear_left_tilt2"/> <joint name="rear_left_tilt2_joint" type="fixed"> <origin rpy="0 -1.25663706144 0.0" xyz="0.0 0.0 0.2"/> <parent link="rear_left_ext"/> <child link="rear_left_tilt2"/> </joint> <link name="rear_left_ext2"> <collision name="rear_left_ext2_collision"> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.4" radius="0.05"/> </geometry> <material name="yellow"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="rear_left_ext2_joint" type="fixed"> <origin rpy="0 0 -2.35619449019" xyz="0.0 0.0 -0.16"/> <parent link="rear_left_tilt2"/> <child link="rear_left_ext2"/> <axis xyz="0 0 1"/> </joint> <link name="rear_left_wheel"> <collision name="rear_left_wheel_collision"> <geometry> <cylinder length="0.15" radius="0.21"/> </geometry> </collision> <visual> <geometry> <cylinder length="0.15" radius="0.21"/> </geometry> <material name="black"/> </visual> <inertial> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </link> <joint name="rear_left_wheel_hinge" type="continuous"> <origin rpy="1.57079632679 0 0" xyz="0 0.1 -0.2"/> <parent link="rear_left_ext2"/> <child link="rear_left_wheel"/> <axis xyz="0 0 1"/> </joint> </robot>