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

problems with a simple realtime joint controller in Gazebo

asked 2011-10-25 12:40:42 -0500

andrew-unit gravatar image

updated 2011-11-03 06:01:20 -0500

Wim gravatar image

Hello,

I'm trying to follow along with the Writing a realtime joint controller tutorial. I've got the class all set up, and I believe I've got it installed correctly using the plugin lib, as I can see the controller when I do

rosrun pr2_controller_manager pr2_controller_manager list

and I can see that the plugin is running OK. The problem is that even when I set the joint_state_->commanded_effort_ to a fixed value, I don't see any change in the joints of my simulation in gazebo. However, when I do a rostopic echo of the /mechanism_statistics, I can see that the commanded effort is non-zero and that the limits haven't been violated:

name: p_one_joint_4
timestamp: 
  secs: 54
  nsecs: 5000000
position: 0.0
velocity: 0.0
measured_effort: 0.0
commanded_effort: -100.0
is_calibrated: True
violated_limits: False
odometer: 0.0
min_position: 0.0
max_position: 0.0
max_abs_velocity: 0.0
max_abs_effort: 0.0

Also, it is interesting that when I go into gazebo and tinker with the joints manually by using the little hand tool and making the joints move, I don't see anything when I add a printf into the controller to print the joint position (it stays 0). I know that putting a printf in the controller is a bad idea for real-time behavior... Any hints on why I can't get the joint to move with my simple controller would be appreciated. Also in my joint definition in my URDF file I do not have a limit or safety_controller tag currently in it (they're below but commented out):

    <joint name="${parent}_${suffix}_joint_4" type="continuous">
        <origin xyz="${link_4_len} 0 0" rpy="0 0 0" />
        <axis xyz="0 1 0" />
        <!-- <limit effort="10" velocity="10" /> -->
        <!-- <safety_controller soft_lower_limit="-1.5" soft_upper_limit="1.5" k_position="1" k_velocity="1"/> -\-> -->
        <joint_properties damping="0.0" friction="0.0" />
        <parent link="${parent}_${suffix}_link_4" />
        <child link="${parent}_${suffix}_link_5" />
    </joint>

I have also verified that the links look OK in the simulation as well as in rviz, and the TF tree looks like it's being published.

edit retag flag offensive close merge delete

Comments

Hmm. Another observation is that when I fire up the simulation and grab the robot with the hand tool to get it to move the joints, and I try to do a rostopic echo of /joint_states, I see all the joints in my urdf file, but the positions, velocities, and effort are all zero. Also in rviz it looks like the joints aren't moving at all.
andrew-unit gravatar image andrew-unit  ( 2011-10-26 00:55:18 -0500 )edit
Puting printfs in the realtime loop won't crash it, though it will diminish its performances you can try it. Have you been through this tutorial : http://www.ros.org/wiki/pr2_mechanism/Tutorials/Running%20a%20controller%20in%20simulation ?
Guido gravatar image Guido  ( 2011-11-15 21:13:55 -0500 )edit

Is this joint connected to any actuators?

sglaser gravatar image sglaser  ( 2012-02-14 13:24:55 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
2

answered 2012-02-14 13:56:28 -0500

hsu gravatar image

updated 2012-02-14 13:56:40 -0500

Do you have gazebo_ros_controller_manager or an equivalent gazebo plugin in your simulated robot XML?

<gazebo>
  <controller:gazebo_ros_controller_manager name="gazebo_ros_controller_manager" plugin="libgazebo_ros_controller_manager.so">
    <alwaysOn>true</alwaysOn>
    <updateRate>1000.0</updateRate>
  </controller:gazebo_ros_controller_manager>
</gazebo>
edit flag offensive delete link more
0

answered 2015-06-29 23:17:47 -0500

jiangxihj gravatar image

you should stop the r_arm_controller use "rosrun pr2_controller_manager pr2_controller_manager stop CONTROLLER_NAME"

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2011-10-25 12:40:42 -0500

Seen: 1,633 times

Last updated: Feb 14 '12