0
$\begingroup$

I'm working with an Ackermann car-like robot. I have an issue with the tf in RVIZ because to make an Ackermann steering you have to make a virtual link due to ROS2 doesn't allow yet 2 dof in a joint. So I have two virtual cylinder for z axis move, inside the front wheels, and the front wheel link for the spin, y axis.

My robot works in Gazebo and move good but when I see the tf in RVIZ the front wheels links don't move but the the virtual cylinders do. I have seen the tf tree and is well done but I don't know why the front wheel tf don't work properly.

In the official supported page for Ackermann controller, section 1.3 says:

If you want rviz to show states of robot's actual joint interfaces' tf through joint_state_controller and robot_state_publisher, you need to convert the two interfaces of ackermann_steering_controller to your robot's specific ones via RobotHW or RobotHWSim (generally used for GAZEBO). This is because the controller only update it's basic interfaces mentioned in the previous section.

Does anyone know what is the RobotHW or RobotHWSim and how to use it in ROS2. I just want it for simulation purpose.

My view_frame here:

enter image description here

$\endgroup$

2 Answers 2

0
$\begingroup$

Be aware that the cited ackermann controller is for ROS 1, and not applicable to ROS 2.

You mean the TF tree is complete, i.e. there are no "white unconnected" boxes in rviz2?

I suggest introspect the joint_states topic. You have to add state interfaces to the ros2_control tag, so that the joint_states topic includes positions of every joint in the kinematic chain. But normally robot_state_publisher would not create a complete TF tree is something is missing..

$\endgroup$
8
  • $\begingroup$ Hi Christoph, I know the ackermann controller documentation is for ROS1. I can't find the official Ackermann documentation for ROS2. I just want to know if there's something else I need to add in this version other than from the controller itself. I have just updated the post explaining it is view_frame what I meant, not TF tree. Sorry for the confusion. In addition, I don't know what you mean with white unconnected boxes in rviz2. Could you explain it? thanks. $\endgroup$ Commented Feb 11 at 17:04
  • $\begingroup$ You haven't written which type of controller you are using. This one(ros2_control) or this gazebo plugin? $\endgroup$ Commented Feb 11 at 19:00
  • $\begingroup$ If you load a robot model into rviz, and the tf tree is not present or not complete you will see the links as white boxes in the middle of the origin. If this would be the case you would immediately know what I mean. $\endgroup$ Commented Feb 11 at 19:00
  • $\begingroup$ have you had a look on the joint_states topic? $\endgroup$ Commented Feb 11 at 19:01
  • 1
    $\begingroup$ If the position is always zero, then you have found why the robot_state_publisher can't update the TF tree. Now you have to check the settings of your gazebo plugins (for which I don't have any experience though). But maybe you want to share the relevant part of your URDF/SDF. $\endgroup$ Commented Feb 14 at 9:38
0
$\begingroup$

I've solved the issue. The ackermann plugin for Gazebo asks for 7 joints:

<gazebo>
  <plugin name="gazebo_ros_ackermann_drive" filename="libgazebo_ros_ackermann_drive.so">
  
      <!--<ros>
          <namespace>demo</namespace>
          <remapping>cmd_vel:=cmd_demo</remapping>
          <remapping>odom:=odom_demo</remapping>
          <remapping>distance:=distance_demo</remapping>
      </ros>-->
  
    <update_rate>100.0</update_rate>
  
    <!-- wheels -->
    <front_left_joint>wheel_left</front_left_joint>
    <front_right_joint>wheel_right</front_right_joint>
    <rear_left_joint>rear_left_wheel_joint</rear_left_joint>
    <rear_right_joint>rear_right_wheel_joint</rear_right_joint>
    <left_steering_joint>front_left_wheel_joint</left_steering_joint>
    <right_steering_joint>front_right_wheel_joint</right_steering_joint>
    <steering_wheel_joint>steering_joint</steering_wheel_joint>

The first 4 are for the movement of the wheels and let the robot move. The following 2 joints are for the steering (in my case, the front wheels, wich are virtual links). The last one is for the steering wheel (like a car).

My urdf code below:

<?xml version="1.0"?>
<link name="base_link">
    <visual>
        <origin
            xyz="0 0 0"
            rpy="1.5707963267948966 0 -1.5707963267948966"/>
        <geometry>
            <mesh
                filename="package://robot_desc/meshes/base_link.stl" scale="0.001 0.001 0.001" />"
        </geometry>
    </visual>
    <collision>
        <origin xyz="0 0 0.03"
                rpy="0 0 0"/>
        <geometry>
            <box size="0.7 0.250 0.08"/>
        </geometry>
    </collision>
    <inertial>
        <origin xyz="0 0.02002 7.595e-3"/>
        <mass value="4"/>
        <inertia ixx="1.8922e-2" ixy="0" ixz="0" iyy="1.27806e-1" iyz="0" izz="1.44868e-1"/>
    </inertial>
</link>

<link name="footprint"/>

<link name="torre">
    <inertial>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <mass value="1.5"/>
      <inertia ixx="0.015" ixy="0" ixz="0" iyy="0.015" iyz="0" izz="0.015"/>
    </inertial>
  
    <visual>
      <origin xyz="0 0 0" rpy="0 0 1.5707963267948966"/>
      <geometry>
        <mesh filename="package://robot_desc/meshes/torre_lidar.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </visual>
  
    <collision>
      <origin xyz="-0.05 0 0.25" rpy="0 0 0"/>
      <geometry>
        <box size="0.2 0.2 0.1"/>
      </geometry>
    </collision>
  </link>
  

<link name="steering_wheel">
    <visual>
      <origin xyz="0 0 0" rpy="1.302101 0 -1.5707963267948966"/>
      <geometry>
        <cylinder radius="0.01" length="0.004"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <cylinder radius="0.01" length="0.004"/>
      </geometry>
      <!--<surface>
        <contact>
          <ode>
            <min_depth>0.003</min_depth>
          </ode>
        </contact>
      </surface>-->
    </collision>
    <inertial>
      <mass value="0.01"/>
      <inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
    </inertial>
  </link>
  

<link name="front_left_wheel">
    <visual>
        <origin 
            xyz="0 0 0"
            rpy="1.5707963267948966 0 1.5707963267948966"/>
        <geometry>
            <mesh 
                filename="package://robot_desc/meshes/rueda.stl" scale="0.001 0.001 0.001"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0 0 0"
                rpy="0 0 0"/>
        <geometry>
            <sphere radius="0.1"/>
        </geometry>
    </collision>
    <inertial>
        <origin xyz="0 0 0"/>
        <mass value="1"/>
        <inertia ixx="0.006292" ixy="0" ixz="0" iyy="0.0039638" iyz="0" izz="0.0039638"/>
    </inertial>
</link>

<link name="virtual_left">
    <visual>
        <origin
            xyz="0 0 0"
            rpy="0 0 0"/>
        <geometry>
            <cylinder radius="0.02" length="0.05"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0 0 0"
                rpy="0 0 0"/>
        <geometry>
            <cylinder radius="0.02" length="0.05"/>
        </geometry>
        <!--<surface>
            <friction>
              <ode>
                <mu>0.9</mu>
                <mu2>0.9</mu2>
                <slip1>0.0</slip1>
                <slip2>0.0</slip2>
              </ode>
            </friction>
            <contact>
              <ode>
                <min_depth>0.001</min_depth>
                <kp>1e9</kp>
              </ode>
            </contact>
          </surface>-->
    </collision>
    <inertial>
        <origin xyz="0 0 0"/>
        <mass value="0.1"/>
        <inertia ixx="0.015" ixy="0" ixz="0" iyy="0.015" iyz="0" izz="0.015"/>
    </inertial>
</link>

<link name="front_right_wheel">
    <visual>
        <origin 
            xyz="0 0 0"
            rpy="1.5707963267948966 0 -1.5707963267948966"/>
        <geometry>
            <mesh 
                filename="package://robot_desc/meshes/rueda.stl" scale="0.001 0.001 0.001"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0 0 0"
                rpy="0 0 0"/>
        <geometry>
            <sphere radius="0.1"/>
        </geometry>
        <!--<surface>
            <friction>
              <ode>
                <mu>0.9</mu>
                <mu2>0.9</mu2>
                <slip1>0.0</slip1>
                <slip2>0.0</slip2>
              </ode>
            </friction>
            <contact>
              <ode>
                <min_depth>0.001</min_depth>
                <kp>1e9</kp>
              </ode>
            </contact>
          </surface>-->
    </collision>
    <inertial>
        <origin xyz="0 0 0"/>
        <mass value="1"/>
        <inertia ixx="0.006292" ixy="0" ixz="0" iyy="0.0039638" iyz="0" izz="0.0039638"/>
    </inertial>
</link>

<link name="virtual_right">
    <visual>
        <origin
            xyz="0 0 0"
            rpy="0 0 0"/>
        <geometry>
            <cylinder radius="0.02" length="0.05"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0 0 0"
                rpy="0 0 0"/>
        <geometry>
            <cylinder radius="0.02" length="0.05"/>
        </geometry>
        <!--<surface>
          <friction>
            <ode>
              <mu>0.9</mu>
              <mu2>0.9</mu2>
              <slip1>0.0</slip1>
              <slip2>0.0</slip2>
            </ode>
          </friction>
          <contact>
            <ode>
              <min_depth>0.001</min_depth>
              <kp>1e9</kp>
            </ode>
          </contact>
        </surface>-->
    </collision>
    <inertial>
        <origin xyz="0 0 0"/>
        <mass value="0.1"/>
        <inertia ixx="0.015" ixy="0" ixz="0" iyy="0.015" iyz="0" izz="0.015"/>
    </inertial>
</link>

<link name="rear_left_wheel">
    <visual>
        <origin 
            xyz="0 0 0"
            rpy="1.5707963267948966 0 1.5707963267948966"/>
        <geometry>
            <mesh 
                filename="package://robot_desc/meshes/rueda.stl" scale="0.001 0.001 0.001"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0 0 0"
                rpy="0 0 1.5707963267948966"/>
        <geometry>
            <sphere radius="0.1"/>
        </geometry>
        <!--<surface>
            <friction>
              <ode>
                <mu>1.1</mu>
                <mu2>1.1</mu2>
                <slip1>0.0</slip1>
                <slip2>0.0</slip2>
              </ode>
            </friction>
            <contact>
              <ode>
                <min_depth>0.001</min_depth>
                <kp>1e9</kp>
              </ode>
            </contact>
          </surface>-->
    </collision>
    <inertial>
        <origin xyz="0 0 0"/>
        <mass value="1"/>
        <inertia ixx="0.006292" ixy="0" ixz="0" iyy="0.0039638" iyz="0" izz="0.0039638"/>
    </inertial>
</link>

<link name="rear_right_wheel">
    <visual>
        <origin 
            xyz="0 0 0"
            rpy="1.5707963267948966 0 -1.5707963267948966"/>
        <geometry>
            <mesh 
                filename="package://robot_desc/meshes/rueda.stl" scale="0.001 0.001 0.001"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0 0 0"
                rpy="0 0 0"/>
        <geometry>
            <sphere radius="0.1"/>
        </geometry>
        <!--<surface>
            <friction>
              <ode>
                <mu>1.1</mu>
                <mu2>1.1</mu2>
                <slip1>0.0</slip1>
                <slip2>0.0</slip2>
              </ode>
            </friction>
            <contact>
              <ode>
                <min_depth>0.001</min_depth>
                <kp>1e9</kp>
              </ode>
            </contact>
          </surface>-->
    </collision>
    <inertial>
        <origin xyz="0 0 0"/>
        <mass value="1"/>
        <inertia ixx="0.006292" ixy="0" ixz="0" iyy="0.0039638" iyz="0" izz="0.0039638"/>
    </inertial>
</link>
    
<joint type="revolute" name="front_left_wheel_joint">
    <origin xyz="0.2525 0.240 0" rpy="0 0 1.5707963267948966"/>
    <parent link="base_link"/>
    <child link="virtual_left"/>
    <limit upper="0.8727" lower="-0.8727" velocity="10" effort="10"/>
    <axis xyz= "0 0 1" />
    <dynamics damping="0.05" friction="1"/>
</joint>

<joint type="continuous" name="wheel_left">
    <origin xyz="0 0 0"/>
    <parent link="virtual_left"/>
    <child link="front_left_wheel"/>
    <axis xyz= "1 0 0" />
    <dynamics damping="0.05" friction="0.1"/>
</joint>

<joint type="revolute" name="front_right_wheel_joint">
    <origin xyz="0.2525 -0.240 0" rpy="0 0 1.5707963267948966"/>
    <parent link="base_link"/>
    <child link="virtual_right"/>
    <limit upper="0.8727" lower="-0.8727" velocity="10" effort="10"/>
    <axis xyz= "0 0 1" />
    <dynamics damping="0.05" friction="1"/>
</joint>

<joint type="continuous" name="wheel_right">
    <origin xyz="0 0 0"/>
    <parent link="virtual_right"/>
    <child link="front_right_wheel"/>
    <axis xyz= "1 0 0" />
    <dynamics damping="0.05" friction="0.1"/>
</joint>

<joint type="continuous" name="rear_left_wheel_joint">
    <origin xyz="-0.2525 0.240 0" rpy="0 0 1.5707963267948966"/>
    <parent link="base_link"/>
    <child link="rear_left_wheel"/>        
    <axis xyz= "1 0 0" />
    <dynamics damping="0.05" friction="0.15"/>
</joint>

<joint type="continuous" name="rear_right_wheel_joint">
    <origin xyz="-0.2525 -0.240 0" rpy="0 0 1.5707963267948966"/>
    <parent link="base_link"/>
    <child link="rear_right_wheel"/>        
    <axis xyz= "1 0 0" />
    <dynamics damping="0.05" friction="0.15"/>
</joint>

<joint type="revolute" name="steering_joint">
    <origin xyz="0.20 0 0.1"/>
    <parent link="base_link"/>
    <child link="steering_wheel"/>
    <limit upper="7.85" lower="-7.85" velocity="10" effort="10"/>
    <axis xyz= "1 0 0" />
    <dynamics damping="0.05" friction="0.00001"/>
</joint>

<joint type="fixed" name="base_torre">
    <parent link="base_link"/>
    <child link="torre"/>
    <origin xyz="0 0 0"/>
</joint>

<joint type="fixed" name="base_footprint">
    <parent link="base_link"/>
    <child link="footprint"/>
    <origin xyz="0 0 -0.1"/>
</joint>

<gazebo reference="front_left_wheel">
    <mu1>0.9</mu1>  
    <mu2>0.9</mu2>
    <kp>1000000</kp>
    <kd>1</kd>
</gazebo>

<gazebo reference="front_right_wheel">
    <mu1>0.9</mu1>  
    <mu2>0.9</mu2>
    <kp>1000000</kp>
    <kd>1</kd>
</gazebo>

<gazebo reference="rear_left_wheel">
    <mu1>1.1</mu1>  
    <mu2>1.1</mu2>
    <kp>1000000</kp>
    <kd>1</kd>
</gazebo>

<gazebo reference="rear_right_wheel">
    <mu1>1.1</mu1>  
    <mu2>1.1</mu2>
    <kp>1000000</kp>
    <kd>1</kd>
</gazebo>

<gazebo>
  <plugin name="gazebo_ros_ackermann_drive" filename="libgazebo_ros_ackermann_drive.so">
  
      <!--<ros>
          <namespace>demo</namespace>
          <remapping>cmd_vel:=cmd_demo</remapping>
          <remapping>odom:=odom_demo</remapping>
          <remapping>distance:=distance_demo</remapping>
      </ros>-->
  
    <update_rate>100.0</update_rate>
  
    <!-- wheels -->
    <front_left_joint>wheel_left</front_left_joint>
    <front_right_joint>wheel_right</front_right_joint>
    <rear_left_joint>rear_left_wheel_joint</rear_left_joint>
    <rear_right_joint>rear_right_wheel_joint</rear_right_joint>
    <left_steering_joint>front_left_wheel_joint</left_steering_joint>
    <right_steering_joint>front_right_wheel_joint</right_steering_joint>
    <steering_wheel_joint>steering_joint</steering_wheel_joint>
    
  
    <!-- Max absolute steer angle for tyre in radians-->
    <!-- Any cmd_vel angular z greater than this would be capped -->
    <max_steer>6</max_steer>
  
    <!-- Max absolute steering angle of steering wheel -->
    <max_steering_angle>7.85</max_steering_angle>
  
    <!-- Max absolute linear speed in m/s -->
    <max_speed>4</max_speed>
  
    <!-- PID tuning -->
    <left_steering_pid_gain>200 0 1</left_steering_pid_gain>
    <left_steering_i_range>0 0</left_steering_i_range>
    <right_steering_pid_gain>200 0 1</right_steering_pid_gain>
    <right_steering_i_range>0 0</right_steering_i_range>
    <linear_velocity_pid_gain>15 0 0</linear_velocity_pid_gain>
    <linear_velocity_i_range>0 0</linear_velocity_i_range>
  
    <!-- output -->
    <publish_odom>true</publish_odom>
    <publish_odom_tf>true</publish_odom_tf>
    <publish_wheel_tf>true</publish_wheel_tf>
    <publish_distance>true</publish_distance>
  
    <odometry_frame>odom</odometry_frame>
    <robot_base_frame>base_link</robot_base_frame>
  
  </plugin>
</gazebo>

At the beginning I was doing this (wrong):

    <front_left_joint>front_left_wheel_joint</front_left_joint>
    <front_right_joint>front_right_wheel_joint</front_right_joint>
    <rear_left_joint>rear_left_wheel_joint</rear_left_joint>
    <rear_right_joint>rear_right_wheel_joint</rear_right_joint>
    <left_steering_joint>front_left_wheel_joint</left_steering_joint>
    <right_steering_joint>front_right_wheel_joint</right_steering_joint>
    <steering_wheel_joint>steering_joint</steering_wheel_joint>

So, although the robot moved good in Gazebo, in RVIZ the front wheels didn't move because I was using the same joint for two purpose.

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.