Gazebo | Ignition | Community
Ask Your Question
0

Making a differential drive robot move

asked 2018-11-10 12:50:21 -0500

zoid gravatar image

updated 2018-11-10 12:53:58 -0500

Hello all,

I am new to Gazebo in general and I require some assistance. I have the following .xacro file that describes links and joints of a differential drive robot. I need to move this robot around in ROS and I found the differential_drive_controller (libgazebo_ros_diff_drive.so) plugin. However, when I launch the simulation and although I publish a message to the /trs/cmd_vel topic (rostopic pub -1 /trs/cmd_vel geometry_msgs/Twist '{linear: {x: 1.0, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 1.0}}') the robot is not moving. Can someone help me on how to fix this?

<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="trs_base">

<xacro:macro name="inertia_cylinder" params="mass radius length"> <mass value="${mass}"/> <inertia ixx="${1 / 12 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0" iyy="${1 / 12 * mass * (3 * radius * radius + length * length)}" iyz="0.0" izz="${mass * radius * radius / 2}"/> </xacro:macro>

<xacro:macro name="trs_base" params="prefix"> <link name="robot"/> <joint name="${prefix}robot_to_chassis" type="fixed"> <parent link="robot"/> <child link="${prefix}chassis_link"/> <origin rpy="0 0 0" xyz="0 0 0"/> </joint>

<link name="${prefix}chassis_link">
  <inertial>
    <mass value="120.911"/>
    <origin rpy="0 0 0" xyz="-0.1832 0.0 0.15"/>
    <inertia ixx="3.50889411882" ixy="0.0" ixz="0.0" iyy="9.06900169571" iyz="0.0" izz="11.7718257055"/>
  </inertial>
  <collision name="base">
    <origin rpy="0.0 0.0 1.57" xyz="-0.2032 0.0 0.15"/>
    <geometry>
      <box size="0.3652 0.8374 0.15"/>
    </geometry>
  </collision>
  <collision name="front_sensor_bar_high">
    <origin xyz="0.1026 0.0 0.20"/>
    <geometry>
      <cylinder length=".075" radius=".2826"/>
    </geometry>
  </collision>
  <collision name="front_sensor_bar_low">
    <origin xyz="0.1026 0.0 0.075"/>
    <geometry>
      <cylinder length=".075" radius=".2826"/>
    </geometry>
  </collision>
  <collision name="rear_sensor_bar_high">
    <origin xyz="-0.498 0.0 0.20"/>
    <geometry>
      <cylinder length=".075" radius=".2826"/>
    </geometry>
  </collision>
  <collision name="rear_sensor_bar_low">
    <origin xyz="-0.498 0.0 0.075"/>
    <geometry>
      <cylinder length=".075" radius=".2826"/>
    </geometry>
  </collision>
  <!-- This model was changed to have a single central caster to remove a contact point and reduce the qcbot model jitter. \
    This change was based on successful, jitter-reducing changes to the RPR model, and is partially made of black magic. -->
  <collision name="center_caster_collision">
    <origin xyz="-0.37 0.0 0.1018"/>
    <geometry>
      <sphere radius=".1018"/>
    </geometry>
  </collision>
  <visual>
    <origin rpy="1.5708 0 1.5708" xyz="0 0 0.2159"/>
    <!-- uncomment to use a lower-resolution stl which includes the bottom of qcbot and its wheels -->
    <geometry>
      <mesh filename="package://trs/meshes/base.stl" scale="0.001 0.001 0.001"/>
    </geometry>
    <!-- uncomment to use a higher-resolution stl which does not include the bottom of qcbot or its wheels -->
    <material name="LightGrey">
      <color rgba="0.4 0.4 0.4 1.0"/>
    </material>
  </visual>


</link>

<link name="${prefix}left_wheel_link">
  <inertial>
    <origin xyz="0 0 0" rpy="0 0 0" />
    <xacro:inertia_cylinder mass="2" radius="0.1018" length="0.04"/>
  </inertial>
  <collision ...
(more)
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2018-11-11 13:02:32 -0500

zoid gravatar image

Hello and thank you for your answer. I have my controller YAML file as follows:

 trs:
  # Publish all joint states -----------------------------------
  joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50  

  # Position Controllers ---------------------------------------
  lift_position_controller:
    type: effort_controllers/JointPositionController
    joint: trs_frame_to_lift_joint
    pid: {p: 10000.0, i: 1.00, d: 1000.0}
  rotary_position_controller:
    type: effort_controllers/JointPositionController
    joint: trs_lift_to_rotary_joint
    pid: {p: 100.0, i: 0.01, d: 10.0}
  forks_position_controller:
    type: effort_controllers/JointPositionController
    joint: trs_rotary_to_forks_joint
    pid: {p: 1000.0, i: 0.1, d: 100.0}
  carriage_position_controller:
    type: effort_controllers/JointPositionController
    joint: trs_rotary_to_carriage_joint
    pid: {p: 1000.0, i: 0.1, d: 100.0}

  # Trs base Controller-----------------------------------------
  diff_drive_controller:
    type: "diff_drive_controller/DiffDriveController"
    left_wheel: base_left_wheel_joint
    right_wheel: base_right_wheel_joint
    wheel_separation: 0.46
    wheel_radius: 0.1018
    cmd_vel_timeout: 0.25
    enable_odom_tf: true
    pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
    twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
    base_frame_id: base_chassis_link

and my launch file as follows:

<launch>
  <arg name="debug" default="false"/>
  <arg name="gui" default="true"/>
  <arg name="paused" default="true"/>

  <!--//////////////////GAZEBO//////////////////-->
  <!-- Include empty world -->
  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="world_name" value="$(find trs_gazebo)/worlds/trs.world"/>
    <arg name="debug" value="$(arg debug)"/>
    <arg name="gui" value="$(arg gui)"/>
    <arg name="paused" value="$(arg paused)"/>
  </include>

  <!--//////////////////URDF//////////////////-->
  <!-- Load URDF into the Ros Parameter Server-->
  <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find trs)/trs_with_base.urdf.xacro'"/>

  <!-- Run a python script to send a service call to gazebo_ros to spawn a URDF robot -->
  <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model trs -robot_namespace trs -J trs_frame_to_lift_joint 1.0" />


  <!--//////////////////JOINT STATE CONTROLLER//////////////////-->
  <!-- load configuration -->
  <rosparam command="load" file="$(find trs_gazebo)/launch/trs_control.yaml" />

  <!-- spawn controllers -->
  <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" ns="/trs" args="lift_position_controller rotary_position_controller forks_position_controller carriage_position_controller joint_state_controller diff_drive_controller" /><!-- mobile_base_controller-->

  <!-- Convert joint states to TF transforms -->
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" ns="trs" output="screen"/>

<!--
  <node name="rviz" pkg="rviz" type="rviz" />
-->
</launch>

Also, the .xacro file as it is right now looks as follows:

<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="trs_base">

<xacro:macro name="inertia_cylinder" params="mass radius length"> <mass value="${mass}"/> <inertia ixx="${1 / 12 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0" iyy="${1 / 12 * mass * (3 * radius * radius + length * length)}" iyz="0.0" izz="${mass * radius * radius / 2}"/> </xacro:macro>

<xacro:macro name="trs_base" params="prefix">

<!--gazebo reference="robot">
  <material>Gazebo/Orange</material>
</gazebo-->
<!--gazebo reference="${prefix}chassis_link">
  <material>Gazebo/Orange</material>
</gazebo-->
<gazebo reference="${prefix}left_wheel_link">
  <material>Gazebo/Orange</material>
</gazebo>
<gazebo reference="${prefix}right_wheel_link">
  <material>Gazebo/Orange</material>
</gazebo>

<link name="robot"/>
<joint name="${prefix}robot_to_chassis" type="fixed">
  <parent link="robot"/>
  <child link="${prefix}chassis_link"/>
  <origin rpy="0 0 0" xyz="0 0 0"/>
</joint>

<link name="${prefix}chassis_link">
  <inertial>
    <mass value="120.911"/>
    <origin rpy="0 0 0" xyz="-0.1832 0.0 0.15"/>
    <inertia ixx="3.50889411882" ixy="0.0" ixz="0.0" iyy="9.06900169571" iyz="0.0" izz="11.7718257055"/>
  </inertial>
  <collision name ...
(more)
edit flag offensive delete link more

Comments

The names of the wheel joints in your URDF do not match the names you've given in the controller yaml. The urdf has ${prefix}left_wheel_joint while the controller has base_left_wheel_joint There will probably be a warning/error message about this somewhere in the console when you launch this.

PeteBlackerThe3rd gravatar imagePeteBlackerThe3rd ( 2018-11-12 06:48:55 -0500 )edit
0

answered 2018-11-11 08:39:20 -0500

PeteBlackerThe3rd gravatar image

It looks live you've made the URDF for this okay, but you'll need to start a few more components to be able to drive this with the /cmd_vel topic. At the moment you've just spawned a robot with controllable joints but without anything controlling them.

You'll need to create a yaml file which contains the configuration of the differential driver controller itself, and optionally a joint_state_controller so that ROS can know the angle of the wheel joints.

The launch file that starts the simulation will need to load the configuration from this yaml file and start the ros_control controllers.

The YAML file should look something like this:

# Publish all joint states -----------------------------------
joint_state_controller:
  type: joint_state_controller/JointStateController
  publish_rate: 50  

# Differential Drive Controller
diff_drive_controller:
  type: "diff_drive_controller/DiffDriveController"
  left_wheel: ['left_wheel_hinge']
  right_wheel: ['right_wheel_hinge'']

  wheel_separation: 0.66
  wheel_radius: 0.1

  cmd_vel_timeout: 0.25
  enable_odom_tf: true

  pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
  twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]

You'll need to add the following lines to your launch file to start the controllers:

  <!-- Load joint controller configurations from YAML file to parameter server -->
  <rosparam file="$(find rorover_skid_steer)/config/rorover_control.yaml" command="load"/>

  <!-- load the controllers -->
  <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
    output="screen" args="joint1_position_controller diff_drive_controller joint_state_controller"/>

You will have to change the joint names to match your robot, but this should get this working for you.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-11-10 12:50:21 -0500

Seen: 5,086 times

Last updated: Nov 11 '18