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

Revolute joint disobeying limits in Gazebo

asked 2023-02-22 09:34:05 -0500

Adude gravatar image

I have a revolute joint being controlled by a custom ros2 controller which is setting the joints position. When the position is set by the controller I would expect Gazebo to handle moving the joint to that position, obeying the velocity parameter in the limit tag of the joint URDF. If that were the case, then the joint would slowly move to the correct position, instead it instantaneously snaps to the desired position and none of the parameters (friction, damping, effort...) seem to make any difference to this.

Is this how it's supposed to work? Surely the controller just issues a command and the hardware interface is responsible for moving to that position? Or have I misunderstood entirely?

This is the joint

<joint name="lower_leg_joint" type="revolute">
  <parent link="upper_leg"/>
  <child link="lower_leg"/>
  <origin xyz="0 0 0" rpy="0 0 0" />
  <axis xyz="0 0 1"/>
  <limit effort="1000.0" lower="${-pi/3}" upper="${pi/3}" velocity="0.1"/>
</joint>

and this is the ros2_control URDF

<ros2_control name="GazeboSystem" type="system">
    <hardware>
        <plugin>gazebo_ros2_control/GazeboSystem</plugin>
    </hardware>

    <joint name="lower_leg_joint">
        <command_interface name="position"/>
        <state_interface name="velocity"/>
        <state_interface name="position"/>
    </joint>
</ros2_control>

<gazebo>
    <plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
        <parameters>./config/controllers.yaml</parameters>
    </plugin>
</gazebo>
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2023-02-23 17:15:33 -0500

shonigmann gravatar image

updated 2023-02-23 17:29:58 -0500

the gazebo_ros2_control position control interface implementation sets joint positions directly. There's no underlying controller - no PID, no bang-bang. You give it a position, and it automagically sets the simulated joint to that position (relevant code here). This will disregard physics, joint limits whatever.

There are at least two approaches if you want a more reasonable "control response". You could either:

a) generate joint trajectories that follow a smooth path and look good, and continue to use the position interface. If you look carefully, the joint would still be "snapping" to each of the intermediate positions, but it would effectively animate the desired motion. You have the added benefit here that things should do exactly what you tell them to do; no controller tuning required, no overshoot, etc. This is probably the intended purpose of the position interface in gazebo - for kinematic simulation. There are a number of tools that can do trajectory generation for you (e.g. moveit, ruckig), or you can write your own for your own needs.

b) if you care about dynamics, you'll want to use the velocity or ideally effort command interface, and have a controller that is tuned to get the the response you're expecting. Like the position interface, the velocity and effort control interfaces are "naive" in that they don't care about higher order limits. The velocity interface doesn't care about acceleration/effort limits, and the effort interface won't care about jerk limits. I don't even think they respect their own limits (e.g. I don't believe anything stops you from setting a higher velocity than the specified joint velocity limit). Anyways, depending on the complexity of your simulated hardware this could be simple or quite involved. For instance, the Gazebo physics engine struggles a bit with serial chain manipulators and creating a stable controller for that might involve a fair bit of tuning gains and the physics settings. If you go this route, the ros2_controllers package has some controller templates that you might find useful for this (e.g. the admittance controller or the joint_trajectory_controller which supports PID parameters to output velocity/effort)

edit flag offensive delete link more

Comments

Perfect, thanks

Adude gravatar image Adude  ( 2023-02-23 17:28:05 -0500 )edit

Question Tools

Stats

Asked: 2023-02-21 10:45:40 -0500

Seen: 603 times

Last updated: Feb 23 '23