Open shrutichakraborty opened 2 months ago
@shrutichakraborty
Thanks for investing your time in this! You are right, what you experience is the difference between closed loop control and open loop control. See my explanation to your previous question. And yes, closed loop only works if the robot is fast enough in tracking the target_frame
. Tweak that behavior as desired.
You are also right that teleoperation should involve some sort of closed loop control. In many use cases, the human teleoperator does that implicitly, checking e.g. with visual feedback their control commands. For your mentioned reasons, I personally prefer to teleoperate my robots with the cartesian_force_controller
. This is more intuitive and there's no delay. The robot stops when I stop. The example from the cartesian_controller_utilities
package is here (ROS2).
@shrutichakraborty
Thanks for investing your time in this! You are right, what you experience is the difference between closed loop control and open loop control. See my explanation to your previous question. And yes, closed loop only works if the robot is fast enough in tracking the
target_frame
. Tweak that behavior as desired.You are also right that teleoperation should involve some sort of closed loop control. In many use cases, the human teleoperator does that implicitly, checking e.g. with visual feedback their control commands. For your mentioned reasons, I personally prefer to teleoperate my robots with the
cartesian_force_controller
. This is more intuitive and there's no delay. The robot stops when I stop. The example from thecartesian_controller_utilities
package is here (ROS2).
Hi @stefanscherzinger , thanks for your response, just to clarify the test that I mention in my comment refers to the open loop code similar to space_nav example where I publish pose_stamped messages to the controller no matter what :
def cb(self, data):
""" Incrementing self.pos in z direction by delta """
now = time.time()
# Position update
self.pos[2] += self.delta
In the numerical values we notice that when starting from the pose :
Starting robot pose : header: seq: 0 stamp: secs: 1714666389 nsecs: 654448271 frame_id: "base_link" child_frame_id: "tool0" transform: translation: x: -0.062304424988338866 y: 0.606872734959198 z: 0.42011388085505985 rotation: x: 0.928559706172538 y: -0.36729748129903694 z: 0.013257649279675543 w: 0.051900549512802034
The current real position of the robot only changes after the "theoretical" model position that we have been incrementing by delta has reached a value that is approximately 30-35 cm larger than the actual real robot position :
Z position sent : 0.7621138808550602 =============================================================================== current real robot Z position : 0.4201022769811397 current theoretical Z position : 0.7621138808550602 Z position sent : 0.7651138808550602 =============================================================================== current real robot Z position : 0.4200787156333022 current theoretical Z position : 0.7651138808550602 Z position sent : 0.7681138808550602 =============================================================================== current real robot Z position : 0.42011877450127083 current theoretical Z position : 0.7681138808550602 Z position sent : 0.7711138808550602 =============================================================================== current real robot Z position : 0.42068409298780646 current theoretical Z position : 0.7711138808550602 Z position sent : 0.7741138808550602 =============================================================================== current real robot Z position : 0.42121722309821574 current theoretical Z position : 0.7741138808550602 Z position sent : 0.7771138808550602
In the above situation, which the robot is physically at 0.4200 m in Z, we are commanding it to move to 0.7621 m in Z which is causing some movement in the robot, before that the real robot position was quite constant at about 0.4200 m... I have noticed this in different tests as well where until the difference does not reach about 30-35 cm the robot does not move.. I find this quite strange. I agree with you on your previous response that in case of small deltas, if the robot is not able to reach the incremented position fast enough and therefore has no effect, but even in the open-loop case we are actually commanding quite a large delta before the robot starts moving...
Regarding controller parameters, as you advised in my previous question , I have tried tweaking the parameters, I am currently using
stiffness: # w.r.t. compliance_ref_link
trans_x: 500
trans_y: 500
trans_z: 500
rot_x: 20
rot_y: 20
rot_z: 20
solver:
error_scale: 0.25 # up to 2.0 was nice in free space
iterations: 2
publish_state_feedback: True
pd_gains:
trans_x: {p: 0.05}
trans_y: {p: 0.05}
trans_z: {p: 0.05}
rot_x: {p: 1.5}
rot_y: {p: 1.5}
rot_z: {p: 1.5}
I had previously tried error scale of 0.5 with iterations from 1 - 5, of which values > 2 were causing my robot to vibrate.
Tuning the P gain values also cause vibration, I tried changing it to 0.08 and 0.1... trying D gain of 0.005 and 0.003 both increased vibrations. Also I must mention this setup is on ROS1 and we are not on a real-time kernel.
Your thoughts would be greatly appreciated!
Alright, I think I got your point. The magic offset of about 30 -35cm
is indeed weird. At the top of my head, I'm thinking of maybe there's something wrong with how the cartesian_compliance_controller
reports its current_pose
...
Could you maybe
Share some code that publishes the data that you print here? I'm particularly interested in how you compute the current theoretical and the position sent.
current real robot Z position : 0.4456996774910867 current theoretical Z position : 0.9541138808550603 Z position sent : 0.9571138808550603
Post the controller configuration for your controller? I'm interested in the links that you specify for end_effector_link
and compliance_ref_link
.
Hi @stefanscherzinger , sorry for the delay, here is the information :
- Share some code that publishes the data that you print here? I'm particularly interested in how you compute the current theoretical and the position sent.
class test:
""" Send PoseStamped messages to command the robot in cartesian space using
cartesian compliance controller. Motion is tested only in Z.
An initial TF lookup assures that the target pose always
starts at the robot's end-effector.
"""
def __init__(self):
rospy.init_node('converter', anonymous=False)
velocity = 0.1
rate_freq = 400/10
self.cnt = 0
self.delta = velocity/rate_freq
self.current_robot_pose_topic = "/current_pose"
self.pose_topic = "/target_frame"
self.frame_id = rospy.get_param('~frame_id', default="base_link")
self.end_effector = rospy.get_param('~end_effector', default="tool0")
self.rate = rospy.Rate(rospy.get_param('~publishing_rate', default=rate_freq))
self.tf_buffer = tf2_ros.Buffer(cache_time=rospy.Duration(3.0))
self.tf_listener = tf2_ros.TransformListener(self.tf_buffer)
self.rot = np.quaternion(0, 0, 0, 1)
self.pos = [0, 0, 0]
# Start where we are
if not self.startup():
sys.exit(0)
self.pub = rospy.Publisher(self.pose_topic, PoseStamped, queue_size=3)
self.sub = rospy.Subscriber(self.current_robot_pose_topic, PoseStamped, self.callback)
self.last = time.time()
self.cycle = 0
rospy.spin()
def startup(self):
try:
start = self.tf_buffer.lookup_transform(
target_frame=self.frame_id, source_frame=self.end_effector, time=rospy.Time(0), timeout=rospy.Duration(5))
except (tf2_ros.InvalidArgumentException, tf2_ros.LookupException,
tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException) as e:
rospy.logwarn(e)
return False
print("Starting robot pose : ", start)
self.pos[0] = start.transform.translation.x
self.pos[1] = start.transform.translation.y
self.pos[2] = start.transform.translation.z
self.rot.x = start.transform.rotation.x
self.rot.y = start.transform.rotation.y
self.rot.z = start.transform.rotation.z
self.rot.w = start.transform.rotation.w
return True
def callback(self, data : PoseStamped):
# Position update
print('===============================================================================')
print("current real robot Z position : ", data.pose.position.z)
print("current theoretical Z position : ", self.pos[2])
if abs(self.pos[2]) < 0.680:
self.pos[2] += self.delta
print(" Z position sent : ", self.pos[2])
self.publish()
def publish(self):
if not rospy.is_shutdown():
msg = PoseStamped()
msg.header.stamp = rospy.Time.now()
msg.header.frame_id = self.frame_id
msg.pose.position.x = self.pos[0]
msg.pose.position.y = self.pos[1]
msg.pose.position.z = self.pos[2]
msg.pose.orientation.x = self.rot.x
msg.pose.orientation.y = self.rot.y
msg.pose.orientation.z = self.rot.z
msg.pose.orientation.w = self.rot.w
try:
# pass
self.pub.publish(msg)
except rospy.ROSException:
# Swallow 'publish() to closed topic' error.
# This rarely happens on killing this node.
pass
if __name__ == '__main__':
conv = test()
Post the controller configuration for your controller? I'm interested in the links that you specify for end_effector_link and compliance_ref_link.
Here is the config :
cartesian_compliance_controller:
type: "position_controllers/CartesianComplianceController"
end_effector_link: tool0
robot_base_link: base_link
ft_sensor_ref_link: tool0
compliance_ref_link: tool0
target_frame_topic: "target_frame"
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
My conclusion was that there was some latency in the cartesian_compliace controller computing the real current pose from the hardware, I am not sure if that is a possibility.
Another thing, in the ros1 version the UR publishes the real end effector pose that it reads from the teach pendant in the tool0_controller
frame and the force torque sensor readings are also in the tool0_controller
frame. However, using this frame in the cartesian_compliance_controller configuration in the end_effector_link, ft_sensor_ref_link, and compliance_ref_link fields gives an error :
even though these frames are present in the tf tree :
Therefore, I had used tool0 frame.. but I am now wondering whether this causes issues ? On my physical robot, I have a screw driver attached to the end effector, and eventually the tcp will be at the end of the tool, although for now in testing phase I have set the tcp to be where the tool0
frame should be on the urdf i.e attached to the flange.
Let me know your thoughts!
You are also right that teleoperation should involve some sort of closed loop control. In many use cases, the human teleoperator does that implicitly, checking e.g. with visual feedback their control commands. For your mentioned reasons, I personally prefer to teleoperate my robots with the
cartesian_force_controller
. This is more intuitive and there's no delay. The robot stops when I stop. The example from thecartesian_controller_utilities
package is here (ROS2).
Regarding teleoperation, yes we would prefer a closed loop approach. I tried the spacenav_to_wrench
example, the performance is definitely better as I seem to have more control, the behaviour feels very similar to when moving the robot around by hand in compliance mode, i.e when the external force is removed the robot will try to return to its previous configuration.
On trying the teleoperation with my teleop device (which returns its pose at ~130 Hz) I can differentiate to get velocity and following the spacenav_to_wrench
example re-publish this velocity as a wrench. In this case again I see that the robot basically stays stationery. Here is a snippet of the force torque values sent to the robot :
wrench commanded : force:
x: -0.16858458714904312
y: -0.07543867430735474
z: 1.3851666876976025
torque:
x: 0.0
y: 0.0
z: 0.0
wrench commanded : force:
x: -0.22836552665639911
y: -0.10242707679412316
z: 1.6924396491351816
torque:
x: 0.0
y: 0.0
z: 0.0
wrench commanded : force:
x: -0.03219571215530468
y: -0.00779475116473081
z: 0.7757122683981977
torque:
x: 0.0
y: 0.0
z: 0.0
wrench commanded : force:
x: 0.011700179609400365
y: 0.03603595068149444
z: 0.9600743153079982
torque:
x: 0.0
y: 0.0
z: 0.0
wrench commanded : force:
x: 0.05866274061673663
y: 0.023318425887776554
z: 0.684146359000793
torque:
x: 0.0
y: 0.0
z: 0.0
wrench commanded : force:
x: 1.0221616416396115
y: 0.5983013694559559
z: 5.052978690636644
torque:
x: 0.0
y: 0.0
z: 0.0
wrench commanded : force:
x: 0.05129485062023167
y: 0.02835620297763527
z: 0.22725583843430397
torque:
x: 0.0
y: 0.0
z: 0.0
wrench commanded : force:
x: 0.1837357334698143
y: 0.27051196316952725
z: 2.4301523617529917
torque:
x: 0.0
y: 0.0
z: 0.0
wrench commanded : force:
x: -0.021529450231511017
y: 0.05016201647946125
z: 0.3636346540420611
With the spacenav_to_wrench
example, the velocities are of similar orders of magnitude :
---
header:
seq: 15905
stamp:
secs: 1715694407
nsecs: 689273595
frame_id: "tool0"
wrench:
force:
x: 0.01953125
y: -0.0078125
z: 0.0
torque:
x: 0.68359375
y: 0.1875
z: 0.19921875
---
header:
seq: 15906
stamp:
secs: 1715694407
nsecs: 696781635
frame_id: "tool0"
wrench:
force:
x: 0.9765625
y: -0.390625
z: 0.0
torque:
x: 3.41796875
y: 0.9375
z: 0.99609375
---
header:
seq: 15907
stamp:
secs: 1715694407
nsecs: 705043554
frame_id: "tool0"
wrench:
force:
x: 0.9765625
y: -0.390625
z: 0.0
torque:
x: 3.41796875
y: 0.9375
z: 0.99609375
---
header:
seq: 15908
stamp:
secs: 1715694407
nsecs: 713551282
frame_id: "tool0"
wrench:
force:
x: 0.01953125
y: -0.0078125
z: 0.0
torque:
x: 0.68359375
y: 0.1875
z: 0.19921875
---
header:
seq: 15909
stamp:
secs: 1715694407
nsecs: 729480504
frame_id: "tool0"
wrench:
force:
x: 0.9765625
y: -0.390625
z: 0.0
torque:
x: 3.41796875
y: 0.947265625
z: 0.99609375
---
header:
seq: 15910
stamp:
secs: 1715694407
nsecs: 736769676
frame_id: "tool0"
wrench:
force:
x: 0.9765625
y: -0.390625
z: 0.0
torque:
x: 3.41796875
y: 0.947265625
z: 0.99609375
---
header:
seq: 15911
stamp:
secs: 1715694407
nsecs: 745304107
frame_id: "tool0"
wrench:
force:
x: 0.9765625
y: -0.390625
z: 0.0
torque:
x: 3.41796875
y: 0.947265625
z: 0.99609375
---
header:
seq: 15912
stamp:
secs: 1715694407
nsecs: 752795934
frame_id: "tool0"
wrench:
force:
x: 0.9765625
y: -0.390625
z: 0.0
torque:
x: 3.41796875
y: 0.947265625
z: 0.99609375
Although there are points where the force/torque values is above 3N. I also tested this via dynamic reconfigure and it seemed that for small values before 1-2 N, sometimes the robot's motion was hardly noticeable. For your teleoperation tests did you mainly work with the space mouse ? Have you noticed similar behaviour as my case?
I am wondering whether republishing the calculated velocities as wrench is not the best way to go for my case as maybe they are too small for the robot to reach while in compliance mode and maybe adding a PID corrector loop on top could help? I also thought about using the cartesian_force_controller
for teleoperation, but having compliance is important to us as there will be cases where the robot is in contact with objects while being teleoperated. Let me know what you advise :)
Hi again @stefanscherzinger, I have been continuing experiments. While teleoperating in compliance mode and sending wrench stamped commands, I observe that once I stop moving the space mouse (the velocity values return to 0) and the robot returns back to its starting position, even at minimum stiffness values. To maintain the robot at a certain position, one has to keep sending commands via space mouse, otherwise the robot will return to its startposition. This is quite inconvenient for teleoperation in my case. When using cartesian_force_controller, when I send zero force commands, the robot stops moving and so I find it bizzare that in this case the robot will try to return to its start position. It seems that in the controller scheme, there is a desired position that is set to the starting position, and therefore the robot tries to return to it...
Could you tell me how I could avoid this and make the robot stay where it was teleoperated to?
So, far I have tried sending pose_stamped messages along with wrench_stamped messages, where the pose_stamped message is always the current_pose of the robot. Unfortunately this does not work. Looking forward to our response!
Hello! I had previously raised some concerns about recommended frequency for teleoperation #193, but upon further testing with the provided scripts I have noticed something quite strange :
In the
pose.py
script that serves to republish twist messages from space mouse as pose stamped messages, the startup function initialises the starting pose of the robot and initialises theself.pos
andself.rot
as follows :Throughout the teleoperation, the
self.pos
andself.rot
values are updated, however the current real pose of the robot is not kept track of, therefore after a few time cycles we may not be properly synchronised with the robot.I reused this code to write a different test code that publishes pose stamped messages to the robot (to simulate having a teleop device that directly communicates pose information). In this test, I treid two approaches :
First method: I have a subscriber that subscribes to the
current_pose
topic and I update the pose with a constant delta and publish this to the robot. I do not make any change to the orientation, and so it will stay the same as the initial orientation.In this test, the robot does not move. I tried delta values between 0.0009 to 0.05. I added a sleep of 1 second at the end as well, for a reasonably high delta (0.05 for instance) the robot move for a few mm, then stops moving.
2nd test : Comparatively, if I use exactly the code in
pose.py
and instead of resetting self.pos to current robot pose incremented by delta, then the robot moves as expected:So, I am wondering: why does the first method not work? Is it due to the fact that we are receiving and publishing at a high frequency, and if we republish the current position + increment, the robot fails to move to this position if the increment is quite small?
For the second method, this works but for teleoperation it is always better to have an idea of the current pose of the robot . For instance, if we make increments based on the initial pose of the robot, then after a few time cycles, isn't there a risk of loss of synchronisation between the real current pose of the robot and the theoretical one we update? For instance with the space mouse, teh robot doesn't immediately stop when no commands are sent, it sort of glides. Here are some numerical values from the test :
But something very strange is that there is a static error of about 35 cm between the real robot position and the theoretical one before the robot starts to move which seem really strange but I have noticed this in several tests..
Are there any suggestions from the team or anyone else who has tried teleoperation with these controllers? @stefanscherzinger
Thank you