Closed Mohatashem closed 1 year ago
Hi @Mohatashem
Sorry for not responding earlier. I had to get my hands on a UR5e and test the velocity interface to confirm my previous experience from years ago. These are my thoughts and observations:
velocity_controllers/..
type should be in-contact manipulation. Some robots seem to have a higher control frequency when sending joint velocities. It's thus reasonable to assume higher overall stability in contrast to position_controllers/..
while being more responsive (faster) to reference inputs. However, this does not seem to work as straight forward with the URe series, as I would like.position_controllers/CartesianForceController
and the velocity_controllers/CartesianForceController
with my hands and tested the overall stability while forcing contact manually with the table surface on different spots.position_controllers/CartesianForceController
was easier to tweak with respect to the d
gains. For the velocity_controllers/CartesianForceController
, I did not find a gain that improved stability and left it to zero.iterations
should be 1
for velocity_controllers/..
. Choosing higher numbers increased the buzzing sound for me (with CartesianMotionControl
) but did not lead to faster response.It seems that things are working, however the motion seems to be very damped and slow.
If it's notably slower and more damped that the position_controllers/..
variant, then something is wrong. It should be very similar. Could you test the CartesianForceController
(which is easier to move around) and report if it's different on both control interfaces?
Given the buzzing sounds from the robot, I wonder if I am doing anything wrong or skipping any steps with regards to setting up the robot for VelocityJointInterface.
It think your setup is correct. The buzzing sound could indicate that you have high controller gains already, as you suggested. I would leave the d
gains at zero at first. The ranges for improving stability might be very thin and you might easily miss them. So it's important to test very small incremental steps.
What's your motivation for using the velocity interface?
Here's the config for the position_controllers/CartesianForceController
:
my_cartesian_force_controller:
type: "position_controllers/CartesianForceController"
end_effector_link: tool0
robot_base_link: base
ft_sensor_ref_link: tool0
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
solver:
error_scale: 0.7 # Can be higher in free motion.
iterations: 1
pd_gains:
trans_x: {p: 0.05, d: 0.005}
trans_y: {p: 0.05, d: 0.005}
trans_z: {p: 0.05, d: 0.005}
rot_x: {p: 1.50}
rot_y: {p: 1.50}
rot_z: {p: 1.50}
And here's the config for the velocity_controllers/CartesianForceController
:
my_cartesian_force_controller:
type: "velocity_controllers/CartesianForceController"
end_effector_link: tool0
robot_base_link: base
ft_sensor_ref_link: tool0
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
solver:
error_scale: 0.4 # In general more unstable than the position interface
iterations: 1
pd_gains:
trans_x: {p: 0.05} # Didn't find a d gain that notably improved stability
trans_y: {p: 0.05}
trans_z: {p: 0.05}
rot_x: {p: 1.50}
rot_y: {p: 1.50}
rot_z: {p: 1.50}
Please re-open if still not working.
Hello @stefanscherzinger,
I am trying to wrap my head around velocity controllers and wanted to see how would
velocity_controllers
or atleast velocity based compliance work on real robots (UR10e).Has anyone tested them for
cartesian_controllers
? How well does it work?I think I got it up and running but I would still request someone to confirm whether I am doing it correctly. When setting up velocity controllers (see extract from yaml file below). Is there anything else we need to do from the robot/controller side so that we have
VelocityJointInterface
up and running?This is what I have done so far:
Set the
transmission_hw_interface
arg in theload_ur10e.launch to
hardware_inteface/VelocityJointInterfaceinstead of the default
hardware_inteface/PositionJointInterface. [Doing a
rosparam get /robot_description` also confirms hardware_interface to be VelocityJointInterface]Launch the bringup and then my launch file to launch the cartesian controllers.
Then run a
rosservice call /controller_manager/list_controllers
to list all the controllers and check whether thetype
and thehardware_interface
are correct. See extract from the terminal:It seems that things are working, however the motion seems to be very damped and slow.
Observations
Even after playing with different values of for
error_scale
,iterations
andpd_gains
[see yaml file above], the motion seems very damped and poorly responsive. Anypd_gains
I set above the mentioned values in the above yaml cause the robot to do a buzzing sound (very little or without shaking). If the gains are increased further, these buzzing sounds are accompanied by oscillations, and further increase after it causes a violent shake and an emergency stop.I began tests without a tool attached to the robot, and in that case, I could go higher in
pd_gains
than depicted above:However, on attaching a tool, the robot does the buzzing, vibrating and shaking at otherwise decent pd values and hits a stop. Lowering the
pd_gains
does work, but the performance in terms of compliance and motion seems poor (slow motion, highly damped response to force).Q. Given the buzzing sounds from the robot, I wonder if I am doing anything wrong or skipping any steps with regards to setting up the robot for
VelocityJointInterface
. Is there anything else I should be looking at or missing something important?Thank you