ros-industrial / ros_canopen

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

CanOpen refuses to initialize canopen_chain_node (Initializing failed: could not reset node '8') #381

Closed mal-a-chillingg closed 4 years ago

mal-a-chillingg commented 4 years ago

To whoever is willing to help with an answer, here is the issue I am having. I am setting up a RobotTeq HBL2360A drive and I have the EDS file and everything. I have put together what I believe is a correct config and launch file. For now I am running the system as a canopen_chain_node and I have manually tested the drives communication with candump and cansend and there are no issues as far as I can tell. The drive responds correctly to sync commands and NMT commands when I manually send them. When I launch the setup I get the following in ROSCore.

CLEAR PARAMETERS
 * /canopen_chain_node/

PARAMETERS
 * /canopen_chain_node/bus/device: can0
 * /canopen_chain_node/nodes/node1/eds_file: /config/HBL2360A.eds
 * /canopen_chain_node/nodes/node1/eds_pkg: little_pig_ctrl
 * /canopen_chain_node/nodes/node1/id: 8
 * /canopen_chain_node/sync/interval_ms: 2000
 * /canopen_chain_node/sync/overflow: 0
 * /rosdistro: melodic
 * /rosversion: 1.14.3

NODES
  /
    canopen_chain_node (canopen_chain_node/canopen_chain_node)

auto-starting new master
process[master]: started with pid [28932]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 0bbb7a12-55c5-11ea-bd2f-00044bddba3d
process[rosout-1]: started with pid [28943]
started core service [/rosout]
process[canopen_chain_node-2]: started with pid [28951]

As far as I can tell there is nothing wrong at this point but when I go to initialize the driver it will not work. I get the following message in the terminal

success: False
message: "could not reset node '8'"

Meanwhile in ROSCORE the following messages are generated.

[ INFO] [1582411558.289981301]: Initializing...
[ INFO] [1582411558.293634531]: Current state: 1 device error: system:0 internal_error: 0 (OK)
[ INFO] [1582411558.296560564]: Current state: 2 device error: system:0 internal_error: 0 (OK)
[ERROR] [1582411569.308112997]: Did not receive a response message
[ WARN] [1582411569.311083926]: discarded message 
[ INFO] [1582411569.314714468]: Current state: 2 device error: system:125 internal_error: 0 (OK)
[ INFO] [1582411569.315000003]: Current state: 0 device error: system:125 internal_error: 0 (OK)
[ INFO] [1582411569.315333857]: Current state: 0 device error: system:0 internal_error: 0 (OK)
[ INFO] [1582411569.315685440]: Current state: 0 device error: system:0 internal_error: 0 (OK)
[ERROR] [1582411569.317187704]: Initializing failed: could not reset node '8'

No matter what I do I cannot get the node to initialize. I am also monitoring the candump on can1 at the same time and here are the results I am getting

ursa@ursa-major:~/catkin_ws/src/little_pig_ctrl/config$ candump can1
can1  000   [2]  82 08
can1  708   [1]  7F
can1  708   [1]  7F
can1  708   [1]  7F
can1  708   [1]  7F
can1  708   [1]  7F
can1  708   [1]  7F
can1  708   [1]  7F
can1  708   [1]  7F
can1  708   [1]  7F
can1  708   [1]  7F
can1  708   [1]  7F
can1  608   [8]  2B 17 10 00 00 00 00 00
can1  588   [8]  60 17 10 00 00 00 00 00
can1  608   [8]  80 17 10 00 00 00 04 05
can1  000   [2]  02 08

All of the documentation I have read sounds like this is exactly what I would expect from the drive. After receiving the NMT command to reset it goes to pre-operational state and just waits. However, Canopen does nothing more and then eventually gives up and tells the node to shut up. Is there anything wrong in what I am seeing in the date. I have already checked the baud rates and I can't find any issues there, I am set at 500k on both devices. I also have tested this with and without 402 enabled on the drive to no avail. I plan to eventually migrate to 402; however, I don't understand enough about it yet and from my understanding I should have full operation on canopen_chain_node.

Here is my Launch file

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

Here is my config file

bus:
  device: can0 # socketcan network
  #loopback: false # socket should loop back messages
  #driver_plugin: can::SocketCANInterface
  #master_allocator: canopen::SimpleMaster::Allocator
sync:
  interval_ms: 2000 #100 # 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: 2000 # heartbeat rate
  #msg: "701#05" # message to send, cansend format: heartbeat of node 1 with status 5=Started

nodes:
  node1:
    id: 8
    eds_pkg: little_pig_ctrl
    eds_file: "/config/HBL2360A.eds"

I appreciate any help you guys can provide. I have been beating this problem around for the last day and I am at my wits end. Thanks

mathias-luedtke commented 4 years ago

After receiving the NMT command to reset it goes to pre-operational state and just waits. However, Canopen does nothing more and then eventually gives up and tells the node to shut up.

According to the CANopen standard, the device must respond with the boot up (00 instead of 7F) message. This is what ros_canopen is waiting for.

mal-a-chillingg commented 4 years ago

Thanks for the info Mathias, I will check with Roboteq as to why this is happening. I would hope for an $800 drive they would have configured it correctly. On Wednesday, February 26, 2020, 06:13:34 AM CST, Mathias Lüdtke notifications@github.com wrote:

After receiving the NMT command to reset it goes to pre-operational state and just waits. However, Canopen does nothing more and then eventually gives up and tells the node to shut up.

According to the CANopen standard, the device must respond with the boot up (00 instead of 7F) message. This is what ros_canopen is waiting for.

— You are receiving this because you authored the thread. Reply to this email directly, view it on GitHub, or unsubscribe.

mal-a-chillingg commented 4 years ago

I have a question regarding implementation for the CANOpen motor node. The drive we are using is a RoboTeq CANOpen dual axes drive that uses CANOpen 402; however, the manufacturer decided to put both axes on the same node. All of the motor 1’s 402 objects are in the range of 6000-67FF, and all of motor 2’s 402 objects are in the range of 6800-6FFF. Is there any way to use ros_canopen to implement this? I guess what I am wondering is if there is a way to spawn two motor controllers on the same node with the object shifted? If not, how much work would it be to implement something like this. If not, is there any way to just spawn a CANOpen node which sends and receives all of it’s PDO objects to ROSTopics. That is kind of what I was looking for in the beginning and I can do all of the mapping after that point. However, it seems like ros_canopen was more geared toward a very specific application and can’t be used in this way.

Thanks

mathias-luedtke commented 4 years ago

Two motors on one node are not supported by canopen_motor_node in ROS. However, ros_canopen should provide you all building blocks to build a custom driver.

If not, is there any way to just spawn a CANOpen node which sends and receives all of it’s PDO objects to ROSTopics.

canopen_chain_node can do this for configured objects: http://wiki.ros.org/canopen_chain_node#ROS_layer But I do not recommend this. Instead, subclass it write your custom handling code.

However, it seems like ros_canopen was more geared toward a very specific application and can’t be used in this way.

ros_canopen consist of 7 packages, which are as generic as possible. canopen_motor_node is the most-specialized package, which is meant for chains of 402-compliant motors and ros_control.

mal-a-chillingg commented 4 years ago

Thanks for the feedback. I am not the best with CS stuff and I really appreciate that foundation that I have with ros_canopen. I think we will try to modify the existing motor_node to instantiate two motors on one node. Might be tricky. In the meantime, I am testing using just one motor and so far, everything initializes correctly as far as I can tell. I get no errors, I have ran through a number of debugging things and everything looks good so far. I have all of the usual CANBUS traffic and the control is clearly reading the status word and necessary feedback. Further, at initialization the motor goes to the following states Remote, Halt, Voltage Enabled, Operation Enabled, Switched On, and Ready to Switch On. All of those look great and I think I am ready to control it. The next question is how to control it. I have it linked to a joint on a vehicle we are simulating. I have the vehicle currently up in a gazebo and I am moving the vehicle in gazebo, should my physical motor be moving now also? That is where I am stuck. I don’t see any commands on the bus to drive the motors. What mechanism actually sends the command? Am I correct to assume that your node reads directly from the joint_interface for the command on what to do?

Thanks for your time and responses.

From: Mathias Lüdtke notifications@github.com Sent: Sunday, March 15, 2020 11:24 AM To: ros-industrial/ros_canopen ros_canopen@noreply.github.com Cc: mal-a-chillingg mal_a_chillingg@yahoo.com; State change state_change@noreply.github.com Subject: Re: [ros-industrial/ros_canopen] CanOpen refuses to initialize canopen_chain_node (Initializing failed: could not reset node '8') (#381)

Two motors on one node are not supported by canopen_motor_node in ROS. However, ros_canopen should provide you all building blocks to build a custom driver.

If not, is there any way to just spawn a CANOpen node which sends and receives all of it’s PDO objects to ROSTopics.

canopen_chain_node can do this for configured objects: http://wiki.ros.org/canopen_chain_node#ROS_layer But I do not recommend this. Instead, subclass it write your custom handling code.

However, it seems like ros_canopen was more geared toward a very specific application and can’t be used in this way.

ros_canopen consist of 7 packages, which are as generic as possible. canopen_motor_node is the most-specialized package, which is meant for chains of 402-compliant motors and ros_control.

— You are receiving this because you modified the open/close state. Reply to this email directly, view it on GitHub https://github.com/ros-industrial/ros_canopen/issues/381#issuecomment-599231976 , or unsubscribe https://github.com/notifications/unsubscribe-auth/AOOARLT46J5L24PCB6XEOGTRHT6LBANCNFSM4KZVN5NA .