diff_drive_controller failing to launch
I want to implement differential drive on a 4 Wheel robot of my own, similar to the Husky and Jackal. In fact both of these mobile robots use diff_drive_controller. However when I implement the controller I get the following problem:
[ERROR] [1595632494.285913005, 0.476000000]: Robot description couldn't be retrieved from param server.
[ERROR] [1595632494.285965899, 0.476000000]: Failed to initialize the controller
[ERROR] [1595632494.286022155, 0.476000000]: Initializing controller 'differential_drive' failed
[ERROR] [1595632495.287013, 1.468000]: Failed to load differential_drive
I am confused to why I get this error as the very first thing I do in my launch file is load the param robot_description
with the URDF file of the robot. I have looked and followed the documentation of the Jackal robot and the wiki page of the diff_drive_controller. I made sure the namespaces are correctly applied and even checked by yaml file. Below I will attach the YAML, launch and URDF files. I thought the solution would be to include a different plugin other than the gazebo_ros_control
. Thank you for your help in advance and apologies if this error is on my behalf, I am still new to ROS. I am on Ubuntu 18.04 and ROS Melodic.
<launch>
<!-- Loads the URDF in the parameter server variable 'robot_description' -->
<param name="robot_description" command="cat $(find monsterborg_description)/urdf/monsterborg.urdf"/>
<!-- Include the file path for empty world, launches the services required for the urdf_spawner node below -->
<include file="$(find gazebo_ros)/launch/empty_world.launch"/>
<!-- Arguements for Gazebo -->
<arg name="x" value="0.0"/>
<arg name="y" value="0.0"/>
<arg name="z" value="0.5"/>
<arg name="urdf_robot_file" value="$(find monsterborg_description)/urdf/monsterborg.urdf" />
<arg name="robot_name" value="monsterborg"/>
<!-- Node to spawm the robot in Gazebo -->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -x $(arg x) -y $(arg y) -z $(arg z) -model $(arg robot_name) -param robot_description"/>
<!-- Launch the robot_state_publisher to broadcast transforms to '/tf' -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn='false' output="screen">
<remap from="/joint_states" to="/monsterborg/joint_states" />
</node>
<!-- Load the joint controller configuration-->
<rosparam file='$(find monsterborg_description)/config/monsterborg_controllers.yaml' command='load'/>
<!-- Load the controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" ns="/monsterborg"
args="joint_state_controller differential_drive"/>
</launch>
monsterborg:
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
differential_drive:
type: diff_drive_controller/DiffDriveController
left_wheel: [base_to_lf_wheel, base_to_lb_wheel]
right_wheel: [base_to_rf_wheel, base_to_rb_wheel]
publish_rate: 50
pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 0.03]
twist_covariance_diagonal: [0.001, 0.001, 0.001, 1000000.0, 1000000.0, 0.03]
cmd_vel_timeout: 0.25
base_frame_id: base_link
wheel_seperation: 0.09
wheel_radius: 0.0525
linear:
x:
has_velocity_limits: true
max_velocity: 2.0 # m/s
has_acceleration_limits: true
max_acceleration: 20.0 # m/s^2
angular:
z:
has_velocity_limits: true
max_velocity: 4.0 # rad/s
has_acceleration_limits: true
max_acceleration: 25.0 # rad/s^2
<robot name="monsterborg">
<link name="base_link">
<visual> ...
I wonder if the robot_description-cat combination works. Did you check if the urdf is ok with