ros_canopen with lwa4d initialization fails
Hi all,
I am quite new to ROS. My intention is to use ROS_CANopen package to connect with my robot (Maxon EPOS2 motor), but I got the failure during initializing the schunk_lwa4d.
Here is my hardware configuration:
- A USB-to-CAN compact is used to communicate between my laptop and the robot. The Linux driver called IXXAT socketcan driver.
- The robot uses Maxon EPOS2 with CANopen. DCF file is generated from EPOS studio.
When initializing...
rosservice call /arm/driver/init
the failure as follows.
success: False
message: /home/cj/catkin_ws/src/ros_canopen/canopen_master/src/sdo.cpp(429): Throw in function void canopen::SDOClient::transmitAndWait(const canopen::ObjectDict::Entry&, const canopen::String&, canopen::String*)
Dynamic exception type: boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<canopen::TimeoutException> >
std::exception::what: SDO
[canopen::tag_objectdict_key*] = 1003sub0
after run roslaunch schunk_lwa4b robot.launch, the log is shown as follows
auto-starting new master
process[master]: started with pid [1962]
ROS_MASTER_URI=http://localhost:11311
setting /run_id to a2e27e66-c8d0-11e6-ba1f-005056c00001
process[rosout-1]: started with pid [1998]
started core service [/rosout]
process[arm/robot_state_publisher-2]: started with pid [2013]
process[joint_state_publisher-3]: started with pid [2015]
process[arm/driver-4]: started with pid [2023]
process[arm/arm_controller_spawner-5]: started with pid [2034]
process[topic_transf-6]: started with pid [2055]
[ INFO] [1482470911.684654700]: Using fixed control period: 0.010000000
[ INFO] [1482470936.775348397]: Initializing XXX
[ INFO] [1482470936.775647194]: Current state: 1 device error: system:0 internal_error: 0 (OK)
[ INFO] [1482470936.775941459]: Current state: 2 device error: system:0 internal_error: 0 (OK)
abort1003#0, reason: Invalid value for parameter (download only).
Could not process message
[ INFO] [1482470936.838776231]: Current state: 0 device error: system:0 internal_error: 0 (OK)
[ INFO] [1482470936.838828278]: Current state: 0 device error: system:0 internal_error: 0 (OK)
Note: I already set the txqueuelen 20.
sudo ip link set can0 txqueuelen 20
From error code showed that 1003sub0, is that possible Epos studio was generated incorrect DCF ? Does someone meet this failure before?
[latest update 12/27] I modified some configuration in epos studio and generated a new DCF. the results are different as follows. When initializing rosservice, the failure as follows.
success: False
message: /home/cj/catkin_ws/src/ros_canopen/canopen_master/src/sdo.cpp(429): Throw in function void canopen::SDOClient::transmitAndWait(const canopen::ObjectDict::Entry&, const canopen::String&, canopen::String*)
Dynamic exception type: boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<canopen::TimeoutException> >
std::exception::what: SDO
[canopen::tag_objectdict_key*] = 2303sub3
after run roslaunch schunk_lwa4b robot.launch, the log is shown as follows.
setting /run_id to 6adddc60-cc2a-11e6-bacb-005056c00001
process[rosout-1]: started with pid [23228]
started core service [/rosout]
process[arm/robot_state_publisher-2]: started with pid [23247]
process[joint_state_publisher-3]: started with pid [23248]
process[arm/driver-4]: started with pid [23249]
process[arm/arm_controller_spawner-5]: started with pid [23257]
process[topic_transf-6]: started with pid [23262]
[ INFO] [1482839325.074128952]: Using fixed control period: 0.010000000
[ INFO] [1482839327.892443220]: Initializing XXX
[ INFO] [1482839327.892948706]: Current state: 1 device error: system:0 internal_error: 0 (OK)
[ INFO] [1482839327.893326862]: Current state: 2 device error: system:0 internal_error: 0 (OK)
abort2303#3, reason: Data cannot be transferred or stored to ...
Your new DCF specifies a ParameterValue (0x00) for 2303sub3, but your controller does not like it.
ros_canopen
sends SDOs for all non-default parameters at start-up. Please consult the EPOS manual to find out in which cases 2303sub3 (and 1003) can be written.I commented some objectdict in my DCF file and run rosservice init. I still observed one error, 60c1sub1, which is not listed in EPOS manual. and I also consulted Drive operation modes, it's shown Interpolated Position. but EPOS manual doesn't mention 60C1 item. Could you plz advise for this issue?
log and details listed on above [latest update 1/2] , thanks for your time and the reply
Maxon uses 0x20C1 instead of 0x60C1, not sure why.. There is not config option for the object to use, so you have to subclass the 402 layer to make it work. Or just use another mode.. (Please ask a new question if you really want to subclass)
You probably want to use Maxon-specific Postion Mode (-1).
Or http://wiki.ros.org/epos_hardware
Did you mean I should not comment some objectdict in my DCF file eg. 2303sub3 (analog position setpoint notation index) or each of Drive operation modes should be included and make it work? I will ask a new question, thanks for the reply.
For my understanding, epos_hardware only supports USB and rs232. My intention is to use CANopen to communicate with my robot. Is ros_canopen package the only one solution for my case? If yes, I will try to let it work on my robot. Thank you for the reply.
Maxon does not support standard IP mode, it uses setpoint (pos, vel & time) with 0x20C1.
You could implement this mode (difficult) or you could implement mode -1 (looks almost like IP mode).
If you do not need full trajectories, you can uses PP mode. Or you can use a PID controller with Pv mode.