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

Difference between kacanopen and ros_canopen?

asked 2017-03-20 23:50:34 -0600

rmck gravatar image

updated 2017-03-22 16:34:33 -0600

I'm attempting to get the output from a Kuebler 5868 draw wire encoder into ROS. The 5868 encoder is a CANOpen device that outputs the draw wire position over the CANbus.

My setup is Indigo running on Ubuntu 14.04 on a PC. Once I've decided between the two libraries I will be using a Raspberry Pi with Rasbian and a CAN shield to listen on the CANBus. My eventual goal is to broadcast the position of the draw wire so MoveIt can compute the extension of a hydraulic boom.

My difficulty at the moment is in working out whether I should be using ROS_canopen or kacanopen to interface with the encoder. I've been trying to understand how to use ROS_canopen for a few hours and haven't had a great deal of luck. Can anyone outline the key differences between these two packages and advise which will be easiest to work with?

EDIT:

Here's my launch file:

    <launch>
    <arg name="yaml" default="$(find extension_publisher)/draw_encoder.yaml" />

    <node name="canopen_chain_node" pkg="canopen_chain_node" type="canopen_chain_node"  output="screen"/>
   </launch>

And here's my yaml:

bus:
  device: can0 # socketcan network, this will require changing based on PLC config
  master_allocator: canopen::ExternalMaster::Allocator 
sync:
  interval_ms: 10 # set to 0 to disable sync
  overflow: 0 # overflow sync counter at value or do not set it (0, default)

nodes:
  defaults: # optional, all defaults can be overwritten per node
    eds_pkg: extension_publisher # optional package  name for relative path
    eds_file: "/kuebler_drivers/S58X8MT_HC.eds"
  node1:
    id: 1
    name: draw_position
    eds_file: "/kuebler_drivers/S58X8MT_HC.eds" #path to EDS/DCF file
    publish: ["6004!"] #Position value
  node2:
    id: 2
    name: draw_speed
    eds_file: "/kuebler_drivers/S58X8MT_HC.eds" #path to EDS/DCF file
    publish: ["6030!"] #Position value

Does that look about right? Thanks!

edit retag flag offensive close merge delete

Comments

I also tried to get ros_canopen to work and after several days only had basic SDO upload working, and not consistently for some reason. I stumbled on KACANOpen in another post and was able to get up and running quickly with it, like an hour or two. As noted in the accepted answer, it doesnt include baked in ros_control support, but for my application we didnt need it and we got up and running much faster.

slee-b gravatar image slee-b  ( 2020-01-23 16:52:51 -0600 )edit

I also tried to get ros_canopen to work and after several days only had basic SDO upload working, and not consistently for some reason.

Normally, it should not take that long to setup the basics. canopen_chain_node should just enable this from any well-formed EDS/DCF. If you stumbled upon a bigger problem, please open an issue.

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2020-01-24 06:01:42 -0600 )edit

1 Answer

Sort by » oldest newest most voted
1

answered 2017-03-21 07:52:27 -0600

Mathias Lüdtke gravatar image

updated 2017-03-21 07:52:58 -0600

(Beware: I am the developer of ros_canopen)

kacanopen and ros_canopenare both implementations for CANopen with ROS bindings.

ros_canopen provides a full-fledged ros_control impelementation for motors. kacanopen just provides bridging examples.

Neither the one nor the other has ROS-support for the encoder profile (406), but both can be used to read the values from the objects.

For a first test you can configure ros_canopen's canopen_chain_node to just publish your data based on a configuration file:

bus:
  device: can0 # socketcan network
sync:
  interval_ms: 10 # set to 0 to disable sync
  overflow: 0 # overflow sync counter at value or do not set it (0, default)
nodes:
  my_encoder:
    id: 1 # node id
    eds_pkg: my_config_package # optionals package  name for relative path
    eds_file: "config/Encoder.dcf" # path to EDS/DCF file
    publish: ["6004!"]

You can achieve the same with kacanopen, but you have to write the code yourself. But it has a simple, clean API, so it's not too bad.

edit flag offensive delete link more

Comments

Thanks Mathias, I'll give that a try. I have a similar config file in place to read position and velocity from the encoder. I'll edit the above to include my launch file, I believe I've got the layout right. What's the importance of the ! in the publish variable?

rmck gravatar image rmck  ( 2017-03-22 16:31:40 -0600 )edit

What's the importance of the ! in the publish variable?

For the sake of completeness:

As explained in the wiki:

Each entry can have an exclamation mark appended that forces the driver to reread the object form the node in each step.

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2020-01-24 06:05:27 -0600 )edit

Question Tools

3 followers

Stats

Asked: 2017-03-20 23:50:34 -0600

Seen: 1,234 times

Last updated: Mar 22 '17