Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Effort position controller fix #33

Merged
merged 3 commits into from
Jul 29, 2013

Conversation

davetcoleman
Copy link
Member

  • Added enforeJointLimits() function
  • Enforced joint limits at update() and starting() functions
  • Cleaned up joint_state_controller
  • Added .gitignore

This fixes a bug where if you start the controller and your current joint position is slightly outside the joint limits, the starting commanded position is also outside the limit, and the shortest_angular_distance_with_limits function returns an incorrect value of 2*PI instead of a small decimal. This causes the error to be very high and causes a lot of noise in the PID controller.

This bug is also issued here: ros/angles#2

@@ -122,7 +122,15 @@ void JointPositionController::setCommand(double cmd)

void JointPositionController::starting(const ros::Time& time)
{
command_.initRT(joint_.getPosition());
ROS_DEBUG_STREAM_NAMED("joint_position_controller","Starting '" << joint_.getName()
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'd rather not make log statements in code that will be executed in a realtime context. Rosconsole macros end up making system calls which trigger a switch from primary (realtime) to secondary (linux) mode.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'll happily remove this but isn't it ok for the constructor and this starting function to be non-realtime?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In the controller manager, starting and stopping a controller is done inside the realtime update() method. Controller construction and init()ialization is non-realtime ,though.

I just checked that the ControllerBase class documentation is not using the \name blocks present in other parts of ros_control. That, at least, can be improved:

/** \name Real-Time Safe Functions
*\{*/
...
/*\}*/


/** \name Non Real-Time Safe Functions
*\{*/
...
/*\}*/

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Improved ControllerBase documentation [here]((pal-robotics/ros_control@4e23e2c).

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Removed the debug output.

davetcoleman added a commit that referenced this pull request Jul 29, 2013
@davetcoleman davetcoleman merged commit 5e3ca7e into hydro-devel Jul 29, 2013
@davetcoleman davetcoleman deleted the effort_position_controller_fix branch July 29, 2013 16:56
po1 pushed a commit to po1/ros_controllers that referenced this pull request Feb 5, 2014
diff_drive: use backslashes in doxygen documentation
efernandez pushed a commit that referenced this pull request Apr 12, 2018
Create linear/quadratic meas cov model classes
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

2 participants