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

ROS Control Computing Error Incorrectly with Negative Joint Limits on a Revolute Joint

asked 2020-07-01 14:28:44 -0500

pmnev gravatar image

Hi,

I am attempting to use the ros_control effort_controllers/joint_position_controller to control a single revolute joint with limits in Gazebo 7. I am running Ubuntu16.04 with ROS Kinetic. What I noticed happening is immediately on unpausing the simulation, the controller outputs a maximum command.

The joint is defined as follows in the URDF:

<joint
name="joint1"
type="revolute">
<origin
  xyz="0 0 0.01"
  rpy="0 0 -1.5708" />
<parent
  link="base_link" />
<child
  link="link_1" />
<axis
  xyz="0 0 1" />
<limit
  lower="-3.6652"
  upper="3.6652"
  effort="10.0"
  velocity="0.5" />
<dynamics damping="0.1" friction="0.0"/></joint>

I looked at the controller state and noticed something very strange - the error was calculated as close to 2pi for a setpoint of 0.0 and a process-value of -1.09322889816e-05. This is not what I expected to occur.

Here is a snapshot of a controller state message:

header: 
  seq: 0
  stamp: 
    secs: 0
    nsecs:   2000000
  frame_id: ''
set_point: 0.0
process_value: -1.09322889816e-05
process_value_dot: -0.000142460010446
error: -6.28317437489
time_step: 0.001
command: -63460.0611864
p: 100.0
i: 0.01
d: 10.0
i_clamp: 0.0
antiwindup: False

What this results in is entirely unstable behavior - the link rotates and hits the limit very quickly. If I change the joint to be in entirely positive limits, then I do not have any such issues. Also, this does not occur if I change it to a continuous joint. Is the proper way to use these controllers to specify a continuous joint in the urdf and then specify the joint limits using the joint_limits_interface? I would appreciate an explanation for how to mitigate this without having to a) change joint limits and b) changing to a continuous joint (unless that is required).

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-07-01 17:44:20 -0500

pmnev gravatar image

Solved?

Issue was: https://github.com/ros-controls/ros_c...

Is there a way to implement this change on Kinetic?

So far the only way I found to resolve this issue was to change the limits to be between -PI and +PI, which works for the time being. I guess I will update my OS+ROS version soon anyways, and hopefully the issue is fixed there.

edit flag offensive delete link more

Comments

1

You could consider building melodic-devel of the ros_control and ros_controllers repositories from source in your workspace.

They should build on Kinetic (I do this myself).

You'll probably need to enable C++11 or C++14 while building.

gvdhoorn gravatar image gvdhoorn  ( 2020-07-02 02:43:52 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-07-01 14:28:44 -0500

Seen: 356 times

Last updated: Jul 01 '20