ros-controls / gazebo_ros2_control

Wrappers, tools and additional API's for using ros2_control with Gazebo Classic
Apache License 2.0
193 stars 124 forks source link

Joints unable to maintain static position under PositionJointInterface #54

Open JaehyunShim opened 3 years ago

JaehyunShim commented 3 years ago

@ahcorde

Opening an issue thread as advised in this https://github.com/ros-simulation/gazebo_ros2_control/pull/44#issuecomment-773896959

According to @Briancbn's comment, the change made in the last commit around joint_limit_interface caused a problem that you can see in the videos from this comment which I also see from my simulated robot on Gazebo.

Any advice? Jaehyun

Briancbn commented 3 years ago

Thanks @JaehyunShim:)!

Could you change the issue title to "Joints unable to maintain static position under PositionJointInterface", which should be more descriptive.

Questions

Proposed solution

  1. Workaround There are several ways to workaround it. Currently, I created an additional gazebo plugin to help calling SetParam("fmax", 0, ) inside the Load() function, so that when joint_limit_interface is ready, I can simply remove my own plugin. You can also modify the gazebo_ros2_control to add in your own fix.

  2. Port joint_limit_interface

Karsten1987 commented 3 years ago

I am having trouble understanding why this behavior should be based on a joint limit interface. For me this actually just looks as if the PID values are off. The robot - in my case a simulated rrbot - moves somewhat appropriately with the effort interface.

JaehyunShim commented 3 years ago

@Briancbn

Adding simjoint->SetParam("fmax", 0, effort_limit_value); fixed the problem. However, as @Karsten1987 mentioned, if I only see the behaviour the robot shows, the problem looks to reside in a not enough P gain.

I have not tested the effort controller.

I will leave this issue thread open until the osrf team gives any comment or closes it.

Thank you very much, Jaehyun

Briancbn commented 3 years ago

I have not tested the effort controller.

It is not needed for effort controller. Check out ROS1 gazebo_ros_control comments.

Drojas251 commented 3 years ago

Thanks @JaehyunShim:)!

Could you change the issue title to "Joints unable to maintain static position under PositionJointInterface", which should be more descriptive.

Questions

  • Why is not setting fmax for hardware_interface/PositionJointInterface during runtime causing this behavior?
  • Why is <limit effort=""/> not automatically translated to max effort in gazebo? (It was always historically done by joint_limit_interface)
  • Why is rrbot demo not facing this problem with the same setup?

Proposed solution

  1. Workaround There are several ways to workaround it. Currently, I created an additional gazebo plugin to help calling SetParam("fmax", 0, ) inside the Load() function, so that when joint_limit_interface is ready, I can simply remove my own plugin. You can also modify the gazebo_ros2_control to add in your own fix.
  2. Port joint_limit_interface

@Briancbn Could you provide this gazebo plugin?

shonigmann commented 3 years ago
  • Why is not setting fmax for hardware_interface/PositionJointInterface during runtime causing this behavior?

Should there be a difference between setting fmax during runtime using a plugin and setting max_force in the urdf within <gazebo reference= tags to use the sdf specification? Doing the latter, I still get the same behavior, despite verifying that the urdf->sdf conversion included the tags. Perhaps gazebo ignores them?

Because setting fmax within the urdf didn't work for me, I tried to dig into just about every possible aspect of the robot model and the plugin to figure out what was causing this behavior on the UR manipulators but not other arms. My best guess for the source of the behavior boils down to how the ODE physics engine handles explicit spring-damper joints, applying velocities/forces to resolve the positions that the gazebo_ros2_control PositionJointInterface explicitly writes. I noticed that the joint separation issue can be largely corrected by adding <friction> and <damping> tags to each joint, which seems to validate this reasoning. This results in uncorrected oscillation of the joints, but at least keeps the robot from tearing itself apart.

Ultimately, the easiest "fix" I found was to use a different physics engine. ODE (with explicit damping) and Bullet both seem to result in the same faulty behavior. The DART engine with default settings worked as expected without any other changes to the robot's URDF.

For the reference of anyone having similar issues, you can easily select gazebo's physics engine either by specifying <physics type="dart"/> in a .world file or as an argument to gzserver.launch.py

shonigmann commented 3 years ago

We dug back into this issue, because we needed a ray sensor in our sim, and those are not yet supported by DART.

Long story short, we found that ODE seemed to work as expected (with the added friction and damping) when we ensured that every node had the use_sim_time parameter set to true. In our case, it was robot_state_publisher using the wall clock instead of gazebo's clock that caused some trouble. (Certainly a downside to the lack of global params in ros2 is that we have to be careful to assign the parameter everywhere.)

I wonder if others had verified that use_sim_time was set in all of their nodes?