-
Notifications
You must be signed in to change notification settings - Fork 119
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
issues with teleoperation #194
Comments
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 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 |
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 :
In the numerical values we notice that when starting from the pose :
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 :
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
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. Your thoughts would be greatly appreciated! |
Alright, I think I got your point. The magic offset of about Could you maybe
|
Hi @stefanscherzinger , sorry for the delay, here is the information :
Here is the config :
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 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 Let me know your thoughts! |
Regarding teleoperation, yes we would prefer a closed loop approach. I tried the On trying the teleoperation with my teleop device (which returns its pose at ~130 Hz) I can differentiate to get velocity and following the
With the
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 |
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. 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! |
Yes, this is right. This is how the
I suggest using the
On first sight, this should work. Do the controllers publish warnings or similar? |
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
The text was updated successfully, but these errors were encountered: