Hi all, I built my custom 4wheeler and after spawning it in gazebo, everything worked out just fine. I then decided to bring it alive by including a diff_drive controller. At this point, it all goes wrong. When I spawn the robot, in Gazebo it looks okay. But in RVIZ, there's a complaint about missing transforms between the base_footprint and the rest of the robot. As you can see from the TF diagram attached, the base_footprint link has been displaced by a new connection between the odom frame and the base_link frame. See my Robot URDF bellow
<?xml version = "1.0"?>
<robot name="Rover" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="wheel_thickness" value="0.12"/> <xacro:property name="wheel_diameter" value="0.22"/> <xacro:property name="wheel_guide_thickness" value="0.05"/> <xacro:property name="wheel_guide_length" value="0.4"/> <xacro:property name="wheel_guide_height" value="0.1"/> <xacro:property name="body_length" value="0.6"/> <xacro:property name="body_width" value="0.5"/> <xacro:property name="body_height" value="0.3"/> <xacro:property name="camera_width" value="0.01"/> <xacro:property name="wheel_mass" value="0.5"/> <xacro:property name="body_mass" value="1"/> <xacro:property name="guide_mass" value="0.5"/> <xacro:property name="axel_mass" value="0.5"/> <xacro:property name="camera_mass" value="0.1"/> <xacro:property name="kinect_mass" value="0.5"/> <xacro:property name="pi" value="3.1415"/>
<xacro:macro name="default_inertial" params="mass"> <inertial> <mass value="${mass}"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial> </xacro:macro>
<xacro:macro name="shape_visual" params="length width height color">
<visual>
<pose xyz="0 0 1.0"/>
<geometry>
<box size="${length} ${width} ${height}"/>
</geometry>
<material name="${color}"/>
</visual>
<collision>
<geometry>
<box size="${length} ${width} ${height}"/>
</geometry>
</collision>
</xacro:macro>
<xacro:macro name="camera_visual" params="length width height color">
<visual>
<geometry>
<box size="${length} ${width} ${height}"/>
</geometry>
<material name="${color}"/>
</visual>
<collision>
<geometry>
<box size="${length} ${width} ${height}"/>
</geometry>
</collision>
</xacro:macro>
<xacro:macro name="wheel_guide_macro" params="prefix reflect">
<link name="${prefix}_wheel_guide">
<visual>
<origin xyz="0 ${reflect*wheel_guide_thickness/2} 0"/>
<geometry>
<box size="${wheel_guide_length} ${wheel_guide_thickness} ${wheel_guide_height}"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<box size="${wheel_guide_length} ${wheel_guide_thickness} ${wheel_guide_height}"/>
</geometry>
</collision>
<xacro:default_inertial mass="${guide_mass}"/>
</link>
<joint name="${prefix}_wheel_guide_joint" type="fixed">
<axis xyz="0 1 0" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="${prefix}_wheel_guide"/>
<origin xyz="0 ${reflect*body_width/2} 0" rpy="0 0 0"/>
</joint>
<gazebo reference="${prefix}_wheel_guide">
<gravity value="true"/>
<mindepth>0.00001</mindepth>
<material>Gazebo/Grey</material>
</gazebo>
</xacro:macro>
<xacro:macro name="wheel_axle_macro" params="prefix suffix reflect1 reflect2">
<link name="${prefix}_${suffix}_wheel_axle">
<visual>
<origin xyz="0 0 0" rpy="0 ${reflect2*2.0*pi/3} 0"/>
<geometry>
<cylinder radius="${wheel_guide_height*0.2}" length="${wheel_guide_length/2}"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<cylinder radius="${wheel_guide_height*0.2}" length="${wheel_guide_length/2}"/>
</geometry>
</collision>
<xacro:default_inertial mass="${axel_mass}"/>
</link>
<joint name="${prefix}_${suffix}_wheel_axle_joint" type="fixed">
<parent link="${prefix}_wheel_guide"/>
<child link="${prefix}_${suffix}_wheel_axle"/>
<origin xyz="${reflect2*wheel_guide_length/2} ${reflect1* wheel_guide_thickness/2} ${-wheel_guide_height}" rpy="0 0 0"/>
</joint>
<gazebo reference="${prefix}_${suffix}_wheel_axle">
<gravity value="true"/>
<mindepth>0.00001</mindepth>
<material>Gazebo/Grey</material>
</gazebo>
</xacro:macro>
<xacro:macro name="wheel_position_macro" params="prefix suffix reflect1 reflect2">
<link name="${prefix}_${suffix}_wheel">
<visual>
<geometry>
<mesh filename="package://learning_tf/meshes/wheels/rubber_wheel_${prefix}.dae"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
<geometry>
<cylinder radius="${wheel_diameter/2}" length="${wheel_thickness}"/>
</geometry>
<surface>
<bounce>
<restitution_coefficient>0.0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
</surface>
</collision>
<xacro:default_inertial mass="${wheel_mass}"/>
</link>
<joint name="${prefix}_${suffix}_wheel_joint" type="continuous">
<axis xyz="0 1 0"/>
<parent link="${prefix}_${suffix}_wheel_axle"/>
<child link="${prefix}_${suffix}_wheel"/>
<origin xyz="${reflect2*body_length/6.0} ${reflect1*wheel_thickness/2} -${body_height/4.0}"/>
</joint>
<gazebo reference="${prefix}_${suffix}_wheel">
<mu1 value="200.0"/>
<mu2 value="100.0"/>
<kp value="1.0e+6"/>
<kd value="1.0"/>
<gravity value="true"/>
<maxvel>0.0000001</maxvel>
<mindepth>0.00001</mindepth>
<material>Gazebo/Black</material>
</gazebo>
<transmission name="${prefix}_${suffix}_wheel_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${prefix}_${suffix}_wheel_motor">
<hardwareinterface>VelocityJointInterface</hardwareinterface>
<mechanicalreduction>1</mechanicalreduction>
</actuator>
<joint name="${prefix}_${suffix}_wheel_joint">
<hardwareinterface>VelocityJointInterface</hardwareinterface>
</joint>
</transmission>
</xacro:macro>
<material name="white"> <color rgba="1 1 1 1"/> </material> <material name="black"> <color rgba="0 0 0 1"/> </material> <material name="blue"> <color rgba="0 0 0.9 1"/> </material> <material name="green"> <color rgba="0 0.8 0 1"/> </material>
<link name="base_footprint"> <visual> <origin xyz="0 0 0"/> </visual> </link> <link name="base_link">
<xacro:shape_visual length="0.6" width="0.5" height="0.3" color="white"/> <xacro:default_inertial mass="${body_mass}"/> </link> <gazebo reference="base_link"> <material>Gazebo/White</material> <mindepth>0.00001</mindepth> <gravity value="true"/> </gazebo> <joint name="base_joint" type="fixed" >="" <parent="" link="base_footprint"/> <child link="base_link"/> <origin xyz="0 0 0.26" rpy="0 0 0"/> </joint>
<xacro:wheel_guide_macro prefix="left" reflect="-1.0"/> <xacro:wheel_guide_macro prefix="right" reflect="1.0"/> <xacro:wheel_axle_macro prefix="right" suffix="front" reflect1="1.0" reflect2="1.0"/> <xacro:wheel_axle_macro prefix="left" suffix="front" reflect1="-1.0" reflect2="1.0"/> <xacro:wheel_axle_macro prefix="left" suffix="back" reflect1="-1.0" reflect2="-1.0"/> <xacro:wheel_axle_macro prefix="right" suffix="back" reflect1="1.0" reflect2="-1.0"/>
<xacro:wheel_position_macro prefix="left" suffix="front" reflect1="-1.0" reflect2="1.0"/> <xacro:wheel_position_macro prefix="left" suffix="back" reflect1="-1.0" reflect2="-1.0"/> <xacro:wheel_position_macro prefix="right" suffix="back" reflect1="1.0" reflect2="-1.0"/> <xacro:wheel_position_macro prefix="right" suffix="front" reflect1="1.0" reflect2="1.0"/>
<link name="camera_link"> <xacro:camera_visual length="0.01" width="${body_width/12.0}" height="${body_width/12.0}" color="black"/> <xacro:default_inertial mass="${camera_mass}"/> </link> <joint name="camera_joint" type="fixed"> <parent link="base_link"/> <child link="camera_link"/> <origin xyz="${body_length/2 + camera_width} 0 0" rpy="0 0 0"/> </joint>
<gazebo reference="camera_link"> <material>Gazebo/Blue</material> <sensor type="camera" name="camera1"> <update_rate>30.0</update_rate> <camera name="head"> <horizontal_fov>1.3962634</horizontal_fov> <image> <width>640</width> <height>480</height> <format>R8G8B8</format> </image> <clip> <near>0.02</near> <far>300</far> </clip> <noise> <type>gaussian</type> <mean>0.0</mean> <stddev>0.007</stddev> </noise> </camera> <plugin name="camera_controller" filename="libgazebo_ros_camera.so"> <alwayson>true</alwayson> <updaterate>0.0</updaterate> <cameraname>camera1</cameraname> <imagetopicname>image_raw</imagetopicname> <camerainfotopicname>camera_info</camerainfotopicname> <framename>camera_link</framename> <hackbaseline>0.07</hackbaseline> <distortionk1>0.0</distortionk1> <distortionk2>0.0</distortionk2> <distortionk3>0.0</distortionk3> <distortiont1>0.0</distortiont1> <distortiont2>0.0</distortiont2> </plugin> </sensor> </gazebo>
<link name="laser_optical_link"/> <joint name="laser_optical_joint" type="fixed"> <axis xyz="0 1 0"/> <parent link="base_link"/> <child link="laser_optical_link"/> <origin xyz="${body_length/2 + camera_width} 0 0.1" rpy="-${pi/2} 0 -${pi/2}"/> </joint>
<link name="hokuyo_link"> <visual> <pose>0 0 0.036 0 0 0</pose>
<geometry>
<mesh filename="package://learning_tf/meshes/hokuyo.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<cylinder radius="0.01" length="0.01"/>
</geometry>
</collision>
<xacro:default_inertial mass="${kinect_mass}"/>
</link>
<joint name="laser_link_joint" type="fixed">
<parent link="base_link"/>
<child link="hokuyo_link"/>
<origin xyz="-${body_length/2.0 - body_width/4.0} 0 ${body_height/2 + body_height/6}"/>
</joint>
<gazebo reference="hokuyo_link">
<sensor type="ray" name="head_hokuyo_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>true</visualize>
<update_rate>40</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-1.570796</min_angle>
<max_angle>1.570796</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicname>/hokuyo/laser/scan</topicname>
<framename>hokuyo_link</framename>
</plugin>
</sensor>
</gazebo>
<gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotnamespace>/</robotnamespace> </plugin> </gazebo> </robot>
Find also below attached my diff_drive YAML file.
type: "diff_drive_controller/DiffDriveController"
publish_rate: 100
left_wheel: ['left_front_wheel_joint','left_back_wheel_joint'] right_wheel: ['right_front_wheel_joint','right_back_wheel_joint']
wheel_separation: 0.50
Odometry covariances for the encoder output of the robot. These values should
be tuned to your robot's sample odometry data, but these values are a good place
to start
pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03] twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03]
Top level frame (link) of the robot description
base_frame_id: base_link
Velocity and acceleration limits for the robot
linear: x: has_velocity_limits : true max_velocity : 0.2 # m/s has_acceleration_limits: true max_acceleration : 0.6 # m/s^2 angular: z: has_velocity_limits : true max_velocity : 2.0 # rad/s has_acceleration_limits: true max_acceleration : 6.0 # rad/s^2
Note that when I ran this URDF without the diff_drive, all the transforms worked just fine. As soon as I included the diff drive, the TF map changed. As a result of the new link between odom frame and base link frame, my Maps are totally skewed. I get very haphazard maps when running slam-gmapping.
Has anyone experienced this? My information provided may not be as concise as you want... Please ask for clarifications if needed. Thank you.