-
Notifications
You must be signed in to change notification settings - Fork 35
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
JointPositionController and JointVelocityController misbehave when stopped and started #374
Comments
Regarding the velocity controller To illustrate the error this causes, I've only been able to use a python script, not only bash. This is probably due to timing. The demonstration below relies on a race condition so that The point is that, if
then At least on my setup, this reproduces the error reliably, but it does seem to rely on specific timing of a race condition, so perhaps run it a few times. here are the steps
You will see the wrist rotate in the positive direction for 5 secs, then it will quickly spin to joint angle [1] #!/usr/bin/python
import rospy
from pr2_mechanism_msgs.srv import LoadController, SwitchController, UnloadController, SwitchControllerRequest
import std_msgs.msg
import time
rospy.init_node("show_velocity_bug")
pos_ctrlr_name = "r_wrist_roll_position_controller"
vel_ctrlr_name = "r_wrist_roll_velocity_controller"
vel_publisher = rospy.Publisher("/"+vel_ctrlr_name+"/command", std_msgs.msg.Float64)
pos_publisher = rospy.Publisher("/"+pos_ctrlr_name+"/command", std_msgs.msg.Float64)
switch_controller = rospy.ServiceProxy('pr2_controller_manager/switch_controller', SwitchController)
def set_velocity(vel):
print("Set velocity to %f"%vel)
assert(
switch_controller( start_controllers=[vel_ctrlr_name],
stop_controllers=[pos_ctrlr_name],
strictness=SwitchControllerRequest.STRICT)
)
vel_publisher.publish(vel)
def set_position(pos):
print("Set position to %f"%pos)
assert(
switch_controller( start_controllers=[pos_ctrlr_name],
stop_controllers=[vel_ctrlr_name],
strictness=SwitchControllerRequest.STRICT)
)
pos_publisher.publish(pos)
#weirdly the first set_velocity command doesn't work.
set_velocity(0.0)
time.sleep(1.0)
set_velocity(1.0)
time.sleep(5.0)
set_position(0.0)
#wait some time for `dt_` to get huge.
time.sleep(5.0)
set_velocity(-1.0)
time.sleep(10.0) [2] which happens here:
|
If these controllers are stopped and then started later (without unloading and loading), then its
update
function is called and within it, thedt_
passed to theupdatePid
function is a very large value, which means that if there is any error at all, the integrator will likely become saturated in one step.What happens is that the commanded effort will jump when you start the controllers. At first I thought perhaps the controller manager was still calling the update loop, causing the integrator to accumulate error, but the controller manager is working properly.
The text was updated successfully, but these errors were encountered: