Gazebo: Arm falls on start after switch to Effort Controllers #651
Replies: 5 comments
-
I agree with the original post. I noticed the same issues when using the UR launch files. |
Beta Was this translation helpful? Give feedback.
-
We'll need to look into that... |
Beta Was this translation helpful? Give feedback.
-
same issue here. $ roslaunch ur_gazebo ur5e_bringup.launch The robot arm starts at a weird pose and moveit doesn't generate proper movements. Cheers |
Beta Was this translation helpful? Give feedback.
-
@ian-chuang @tommyvtran97 @stevensu1838 Sorry for the delayed response. I had a look into the mechanisms of startup and came to the following conclusions: BackgroundIt seems true, that this issue only appeared after switching to ProblemThe issue I see at startup is roughly like this:
WorkaroundThe most reliable approach for me is to start gazebo in paused mode, e.g. with roslaunch ur_gazebo ur5e_bringup.launch paused:=true and once Gazebo is up, I set the important parameters via its command line instructions in a new terminal gz physics -g 0,0,0 # set gravity to zero
gz world -p 0 # unpause the engine. This triggers the controller_manager and the robot should stay where it started.
gz physics -g 0,0,-9.81 # reset gravity to its original value I also experimented with setting |
Beta Was this translation helpful? Give feedback.
-
Hello, I am having the same issue running on Ubuntu20.04 with Noetic and the universal_robot packages installed via apt (v1.3.1). The workaround does work, but fixing the launch would be prefereable, is there any update on this? Would be glad to help set this up if theres any ideas on where to start? |
Beta Was this translation helpful? Give feedback.
-
When launching ur5e_bringup.launch on ur_gazebo on branch melodic-devel-staging, the robot immediately falls when Gazebo starts. The arm can be controlled just fine but needs to be brought back up from where it fell. I think this is due to the recent change to using effort controllers instead of position controllers (#619). When using position controllers (without setting pids in gazebo_ros_control), the robot will start at its designated initial position. However effort controllers are needed for doing realistic grasps. Is there a way to fix this?
I am using ROS noetic on WSL.
Beta Was this translation helpful? Give feedback.
All reactions