ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

roscanopen + joint_trajectory_controller + Interpolated Position Mode

asked 2017-12-22 16:41:59 -0600

JadTawil gravatar image

updated 2017-12-22 16:44:40 -0600

I would like clarification regarding the control flow that occurs when a joint_trajectory_controller is used with ros-canopen to control motor controllers in Interpolated Position Mode (CanOpen drive mode).

Let's describe the situation. I am actually using three canopen DS402 servomotors to control a Parallel Delta Robot. I am using ROS and will interface ROS with the servo motors using ros-canopen.

the "required_drive_mode" field in the canopen_motor_node configuration is set to 7, to indicate to the joint_trajectory_controller that the canopen controllers are in interpolated position mode.

My understanding is that ros-canopen's control loop is specified by the SYNC interval, which i specify in the canopen_chain_node using the interval_ms parameter.

I would like to define a trajectory for my delta robot, which consists of three axes in interpolated position mode. The canopen controllers only support linear interpolation between setpoints, so the interpolation data records each consist of 1 target position. My confusion arises when thinking about the writing of the setpoints to the interpolation data buffer of the canopen controllers.

When i send the joint_trajectory_controller a trajectory with positions and timestamps (no velocity or acceleration for now), the trajectory controller will write the first position data to the canopen controllers at the specified time in the trajectory message, at the next SYNC interval (as controlled by ros-canopen). The controllers will receive this setpoint, and interpolate between current positon and the setposition and begin motion. In order to have smooth motion between setpoints, i have to load another interpolation data record into the interpolation data buffer before the execution of the current setpoint is complete. The problem, is that the joint_trajectory controller will not write another value to the hardware interface until the setpoint is complete. Would this not create a situation where the axles stop everytime a setpoint is reached and wait a small amount of time to receive another record. How can i get the joint_trajectory_controller to write a bunch of setpoints to the canopen controllers to ensure smooth transition from one linear interpolation to another...

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
0

answered 2017-12-27 04:04:47 -0600

Mathias Lüdtke gravatar image

In addition to the interpolation between current and target position, a drive in IP mode might extrapolate the motion for a limited amount of time. The overall behavior is determined by the maximum buffer size, buffer type, interpolation period and SYNC rate. The default implementation in canopen_402 should work for a buffer size of 1 and an interpolation period that matches to the SYNC interval.

There is no direct way to write a bunch of set-points, because this is not supported by all vendors. You could try to increase the interpolation period, but it might lead to overflow errors. As a last resort you could subclass Motor402 to provide a custom mode handler with a sophisticated buffer management.

edit flag offensive delete link more

Comments

Thanks Mathias. So using the trajectory_joint_controller on a IP mode controller should have smooth motion between the setpoints specified in the trajectories sent to the trajectory_joint_controller, if the interpolation period and SYNC interval match?

JadTawil gravatar image JadTawil  ( 2017-12-27 13:40:12 -0600 )edit

Yes, this should work. The trajectory_joint_controller will interpolate the trajectory (with splines) to generate set-points with the SYNC/update rate. And the drives will further interpolate between these small steps; or extrapolate if necessary.

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2018-01-08 08:06:44 -0600 )edit

Thanks Mathias.

JadTawil gravatar image JadTawil  ( 2018-01-10 07:03:44 -0600 )edit

Mathias, if i wanna use profile velocity for instance. I would map the velocity actual value (606C) to TxPDO, and the velocity target value (60FF) to RxPDO, in my controller. What do i do on the ros-canopen side?

JadTawil gravatar image JadTawil  ( 2018-01-10 08:39:32 -0600 )edit

This is a different topic.. You just have to set-up a velocity controller and set required_drive_mode: 3.

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2018-01-10 10:25:17 -0600 )edit

Hey Mathias. What transmission type for the RPDO do you set for the interpolation data record (60C1)? FF or 01? also, does IP mode require the mapping of anything other than 60C1, 6064, and the control/status words?

JadTawil gravatar image JadTawil  ( 2018-02-07 10:03:57 -0600 )edit

JadTawil, did you ever figure out how to do this successfully? My Elmo servo drives do not respond to ROS CANOpen commands in IP mode.

jxy gravatar image jxy  ( 2019-01-14 14:38:54 -0600 )edit

do you have 60C1 set as an RPDO, what transmission type are you using ?

JadTawil gravatar image JadTawil  ( 2019-01-15 18:29:04 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2017-12-22 16:41:59 -0600

Seen: 1,058 times

Last updated: Dec 27 '17