ros-industrial / ros_canopen

CANopen driver framework for ROS (http://wiki.ros.org/ros_canopen)
GNU Lesser General Public License v3.0
328 stars 267 forks source link

Unable to initialize driver: Supported drive modes (object 6502) is not valid #462

Open mzahana opened 2 years ago

mzahana commented 2 years ago

Hi!

I have a brushless motor driver that supports CANopen, and I would like to control it in profile velocity mode. The driver supports only 3 modes 1: Profile Position Mode 3: Profile Velocity Mode 4: Profile Torque Mode'

The modes can be set by OD 6060h (Mode of operation), and can be read by 6061h (Mode of operation display). I have read so many docs and posts in order to understand how to use the ros_canopen package, and here are the steps I followed, which lead to the issues of not able to initialize the drivers.

  1. I prepared a config file can0.yaml
    
    # Can bus layer
    bus:
    device: can0 # socketcan network
    # loopback: false # socket should loop back messages
    # driver_plugin: can::SocketCANInterface
    master_allocator: canopen::SimpleMaster::Allocator
    sync:
    interval_ms: 10 # set to 0 to disable sync
    # update_ms: <interval_ms> #update interval of control loop, must be set explecitly if sync is disabled
    overflow: 0 # overflow sync counter at value or do not set it (0, default)
    heartbeat: # simple heartbeat producer, optional!
    rate: 20 # heartbeat rate
    msg: "77f#05" # message to send, 

Nodes layer

nodes: node1: id: 1 name: front_left_wheel_joint eds_pkg: ugv_hardware eds_file: "config/zlac8030L_mapped.eds" node2: id: 2 name: rear_left_wheel_joint eds_pkg: ugv_hardware eds_file: "config/zlac8030L_mapped.eds" node3: id: 3 name: rear_right_wheel_joint eds_pkg: ugv_hardware eds_file: "config/zlac8030L_mapped.eds" node4: id: 4 name: front_right_wheel_joint eds_pkg: ugv_hardware eds_file: "config/zlac8030L_mapped.eds"

defaults: # optional, all defaults can be overwritten per node

eds_pkg: ugv_hardware # optional package name for relative path

eds_file: "config/zlac8030L_mapped.eds" # path to EDS/DCF file

dcf_overlay: # "ObjectID": "ParameterValue" (both as strings)

"1016sub1" : "0x7F0064" # heartbeat timeout of 100 ms for master at 127

"1017": "100" # heartbeat producer

canopen_chain_node settings ..

motor_allocator: canopen::Motor402::Allocator # select allocator for motor layer motor_layer: #settings passed to motor layer (plugin-specific) switching_state: 5 # (Operation_Enable), state for mode switching

pos_to_device: "rint(rad2deg(pos)*1000)" # rad -> mdeg

pos_from_device: "deg2rad(obj6064)/1000" # actual position [mdeg] -> rad

pos_from_device: "(obj6064)1" # unit is counts for zlac8030L, according to their canopen manual vel_to_device: "rint(vel9.5493)" # rad/s -> rpm

vel_from_device: "deg2rad(obj606C)/1000" # actual velocity [mdeg/s] -> rad/s

vel_from_device: "(obj606C)0.10.10472" # actual velocity (0.1*rpm) to rad/s

eff_to_device: "rint(eff)" # just round to integer

eff_from_device: "0" # unset

2. Created the following launch file `driver.launch`
```xml
<launch>
    <arg name="can_yaml" default="$(find ugv_hardware)/config/can0.yaml"/>
    <node pkg="canopen_motor_node" name="canopen_motor_node" type="canopen_motor_node" >
        <rosparam file="$(arg can_yaml)" command="load" />
    </node>
</launch>

When I launch the above launch file, and execute rosservice call /driver/init I get the following output from the motor node which matches the msg in the service response,

process[canopen_motor_node-1]: started with pid [4086]
[ WARN] [1653470014.275057611]: illegal transition 0 -> 2
[ERROR] [1653470014.277755072]: Initializing failed: /tmp/binarydeb/ros-melodic-canopen-402-0.8.5/src/motor.cpp(270): Throw in function virtual bool canopen::Motor402::isModeSupportedByDevice(uint16_t)
Dynamic exception type: boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<std::runtime_error> >
std::exception::what: Supported drive modes (object 6502) is not valid
; Could not set transition

NOTE: in the EDS file provided by the manufacturer, the OD 6502 is not defined, and I am not sure if this is an issue.

@mathias-luedtke Any help in debugging this issue is highly appreciated.

The driver manual, and the EDS file are attached for reference.

zlac8030L.txt ZLAC8030L CANopen COMMUNICATION Version 1.00-1.pdf

mzahana commented 2 years ago

@mathias-luedtke any hints? Or anyone else can assist with this? Thanks in advance.

flippybit commented 1 year ago

i have the ZLAC8015 and its missing that object (6502h) i ve managed to inicialize it on canopen_chain but with motor_node its not woking, is there a way to make it look on another object ?

flippybit commented 1 year ago

i have the ZLAC8015 and its missing that object (6502h) i ve managed to inicialize it on canopen_chain but with motor_node its not woking, is there a way to make it look on another object ?

Hi flippybit. May I ask how to initialize using only canopen_chain?. Did you only rum chain node in launch file. If that is the case, have you tried to control the motor using chain node?.

hey PHONG, ive used this launch file, it inits the driver when i use rosservice call /driver/init and i can pass can commands with the service driver/set/object and /driver/get_object and get the wheels moving, but im failing to get the controllers to work, im still new at ROS and just begging to understand CANbus so...

launch file

launch>
  <!-- Load URDF into ROS parameter server -->
  <param name="robot_description" textfile="$(find second_ROS_assembly)/urdf/second_ROS_assembly.urdf" />

  <arg name="yaml"/>
  <node name="canopen_chain" pkg="canopen_chain_node" type="canopen_chain_node" output="screen" 
    clear_params="true">
    <rosparam command="load" file="$(find canopen_chain_node)/launch/my_yml_eds.yaml" />
    <rosparam command="load" file="$(find canopen_chain_node)/config/node.yaml" />
  </node>

  <!-- Load Joint Controller configuration from YAML file to parameter server -->
  <rosparam file="$(find berry_bot_bringup)/config/berry_bot_controllers.yaml" command="load"/>
  <!-- load the controllers-->
  <node name="controller_spawner" pkg="controller_manager" type="controller_manager" respawn="false"
    output="screen" 
    args="spawn 
          joint_state_controller
          rueda1_velocity_controller
          rueda2_velocity_controller
          rueda3_velocity_controller
          rueda4_velocity_controller
          "/>

  <!--combine joint values-->
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>

  <!--Show in Rviz-->
  <node name="rviz" pkg="rviz" type="rviz"/>

</launch>

the files i load to can_open_chain are

  1. my_yml_eds.yaml.
  2. node.yaml

my_yml_eds.yaml

---
bus:
  device: can0 # socketcan network
  # loopback: false # socket should loop back messages
  driver_plugin: can::SocketCANInterface
  master_allocator: canopen::SimpleMaster::Allocator
sync:
  interval_ms: 20 # set to 0 to disable sync
  #overflow: # overflow sync counter at value or do not set it (0, default)
  update_ms: 20 #update interval of control loop, must be set explecitly if sync is disabled
#heartbeat: # simple heartbeat producer, optional!
  #rate: 20 # heartbeat rate
  #msg: "77f#05" # message to send, cansend format: heartbeat of node 127 with status 5=Started
  # struct syntax
nodes:
  node1:
    id: 1
    #eds_pkg: my_config_package # optionals package  name for relative path
    eds_file: "/path/to/canopen_chain_node/launch/ZLAC8015D_V1.0.eds" # path to EDS/DCF file
switching_state: 3 # (Operation_Enable), state for mode switching. Drive mode of operation from canopen_402 wiki

node.yaml

this makes changes the name of the node to "wheel_back_left_joint" keep this in mind when your try to communicate to the driver using rosservice call to for example object 6040

rosservice call /driver/set_object "node: 'wheel_back_left_joint'
object: '6040'
value: '0'
cached: false" 
success: True
message: ''
nodes:
  node1:
    id: 1
    name: wheel_back_left_joint
    #eds_pkg:  # optionals package  name for relative path
    eds_file: "/path/to/file/canopen_chain_node/launch/ZLAC8015D_V1.0.eds" # path to EDS/DCF file

defaults: # optional, all defaults can be overwritten per node
#  eds_pkg: my_config_package # optional package  name for relative path
#  eds_file: "my_config.dcf" # path to EDS/DCF file
#   dcf_overlay: # "ObjectID": "ParameterValue" (both as strings)
#    "6098": "0" # No homing operation required
#    "1016sub1" : "0x7F0064" # heartbeat timeout of 100 ms for master at 127
#    "1017": "100" # heartbeat producer

# canopen_chain_node settings ..
  motor_allocator: canopen::Motor402::Allocator # select allocator for motor layer
#   motor_layer: settings passed to motor layer (plugin-specific)
  switching_state: 2 # (Operation_Enable), state for mode switching. Drive mode of operation from canopen_402 wiki
  pos_to_device: "pos" # inc
  pos_from_device: "obj6064" # inc 
  vel_to_device: "vel" # rpm
  vel_from_device: "obj606C" # rpm

Like i said i'm having trouble with ROS so any help would be appreciated

oren-hinkis commented 1 year ago

If 6502 isn't defined in the EDS you will have issues using the motor chain. The reason for this is that it queries 6502 to validate that the requested mode (eg: profile position, profile velocity) is supported.

I ran into a similar issue, one of my drivers didn't implement 6502. You can get around this by adding 6502 to the EDS and using the DefaultValue field to add in the required mode. The reason you can do this is that the call to object 6502 in the code gets cached data, so if DefaultValue exists it will just pull that instead of calling the SDO.

To modify your EDS/DCF you can do the following: You should have a field called OptionalObjects, under it you need to add another object for 6502 as well setting SupportedObjects to be equal to the new total number of objects in this list.

For example, in my case I already had 55 objects, I added object 56=0x6502 on the end, and set Supported objects to 56. [OptionalObjects] SupportedObjects=56 56=0x6502

Then, you need to add the object itself with a DefaultValue that passes the Supported Drive Mode check. 3FF should be fine as it will catch all the possibilities.

[6502] ParameterName=Supported Drive Modes ObjectType=7 DataType=0x0007 AccessType=ro DefaultValue=0x3FF PDOMapping=1

flippybit commented 1 year ago

Thnx Oren, i was thinking there had to be a way, but now i know! ill give it a try and hopefully get this thing moving

Cheers! Ben

mzahana commented 1 year ago

The following repos I created might be useful.

I was able to run ZLAC8030L with ROS Melodic (Python 2)

https://github.com/mzahana/zlac8030l_ros

https://github.com/mzahana/ZLAC8030L_CAN_controller

flippybit commented 1 year ago

The following repos I created might be useful.

I was able to run ZLAC8030L with ROS Melodic (Python 2)

https://github.com/mzahana/zlac8030l_ros

https://github.com/mzahana/ZLAC8030L_CAN_controller

thnx ill give it a look