ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Nav2 odometry for Ackermann plugin

asked 2023-03-28 16:12:42 -0500

Vini71 gravatar image

updated 2023-03-28 16:16:01 -0500

Hi I am following this tutorial to set the odom to my truck_robot xacro

Unfortunately, I was not able to see the \odom or \demo_odom topic published in my terminal. After issue "ros2 topic list" I just get:

/clock
/demo/imu
/joint_states
/parameter_events
/performance_metrics
/robot_description
/rosout
/tf
/tf_static

I am unsure if the libgazebo_ros_ackermann_drive I used is still unavailable to ROS2 (I think this might not be the issue).

For the simple wheeled robot configured in the tutorial, the odom was published (it used the differential plugin instead).

Can someone figure out the issue and assist me in getting the odometry topic published? My xacro is correct and opened on rviz and the gazebo. My launch_file

edit retag flag offensive close merge delete

Comments

This doesn't seem directly related to Nav2, but instead your control / simulation plugins. You might want to change the question's name.

stevemacenski gravatar image stevemacenski  ( 2023-03-30 10:16:09 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2023-04-03 00:08:35 -0500

Vini71 gravatar image

updated 2023-04-03 00:09:15 -0500

I've resolved the issue, and it turned out to be simpler than I initially thought. The problem was due to incorrect joint name nomenclature and not calling the <gazebo> tags before the plugin declaration. By correcting the joint names and properly including the <gazebo> tags, the truck now moves as expected using the Ackermann plugin

The fixed snippet of code:

  <gazebo>

    <plugin name="gazebo_ros_ackermann_drive" filename="libgazebo_ros_ackermann_drive.so">
      <ros>
        <namespace>/demo</namespace>
        <parameter name="cmd_vel_topic" value="cmd_demo"/>
        <parameter name="odom_topic" value="odom_demo"/>
        <parameter name="distance_topic" value="distance_demo"/>
      </ros>

      <update_rate>100.0</update_rate>

      <!-- wheels -->
      <front_left_joint>front_left_wheel_joint</front_left_joint>
      <front_right_joint>front_right_wheel_joint</front_right_joint>
      <rear_left_joint>rear_second_left_wheel_joint</rear_left_joint>
      <rear_right_joint>rear_second_right_wheel_joint</rear_right_joint>

      <!-- steering joints -->
      <left_steering_joint>front_left_steer_joint</left_steering_joint>
      <right_steering_joint>front_right_steer_joint</right_steering_joint>

      <!-- Other parameters remain the same -->
      <max_steer>0.6458</max_steer>
      <max_steering_angle>7.85</max_steering_angle>
      <max_speed>20</max_speed>

      <!-- PID tuning -->
      <left_steering_pid_gain>1500 0 1</left_steering_pid_gain>
      <left_steering_i_range>0 0</left_steering_i_range>
      <right_steering_pid_gain>1500 0 1</right_steering_pid_gain>
      <right_steering_i_range>0 0</right_steering_i_range>
      <linear_velocity_pid_gain>1000 0 1</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_demo</odometry_frame>
      <robot_base_frame>chassis</robot_base_frame>
    </plugin>
  </gazebo>

image description

The result: https://youtu.be/Wf3rhqRSTKw

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2023-03-28 16:12:42 -0500

Seen: 265 times

Last updated: Apr 03 '23