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

Interpolated Position mode not producing motion

asked 2018-02-07 11:11:34 -0600

JadTawil gravatar image

updated 2018-02-08 19:02:46 -0600

Hello all. I am attempting to run my controller in IP mode using ros-canopen but the motor fails to start motion. I am using a joint_trajectory_controller to command the controller. The controller works as expected in PP and PV modes.

I am troubleshooting by publishing the object 60C1sub1 (interpolation data record) and 6062 (Position demand value).

In PP mode, object 607A updates and 6062 updates to reflect the commanded postion shortly after. The motor moves, as expected.

In IP mode, 60C1sub1 updates as expected when a trajectory is commanded via the joint_trajectory_controller topic interface, however, 6062 does not update, and consequently, the motor never moves.

I attempted to change the RPDO transmission type of 60C1sub1 from FF to 01. Both produce the same result however.

I am using a SYNC interval of 10 ms, and i have the interpolation time period set to 10 ms as well. I tried raising it to 50 ms, but that does not change the result.

To add, i am publishing the control word and status words using the SDO troubleshooting mechanism provided by ros-canopen (6040! and 6041!). Bit 4 in the control word, which activaltes the interpolation seems to be set. Bit 12 in the status word, which indicates interpolation active/inactive, is never set. So it seems that setting the interpolation to active is being a problem. Interestingly, the target reached bit is always set... Would this be preventing motion? Also, i tried running it through the action interface, via the terminal by publishing to /goal topic, and the goal status reported is 1 active, then 3 succeeded... but the motor never moves as the position demand value never changes. how can the trajectory controller report success if the joint_states never indicated that? that seems weird. could it be transmission types of PDO's?

I am able to run IP Mode via the software of the manufacturer. The only difference i perceive is that in that software, i am writing 1 value to the data record that is very far from the current value, the controller does the interpolation and goes there. However, through ROS, i am writing the values on a ramp via the traj controller and so overwriting the value constantly. This shouldn't be a problem tho, could it be...?

The maximum buffer size of the controller i am using is 1. Could this be an issue?

Essentially, when the drive initializes, it sets bit4 in control word, which is correct, but bit 12 in status word,which indicates that ip mode is active, is never set ...

See below the terminal output of the statusword, control word, and mode display, as printed using the periodic printing provided by ros-canopen for debugging. The init service is called, and the following is outputted:

Status      Control    Mode Display

data: 38455 data: 271   data: 6   #Operation Enabled, Interpolation active

data: 38455 data: 271   data: 6

data: 38455 data: 271   data: 6

data: 38455 data: 271   data: 6

data: 38455 data: 271   data: 6

data ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-02-08 14:59:09 -0600

JadTawil gravatar image

updated 2018-02-09 08:21:45 -0600

The problem was resolved.

According the the DSP 402 protocol, if the halt bit is 1, bit 4 of the control word is not executed in IP mode, and therefore IP mode is not activated, and therefore the axles don't move.

It seems that ros-canopen sets the halt bit to 1 in line 413 of the Handlewrite function in the canopen_402/motor.cpp code and only clears it if the state is Operation Enabled.

For my controller (nanotec controller), the mode cannot be switched in OE state, the controller has to transition to Switched on, or Ready to Switch on, or Switch on disabled states to perform a mode switch. ros-canopen accounts for such controllers by allowing you to switch states on initialization to set the desired mode of operation (IP mode in my case). When the state was switched down from OE, the handlewrite was setting the halt bit in the control word.

Another factor was that the RPDO for the control word i had with transmission type FF, rather than 01. This was done because when i set the transmission type to 01, roscanopen fails to initialize with the error "Could not enable motor", which is a result of failing to transition to OE state. The only way i managed to get past that error was to set RPDO transmission to FF for the control word.

So because the RPDO is asynchronous, the last time the controller processed the control word was when the halt bit was set to "1".

You can see this in the post above. The control word was being written as 31 (1111 binary) with bit 4 set to 1, but the controller was ignoring it because it is asynchronous PDO, so the last time it processed it the halt bit was set, and so IP was never activated.

I solved this by commenting out the setting of the halt bit in line 413 of motor.cpp.

This problem would not have occured if my controller was able to switch modes in OE State.

I caution users. IF your controller cannot switch modes in OE State, AND you want to use IP mode, AND you have the transmission type of the control word RPDO set to FF, this issue might occur to you, and you might solve it the way i did, or find a better way.

what ramifications does my solution have to the general operation of the controller? Is there a smarter way of doing this?

Thanks.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-02-07 11:11:34 -0600

Seen: 333 times

Last updated: Feb 09 '18