UTNuclearRoboticsPublic / jog_arm

A real-time robot arm jogger.
45 stars 22 forks source link

Support for position controlled robots? #85

Closed gavanderhoorn closed 5 years ago

gavanderhoorn commented 5 years ago

Forgive me if this has been asked before (and feel free to close this and point to earlier issues), but I'm trying to figure out how well position controlled robots are supported by jog_arm.

The system I'm considering to use jog_arm with has a ros_control stack setup with a position_controllers/JointGroupPositionController controller and a position_controllers/JointTrajectoryController configured. No velocity or effort control is supported. Everything runs at 125 Hz (similar to a non-e-series UR).

It's also a finicky system, and as position_controllers/JointGroupPositionController is a forward-commanding controller, jog_arm would have to provide properly spaced (in time and space) position setpoints which fall within the velocity and acceleration capabilities of the robot (it should essentially close the loop).

Reading the code I have the impression that there could be support for a JointGroupPositionController, but I'm not sure and would like to get this confirmed before diving into this package more. I guess that if there is support, the target positions sent to the robot driver (ie: JointGroupPositionController) would be absolute positions, not increments (but I'd also like to make sure).

And of course I could setup a simulation of this system and see how things work, but due to time constraints that is not a luxury I have unfortunately.

gavanderhoorn commented 5 years ago

Saw #11 and that gave me hope.

AndyZe commented 5 years ago

I'm 99% sure I've done this on a position-controlled UR robot before and it was fine, but I'll try again and let you know. Hopefully by the end of today.

AndyZe commented 5 years ago

Good news, a JointGroupPositionController did work on my UR3. Here was the config file:

gazebo: false # Whether the robot is started in a Gazebo simulation environment collision_check: false # Check collisions? command_in_type: "unitless" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s scale: # Only used if command_in_type=="unitless" linear: 0.002 # Max linear velocity. Meters per publish_period. Units is [m/s] rotational: 0.004 # Max angular velocity. Rads per publish_period. Units is [rad/s] joint: 0.01 # Max joint angular/linear velocity. Rads or Meters per publish period. Units is [rad/s] or [m/s]. cartesian_command_in_topic: /jog_arm_server/delta_jog_cmds # Topic for xyz commands joint_command_in_topic: /jog_arm_server/joint_delta_jog_cmds # Topic for angle commands command_frame: base_link # TF frame that incoming cmds are given in incoming_command_timeout: 1 # Stop jogging if X seconds elapse without a new cmd joint_topic: joint_states move_group_name: manipulator # Often 'manipulator' or 'arm' lower_singularity_threshold: 30 # Start decelerating when the condition number hits this (close to singularity) hard_stop_singularity_threshold: 45 # Stop when the condition number hits this lower_collision_proximity_threshold: 0.1 # Start decelerating when a collision is this far [m] hard_stop_collision_proximity_threshold: 0.005 # Stop when a collision is this far [m] planning_frame: base_link # The MoveIt! planning frame. Often 'base_link' low_pass_filter_coeff: 2. # Larger --> trust the filtered data more, trust the measurements less. publish_period: 0.008 # 1/Nominal publish rate [seconds] publish_delay: 0.005 # delay between calculation and execution start of command collision_check_rate: 5 # [Hz] Collision-checking can easily bog down a CPU if done too often. warning_topic: jog_arm_server/warning joint_limit_margin: 0.1 # added as a buffer to joint limits [radians]. If moving quickly, make this larger. command_out_topic: /joint_group_pos_controller/command command_out_type: std_msgs/Float64MultiArray publish_joint_positions: true publish_joint_velocities: false publish_joint_accelerations: false

AndyZe commented 5 years ago

The code does check joint velocity limits, currently, but not accelerations. One thing you could do is crank up low_pass_filter_coeff if acceleration limits are problematic. That will dampen motion.

gavanderhoorn commented 5 years ago

Thanks. I'll try setting things up next week.

The code does check joint velocity limits, currently, but not accelerations. One thing you could do is crank up low_pass_filter_coeff if acceleration limits are problematic. That will dampen motion.

It's even worse: the robot requires constant jerk limited trajectories. I'll see if the filter keeps things inside the limits.

gavanderhoorn commented 5 years ago

Ok so I tested this. The good news: support for position controlled robots is definitely there. Configuring jog_arm for just publish_joint_positions: true outputs the proper data (I guess you already knew that).

Unfortunately my robot is just too finicky, and immediately faults out on the first bit of noise on the position commands (2nd derivatives show rather large spikes on all axes).

Also unfortunately: I'm not a control engineer, so some of what is going on inside jog_arm is black magic to me. I've got low_pass_filter_coeff at rather large values (double digits), and it does seem to smooth things out, but can't prevent the jumps in the position commands I'm seeing apparently.

AndyZe commented 5 years ago

I'm sorry to hear that, thanks for trying. What I should do is use the Reflexes library to smooth these commands. http://www.reflexxes.ws

gavanderhoorn commented 5 years ago

Yes, relfexxes is nice, but only type 5 is jerk limited and that is not open-source (or available any more afaik).