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

ROS Gazebo URDF Joint Control works with position controller but not any other type

asked 2019-03-27 21:07:11 -0500

hillripper21 gravatar image

Hello, I've noticed a few other questions of a similar nature usually having trouble with namespaces when trying to control joints in ROS Gazebo. I think I've got the namespaces down, but I'm having a weird issue where everything works fine when I use a position controller, but as soon as I try to switch to any other type of controller I get errors. Here are the relevant parts of the files of the working version with position controllers.

Relevant section of urdf:

<transmission name="antenna_rotation">
 <type>transmission_interface/SimpleTransmission</type>
 <actuator name="$antenna_motor">
  <mechanicalReduction>1</mechanicalReduction>
  <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</actuator>
 <joint name="antenna_base_to_antenna">
  <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
 </joint>
</transmission>

 <!-- plugin needed to control robot using ros -->
 <gazebo>
  <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
    <robotNamespace>/antenna_robot</robotNamespace>
  </plugin>
 </gazebo>

Relevant section of launch file, I have the whole robot under its own namespace since I am using 2 different robots.

<group ns="antenna_robot">
    <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" output="screen" args="-file $(find 
     antenna_sim_description)/com_base_station/model.urdf -urdf -x 6.5 -y -6.5 -z 0 -model antenna" />

<arg name="model" default="$(find antenna_sim_description)/com_base_station/model.urdf"/>
<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />

  <rosparam command="load"
      file="$(find antenna_sim_description)/com_base_station/config/joints.yaml"
      ns="antenna_sim_joint_state_controller" />

    <rosparam command="load"
      file="$(find antenna_sim_description)/com_base_station/config/antenna.yaml"
      ns="antenna_sim_antenna_controller" />

    <node name="antenna_sim_controller_spawner" pkg="controller_manager" type="spawner"
      args="antenna_sim_joint_state_controller
      antenna_sim_antenna_controller" />
  </group>

joints.yaml:

type: "joint_state_controller/JointStateController"
publish_rate: 50

antenna.yaml:

type: "position_controllers/JointPositionController"
joint: antenna_base_to_antenna

Everything works great, can this command to rotate the antenna for example:

rostopic pub /antenna_robot/antenna_sim_antenna_controller/command std_msgs/Float64 "data: -0.707"

Now I try to switch to a different type of controller, I change my urdf to VelocityJointInterface I change my antenna.yaml to velocity_controllers/JointTrajectoryController

I get the following errors when I launch:

[ERROR] [1553738576.470885508, 1298.720000000]: Could not find 'joints' parameter (namespace: /antenna_robot/antenna_sim_antenna_controller).
[ERROR] [1553738576.470958595, 1298.720000000]: Failed to initialize the controller
[ERROR] [1553738576.471007007, 1298.720000000]: Initializing controller 'antenna_sim_antenna_controller' failed
[ INFO] [1553738577.027059438, 1299.280000000]: Datum (latitude, longitude, altitude) is (49.900000, 8.900000, 0.000000)
[ INFO] [1553738577.027100296, 1299.280000000]: Datum UTM coordinate is (492818.438771, 5527517.135857)
[ INFO] [1553738577.027129711, 1299.280000000]: Initial odometry pose is Origin: (0 0 0)
Rotation (RPY): (0, -0, 0)
[ INFO] [1553738577.027219487, 1299.280000000]: Corrected for magnetic declination of 0.000000, user-specified offset of 1.570796 and meridian convergence of -0.001335. Transform heading factor is now 1.569461
[ INFO] [1553738577.027244788, 1299.280000000]: Transform world frame pose is: Origin: (0 0 0)
Rotation (RPY): (0, -0, 0)

[ INFO] [1553738577.027269780, 1299.280000000]: World frame->utm transform is Origin: (-5528170.1551857395098 485438.39578638831154 0)
Rotation (RPY): (0, 0, -1.5694612597485673167)

[ERROR] [1553738577.472082, 1299.720000]: Failed to load antenna_sim_antenna_controller

Not sure how this is happening. I've double checked to make sure I have all the controller types installed and I can see that the yaml file is being parsed based on these parameters ... (more)

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-03-28 05:09:02 -0500

gvdhoorn gravatar image

The issue is in your configuration.

First you use:

type: "position_controllers/JointPositionController"
joint: antenna_base_to_antenna

Which is a JointPositionController in the position_controllers package.

Then you state (emphasis mine):

Now I try to switch to a different type of controller, I change my urdf to VelocityJointInterface I change my antenna.yaml to velocity_controllers/JointTrajectoryController

That is a different controller (provided by the joint_trajectory_controller package) and it requires different parameters, one of which is the joints parameter (here).

You only have joint in your antenna.yaml, so you'll have to change it.

This is also clear from the error message in the console output you show:

[ERROR] [1553738576.470885508, 1298.720000000]: Could not find 'joints' parameter (namespace: /antenna_robot/antenna_sim_antenna_controller).

Please also note that joint_trajectory_controllers will require you to send FollowJointTrajectory goals. A single std_msgs/Float64 will no longer work.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2019-03-27 21:07:11 -0500

Seen: 2,387 times

Last updated: Mar 28 '19