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

Strange behavior and instability of six-axis manipulator in ROS 2 with Gazebo(Classic) when using position control

asked 2023-05-31 04:57:36 -0500

Roskuttan gravatar image

updated 2023-05-31 10:13:51 -0500

Hello Ros Community,

Description: I am currently in the process of developing a six-axis manipulator in ROS 2, utilizing MoveIt 2 for motion planning and Gazebo for simulation. Regrettably, I am facing a perplexing issue where the manipulator demonstrates peculiar behavior and instability, particularly when I employ position control as the command interface in Gazebo. To provide further clarity, I have included relevant visuals,launch files and urdf that can be accessed HERE.

I am using ROS2 Humble

To provide more context and aid in troubleshooting, here are the details related to the problem:

I am using the following launch file to start the Gazebo simulation and relevant ROS nodes:

ros2 launch hexa_bot_description gazebo.launch.py use_sim_time:=true

When executing the gazebo.launch.py launch file, the following log messages are displayed:

[spawn_entity-5] /opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/qos.py:307: UserWarning: DurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL is deprecated. Use DurabilityPolicy.TRANSIENT_LOCAL instead. [spawn_entity-5] warnings.warn( [ros2-7] Sucessfully loaded controller joint_state_broadcaster into state active [ros2-6] Sucessfully loaded controller arm_controller into state active

edit retag flag offensive close merge delete

Comments

I'm also having such issues in my project someone help me with a solution it's so urgent I'm at the deadline of my project

Gio gravatar image Gio  ( 2023-05-31 05:01:46 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2023-05-31 06:47:12 -0500

danzimmerman gravatar image

Assuming this is Gazebo Classic (as opposed to the new Gazebo, formerly Ignition) I suspect this is the same as https://github.com/UniversalRobots/Un...

There's a lot of detail there but I'll briefly summarize for the forum here.

In ROS 1, gazebo_ros_control set the Open Dynamics Engine dParamFmax parameter here. This parameter is used in ODE joint motors:

http://ode.org/wiki/index.php/Manual#...

Joint motors solve all these problems: they bring the body up to speed in one time step, provided that does not take more force than is allowed

The gazebo_ros2_control plugin, as far as I can tell, does not set this parameter right now and IIRC it defaults to zero.

Because of the way passive joint friction is implemented in ODE, a joint motor with zero speed and a max force, a workaround for active joints without building gazebo_ros2_control from source is to add a joint <dynamics> tag to your URDF with the friction parameter set to some suitable value for this maximum joint motor force parameter.

gazebo_ros_control set the dParamFmax or fmax parameter to the joint effort limit. IMO, theoretically, it should probably be higher than that with joint effort limits enforced in some other way, but practically either should work fine for simulation.

edit flag offensive delete link more

Comments

I would like to extend my deepest gratitude for the outstanding solution you provided to our problem. The inclusion of the dynamics tag, incorporating friction and damping, in my code has had a remarkable impact. The manipulator now remains stationary as intended, which is exactly the behavior I had anticipated. Your willingness to address my inquiries has been incredibly beneficial. Your contribution, particularly the integration of the dynamics tag, has made a significant and valuable difference. I cannot express enough how grateful I am for your assistance.

Roskuttan gravatar image Roskuttan  ( 2023-05-31 08:30:09 -0500 )edit

This solved my issue as well. Thank you so much. @danzimmerman and @Roskuttan. :)

Aki1608 gravatar image Aki1608  ( 2023-06-06 02:37:36 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2023-05-31 04:57:36 -0500

Seen: 251 times

Last updated: May 31 '23