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

ros_canopen dcf_overlay setting

asked 2016-12-30 02:29:29 -0600

Craig gravatar image

updated 2016-12-30 02:57:01 -0600

Hi,

I'm using ros_canopen to control my robot.

The joint_position_controller works but I get stuck with joint_trajectory_controller. I set PDO mapping through dcf_overlay :

dcf_overlay:
    "1600sub0": "2"
    "1600sub1": "0x60400010" # map Control Word to RPDO1
    "1600sub2": "0x60c10120" # map 60c1sub2(position for PVT mode) to RPDO1
    "1601sub0": "2"
    "1601sub1": "0x60400010" # map Control Word to RPDO2
    "1601sub2": "0x60600008" # map 0x6060(mode of operation) to RPDO2
    "60c0": "0x0000" # map Interpolation submode 0:Linear interpolation with constant time

The candump message confused me because:

$ candump can0 -dcex |grep 201 # candump RPDO1
   can0  TX - -  201   [6]  04 00 AA 32 00 00
$ candump can0 -dcex |grep 301 # candump RPDO2
   can0  TX - -  301   [3]  1F 01 07 # halt the drive?
   can0  TX - -  301   [3]  1F 00 07
   can0  TX - -  301   [3]  1F 01 07  # halt the drive?
   can0  TX - -  301   [3]  1F 00 07
   ...

1.How come the first two bytes of the RPDO1 message differ with that of RPDO2 since they both are mapped to control word?

2.$ candump can0 -dcex |grep 201 showed that the position data were successfully sent to CAN bus. But the robot didn't move. Control word 1F 01 seems to be halting the drive and indicates the operation mode is profile position mode(see Copley Manual P58). Is it a problem?

Thank you in advance.

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
3

answered 2016-12-30 04:13:47 -0600

Mathias Lüdtke gravatar image

updated 2016-12-30 08:26:13 -0600

Mapping an object to multiple PDOs is not supported ( https://github.com/ros-industrial/ros... ). Each object can only be mapped once, not even twice within the same PDO.

edit flag offensive delete link more

Comments

Thank you. Now I've changed the PDO mappings(github.com/Linkeway/BIRL_modular_robot/blob/master/birl_module_canopen/config/manipulator5d_motors.yaml).abort60c1#1, reason: Invalid value for parameter (download only) showed up during initialization. I set DefaultValue for 60c1#1 in dcf. No luck.

Craig gravatar image Craig  ( 2016-12-30 07:34:11 -0600 )edit

candump showed

can0  TX - -  601   [8]  23 C1 60 01 00 00 00 00
can0  RX - -  581   [8]  80 C1 60 01 30 00 09 06
Craig gravatar image Craig  ( 2016-12-30 07:59:26 -0600 )edit

Looks like your PDO mapping was not applied correctly. Please fix doubled object in https://github.com/Linkeway/BIRL_modu... And all other doubled configs.

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2016-12-30 08:23:42 -0600 )edit

In addition your DCF is wrong: https://github.com/Linkeway/BIRL_modu... It even misses the 140x entries.

Please use CANeds

And: using the Schunk DCF as a template might be error prone, too!

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2016-12-30 08:44:10 -0600 )edit

You are right. I used the Schunk DCF because the Copley eds was faulty. I use a modified Copley eds now, and initialization produces:

[ERROR]:canopen_master/src/pdo.cpp(372): Throw in function void canopen::PDOMapper::Buffer::write(const canopen::ObjectDict::Entry&, const canopen::String&)
Craig gravatar image Craig  ( 2016-12-31 02:56:20 -0600 )edit

Dynamic exception type: boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<std::bad_cast> > std::exception::what: std::bad_cast [canopen::tag_objectdict_key*] = 60c1sub1

Craig gravatar image Craig  ( 2016-12-31 03:01:45 -0600 )edit

Your DCF contains a wrong object type for 60c1, please use CANeds to validate your DCF against 301 and 402 standard and fix all warnings.

Update: The object type should work as well, not sure why you get the size mismatch..

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2016-12-31 07:15:25 -0600 )edit

Question Tools

3 followers

Stats

Asked: 2016-12-30 02:29:29 -0600

Seen: 705 times

Last updated: Dec 30 '16