fzi-forschungszentrum-informatik / cartesian_controllers

A set of Cartesian controllers for the ROS1 and ROS2-control framework.
BSD 3-Clause "New" or "Revised" License
368 stars 109 forks source link

Setting up velocity controllers for UR10e robot, robot makes weird buzzing and vibrating sounds #76

Closed Mohatashem closed 1 year ago

Mohatashem commented 2 years ago

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:

  1. Write a controller.yaml file as below:
my_cartesian_compliance_controller:
    type: "velocity_controllers/CartesianComplianceController"
    end_effector_link: "$(arg prefix)tcp_coll"
    robot_base_link: "$(arg prefix)base_link"
    ft_sensor_ref_link: "$(arg prefix)tool0"
    compliance_ref_link: "$(arg prefix)tcp_coll"
    target_frame_topic: "/$(arg prefix)target_frame"
    joints: 
    - $(arg prefix)shoulder_pan_joint
    - $(arg prefix)shoulder_lift_joint
    - $(arg prefix)elbow_joint
    - $(arg prefix)wrist_1_joint
    - $(arg prefix)wrist_2_joint
    - $(arg prefix)wrist_3_joint

    stiffness:
        trans_x: 100
        trans_y: 100
        trans_z: 100
        rot_x: 5
        rot_y: 5
        rot_z: 5

    pd_gains:
        trans_x: {p: 0.07}
        trans_y: {p: 0.07}
        trans_z: {p: 0.07}
        rot_x: {p: 0.1}
        rot_y: {p: 0.1}
        rot_z: {p: 0.1}

    gravity:
         x: 0.0
         y: 0.0 
         z: 9.81

    tool: # should be in the ft_sensor_ref_link

        mass: 0.61
        com_x: 0.007
        com_y: -0.003
        com_z: 0.054

my_motion_control_handle:
   type: "cartesian_controllers/MotionControlHandle"
   end_effector_link: "$(arg prefix)tcp_coll"
   robot_base_link: "$(arg prefix)base_link"
   target_frame_topic: "/$(arg prefix)target_frame"
   joints: 
    - $(arg prefix)shoulder_pan_joint
    - $(arg prefix)shoulder_lift_joint
    - $(arg prefix)elbow_joint
    - $(arg prefix)wrist_1_joint
    - $(arg prefix)wrist_2_joint
    - $(arg prefix)wrist_3_joint
  1. Set the transmission_hw_interface arg in the load_ur10e.launch tohardware_inteface/VelocityJointInterfaceinstead of the defaulthardware_inteface/PositionJointInterface. [Doing arosparam get /robot_description` also confirms hardware_interface to be VelocityJointInterface]

  2. Launch the bringup and then my launch file to launch the cartesian controllers.

  3. Then run a rosservice call /controller_manager/list_controllers to list all the controllers and check whether the type and the hardware_interface are correct. See extract from the terminal:

name: "my_cartesian_compliance_controller"
state: "running"
type: "velocity_controllers/CartesianComplianceController"
claimed_resources: 
- 
hardware_interface: hardware_interface::VelocityJointInterface
resources: [ceiling_arm_elbow_joint, ceiling_arm_shoulder_lift_joint, ceiling_arm_shoulder_pan_joint, ceiling_arm_wrist_1_joint, ceiling_arm_wrist_2_joint, ceiling_arm_wrist_3_joint]

It seems that things are working, however the motion seems to be very damped and slow.

Observations

  1. Even after playing with different values of for error_scale, iterations and pd_gains [see yaml file above], the motion seems very damped and poorly responsive. Any pd_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.

  2. I began tests without a tool attached to the robot, and in that case, I could go higher in pd_gains than depicted above:

    pd_gains:
        trans_x: {p: 0.1}
        trans_y: {p: 0.1}
        trans_z: {p: 0.1}
        rot_x: {p: 3.0}
        rot_y: {p: 3.0}
        rot_z: {p: 3.0}

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).

  1. I performed this test on both the UR10e robots in the lab. The behaviour was similar.

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

stefanscherzinger commented 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:

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?

stefanscherzinger commented 1 year ago

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}
stefanscherzinger commented 1 year ago

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}
stefanscherzinger commented 1 year ago

Please re-open if still not working.