-
Notifications
You must be signed in to change notification settings - Fork 280
Description
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.
- 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(vel*9.5493)" # rad/s -> rpm
# vel_from_device: "deg2rad(obj606C)/1000" # actual velocity [mdeg/s] -> rad/s
vel_from_device: "(obj606C)*0.1*0.10472" # actual velocity (0.1*rpm) to rad/s
# eff_to_device: "rint(eff)" # just round to integer
# eff_from_device: "0" # unset- Created the following launch file
driver.launch
<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 transitionNOTE: 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