$\color{white}\colorbox{FE9227}{Reaching expertise and embracing new challenges!}$ ▓▓▓▓▓▓▓▓▓▓▓▓▓▓▓▓▓▓▓▓▓▓░░░░░░ 80%
In order to control the Ackermann steering joints, we need to define the gazebo_ros2_control
parameters to send commands. Unlike the DIFFERENTIAL drive robot which could use a simple Gazebo
plugin to control movement, the Gazebo
Ackermann steering plugin can only be used to publish odometry information from the wheels but currently does not work for control for the Humble
ROS Distro.
Now it’s time to create controllable joints for the robot. First, we are going to change all the wheel joints from fixed
back to continuous. Also, change the steer joints from fixed
to revolute
. This will break your tf2
tree in RVIZ, but that’s okay because we are going to be adding Gazebo
plugins to fix this.
Navigate to your hunter_steer.xacro
, and change steer_joint
from fixed
to revolute
. Next, change your wheel_joint
from fixed
to continuous
. Navigate to your hunter_motors.xacro
, and change your wheel_joint
from fixed
to continuous
.
Next, we are going to be creating a new XACRO
called hunter_se_gazebo.xacro
. Open your hunter_se_gazebo.xacro
file and paste the following code:
<?xml version="1.0"?>
<robot name="hunter_se_gazebo" xmlns:xacro="<http://wiki.ros.org/xacro>">
<xacro:macro name="steering_control"
params="
name
steer_limlow
steer_limhigh">
<joint name="${name}_steer_joint">
<command_interface name="position">
<param name="min">${steer_limlow}</param>
<param name="max">${steer_limhigh}</param>
</command_interface>
<state_interface name="position" />
<state_interface name="velocity" />
</joint>
</xacro:macro>
<xacro:macro name="velocity_control"
params="
name
velocity_limlow
velocity_limhigh">
<joint name="${name}_wheel_joint">
<command_interface name="velocity">
<param name="min">${velocity_limlow}</param>
<param name="max">${velocity_limhigh}</param>
</command_interface>
<state_interface name="position" />
<state_interface name="velocity" />
<state_interface name="effort" />
</joint>
</xacro:macro>
</robot>
Next, navigate to your hunter_se.xacro
file and create the gazebo_ros2_control
plugin call, ros2_control
tags and the macro
calls:
<xacro:include filename="$(find hunter_se_description)/models/xacro/hunter_se_gazebo.xacro" />
<gazebo>
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
<robotNamespace>${robot_namespace}</robotNamespace>
<parameters>$(find hunter_se_description)/models/config/controllers.yaml</parameters>
</plugin>
</gazebo>
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
<robotNamespace>${robot_namespace}</robotNamespace>
</hardware>
<xacro:steering_control
name="center"
steer_limlow="${-max_steer}"
steer_limhigh="${max_steer}" />
<xacro:steering_control
name="front_right"
steer_limlow="${-max_steer}"
steer_limhigh="${max_steer}" />
<xacro:steering_control
name="front_left"
steer_limlow="${-max_steer}"
steer_limhigh="${max_steer}" />
<xacro:velocity_control
name="rear_right"
velocity_limlow="-7.5"
velocity_limhigh="10.0" />
<xacro:velocity_control
name="rear_left"
velocity_limlow="-7.5"
velocity_limhigh="10.0" />
<xacro:velocity_control
name="front_right"
velocity_limlow="-7.5"
velocity_limhigh="10.0" />
<xacro:velocity_control
name="front_left"
velocity_limlow="-7.5"
velocity_limhigh="10.0" />
</ros2_control>
First, we define macros
that set the command
and state
parameters. These tags define how the joint is able to be controlled, and what information the joint should return to the joint_states
topic. For the steer joint
we define the command interface to be a position
interface and want it to return both the position
and velocity
information. For the rear wheel joints, we set the command
interface to be a velocity
interface and want it to return the position
, velocity
, and effort
information.
<aside> ⚠️ All joints must return position information for them to be visible in RVIZ.
</aside>
<xacro:macro name="steering_control"
params="
name
steer_limlow
steer_limhigh">
<joint name="${name}_steer_joint">
<command_interface name="position">
<param name="min">${steer_limlow}</param>
<param name="max">${steer_limhigh}</param>
</command_interface>
<state_interface name="position" />
<state_interface name="velocity" />
</joint>
</xacro:macro>
<xacro:macro name="velocity_control"
params="
name
velocity_limlow
velocity_limhigh">
<joint name="${name}_wheel_joint">
<command_interface name="velocity">
<param name="min">${velocity_limlow}</param>
<param name="max">${velocity_limhigh}</param>
</command_interface>
<state_interface name="position" />
<state_interface name="velocity" />
<state_interface name="effort" />
</joint>
</xacro:macro>
Next, we add the file inclusion tag, plugin import, and macro calls to our hunter_se.xacro
file.
Within the gazebo_ros2_control
plugin inclusion, the <parameters>
file is set to controllers.yaml
, we will create this file next to define our controller types.
<xacro:include filename="$(find hunter_se_description)/models/xacro/hunter_gazebo.xacro" />
<gazebo>
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
<namespace>${robot_namespace}</namespace>
<parameters>$(find hunter_se_description)/models/config/controllers.yaml</parameters>
</plugin>
</gazebo>
Next, ros2_control
tags are created and the macros
defined earlier are placed within them. It is important that these ros2_control
tags are only called on once, otherwise, the latest call will override earlier calls. The plugin type is set to the gazebo_ros2_control/GazeboSystem
plugin.