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

Applying apply_joint_effort and apply_body_wrench

asked 2011-03-16 00:06:27 -0600

mbj gravatar image

updated 2012-02-27 07:37:22 -0600

kwc gravatar image

Hi again.

I'm simulating in Gazebo the R2D2 robot from this tutorial (although there is no link in this page, I dowloaded all the urdf tutorials stacks and there is a model called 07-physics.urdf with the correct physics of the robot).

I'm trying to apply some forces to the joints to interact with the robot using /apply_joint_effort and /apply_body_wrench.

First, I spawn the robot:

rosrun gazebo spawn_model -urdf -file 07-physics.urdf -model r2d2 -z 0.5

Next, I make a shell script that executes the next orders:

rosservice call /gazebo/apply_joint_effort '{joint_name: "left_back_wheel_joint", effort: -0.2, start_time: 0, duration: -1 }'
rosservice call /gazebo/apply_joint_effort '{joint_name: "left_front_wheel_joint", effort: -0.2, start_time: 0, duration: -1 }'

I obtained the following possible answers:

  • The robot turns a little to the right before hitting the ground and go straight. (Most common).
  • The robot is rotating to the right while moving in a "straight" direction.
  • The robot dumps (also quite common xD).

I tried to change the start time (setting to 5, 10...) and the duration (setting to 50000, 500, 50...), but the response is always the same. I think that the correct answer would be that the robot will rotate on itself pivoting on the imaginary axis of the right wheels.

What I doing bad? Thanks!

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2011-03-23 23:28:07 -0600

mbj gravatar image

The answer wasn't the correct because I didn't apply a correct contact propierties of the wheel (friction coefficients, contact stiffnes and contact damping, explained here and here). When this was solved, the answer was the expected.

Although this, I only obtain correct responses when the duration time was -1 (infinite). When I set the duration_time or start_time to any positive valor (like 50) Gazebo worked as if it had been set to infinity.

edit flag offensive delete link more
0

answered 2011-03-25 06:42:43 -0600

hsu gravatar image

Default friction coefficients are too high on the wheels, forcing the robot to go straight. Try adding this block:

<gazebo reference="right_back_wheel">
  <mu1 value="1.0" />
  <mu2 value="1.0" />
</gazebo>
<gazebo reference="left_back_wheel">
  <mu1 value="1.0" />
  <mu2 value="1.0" />
</gazebo>
<gazebo reference="right_front_wheel">
  <mu1 value="1.0" />
  <mu2 value="1.0" />
</gazebo>
<gazebo reference="left_front_wheel">
  <mu1 value="1.0" />
  <mu2 value="1.0" />
</gazebo>

and applying slightly more efforts,

rosservice call /gazebo/apply_joint_effort '{joint_name: "left_back_wheel_joint", effort: -2, start_time: 0, duration: -1 }'

rosservice call /gazebo/apply_joint_effort '{joint_name: "right_front_wheel_joint", effort: 2, start_time: 0, duration: -1 }'

The robot should rotate in place.

Regarding robot dumping, can you obtain a backtrace of gazebo? Thanks.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2011-03-16 00:06:27 -0600

Seen: 1,490 times

Last updated: Mar 25 '11