ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
To summarize the cause of the two issues, in case others come across this question in the future:
1) ros2_control
/gazebo
trying to load a controller multiple times
This shouldn't happen, and in this case was caused by multiple launch files loading the controllers.
2) "Command interface with 'front_left_steering_joint/velocity' does not exist";
Your controller is looking for a velocity
control interface for joint front_left_steering_joint
, but your <ros2_control>
tag in your URDF is telling the controller_manager
that your "hardware" only supports position
control for this joint. The diff_driver_controller
currently only supports velocity
commands to the wheels, and accepts position
or velocity
state interfaces (you can take a look at the source here for reference).
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<joint name="front_left_steering_joint">
<command_interface name="position"/> <------------------- here
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
Since this is a gazebo question, you can resolve this by simply changing front_left
, front_right
, rear_left
and rear_right
joints to be velocity
controlled in the <ros2_control>
block of your URDF.
All that said, based on the naming convention you used, it sounds like you want those to be steerable joints. Perhaps you want to consider implementing an Ackermann
controller or similar. The ros2_controllers
repo has a tricycle_controller which you may find to be a good starting point. Alternately, you could take a crack at porting either the ros1 ackermann_controller or this swerve_steering_controller to ros2.