-
Notifications
You must be signed in to change notification settings - Fork 525
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
Conversation
@@ -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() |
There was a problem hiding this comment.
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.
There was a problem hiding this comment.
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?
There was a problem hiding this comment.
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
*\{*/
...
/*\}*/
There was a problem hiding this comment.
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).
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Removed the debug output.
Effort position controller fix
diff_drive: use backslashes in doxygen documentation
Create linear/quadratic meas cov model classes
update()
andstarting()
functionsThis 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