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

roscanopen - Transition timeout; Could not enable motor

asked 2018-01-13 15:35:48 -0500

JadTawil gravatar image

roscanopen's driver initilization service call is failing with error message:

success: False message: Transition timeout; Could not enable motor

After looking at the source code, it seems like a timeout is occuring when the driver is attempting to change the state of the controller from: Switch_On_Disabled -> Ready_To_Switch_On -> Switched_On -> Operation_Enable

It is timing out when trying to change the state from Switch_On_Disabled -> Ready_To_Switch_On.

I am able to operate the controller via canbus using the manufacturer's software, and the fact that ros-canopen is able to read the initial state of the controller (Switch_On_Disabled) means that the bus communication is up and running functionally. So i highly doubt this is a hardware issue. The controller im using is a Nanotec N5-5-2 which is DS402.

The steps i took to prepare the driver included changing the control word RPDO transmission type to 1 (every sync), and the status word TPDO transmission type to 1. Also, i added a target velocity RPDO with transmission type 1 and a Current velocity TPDO with transmission type 1 for feedback in order to run the controller in profile velocity mode via ros-canopen.

sudo ip link can0 up type can bitrate 1000000

The baudrate in the controller and Node ID are set to 1Mbps, and 1, respectively (using DIP switches).

The following is the configuration of the driver, and the output of candump after the initialize service is called. I hope someone can spot the issue. I will repeat, transitioning states is functional with the manufacturer's software, but it seems like ros-canopen is failing to get the states changed.

My configuration parameters:

bus:

  device: can0

sync:

  interval_ms: 10

  overflow: 0

defaults:

  eds_pkg: my_pkg

  eds_file: "config/N5-2-2.eds"

  vel_to_device: "rint((vel))"

nodes:

  wheel_joint:

  id: 1

joint_names: [fr_wheel_joint]

joint_state_controller:

  type: joint_state_controller/JointStateController

  publish_rate: 50

wheel_joint_velocity_controller:

  type: velocity_controllers/JointVelocityController

  joint: fr_drive_joint

  required_drive_mode: 3

More importantly, here is the candump output when the initialization service of ros_canopen is called:

can0 000 [2] 82 01

can0 701 [1] 00

can0 601 [8] 2B 17 10 00 00 00 00 00

can0 581 [8] 60 17 10 00 00 00 00 00

can0 000 [2] 01 01

can0 701 [1] 05

can0 181 [3] 40 06 03

can0 281 [4] AC FF FF FF

can0 381 [2] 00 00

can0 481 [4] 00 00 00 00

can0 601 [8] 40 61 60 00 00 00 00 00

can0 581 [8] 4F 61 60 00 03 00 00 00

can0 201 [7] 00 01 03 00 00 00 00

can0 601 [8] 40 61 60 00 00 00 00 00

can0 581 [8] 4F 61 60 00 03 00 00 00

can0 080 [0]

can0 181 [3] 40 06 03

can0 481 [4] 00 00 00 00

can0 601 [8] 40 61 60 00 00 00 00 00

can0 581 [8] 4F 61 60 00 03 00 00 00

can0 201 [7] 06 01 03 00 00 00 00

//This Block Repeats for a certain period

can0 080 [0]

can0 181 [3] 40 ... (more)

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-01-14 13:43:42 -0500

JadTawil gravatar image

SOLVED.

The problem here was that RPOD1 in my controller, which is mapped to the Control Word (6040) and the Mode selection (6060), had the communication paramter "transmission type" set to 1 (every SYNC).

When i changed this back to 0xFF (asynchronous), It worked.

edit flag offensive delete link more

Comments

I know it's been a while but could you elaborate how you managed to do this?

YellowShyGuy gravatar image YellowShyGuy  ( 2020-02-19 06:55:49 -0500 )edit

Perhaps it is editing an EDS file. 'ParameterName=Transmission type...' Change the "DefaultValue" of the "ParameterName=Transmission type..." to 255.

miura gravatar image miura  ( 2020-09-29 10:20:31 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-01-13 15:35:48 -0500

Seen: 695 times

Last updated: Jan 14 '18