Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Migration from ROS1 to ROS2 fails with Boot Issue: Value of object 1018:03 from CANopen device is different to value in object 1F87 (Revision number) #301

Closed
cschindlbeck opened this issue Aug 8, 2024 · 3 comments
Labels
bug Something isn't working

Comments

@cschindlbeck
Copy link
Contributor

Setup

We have a working ROS1 canopen setup that drives two motors, each motor has its own controller (which is a slave in the CAN).
We have followed the ros2_canopen documentation to migrate our setup to ROS2.

Describe the bug

The launch process waits for slaves to boot while the slaves have already send their boot-up message.
After sending a 000#82.00 message on the can, the slaves boot a second time and the launch process continues.
The first output after continuing is an error:

Boot Issue: Value of object 1018:03 from CANopen device is different to value in object 1F87 (Revision number).

This is the only error in the launch process. The launch process ends with:

[canopen_402_driver]: Fault reset

After that, the master sends messages with id 601 id's and the slaves are answering with 580 id's.
So the can should work some how.

We changed the mode of the slaves with the service to position_mode, but the response was "success=False".

The launch Terminal said "Mode is not supported".

I think the service should be supported, because the service is built.
Is the ros2_canopen package missing some implementation here?

I am trying to control motors with the slaves.

My idea was to use the target Service or the 0x607A RPDO. Both did not work.

When sending RPDO's on the topic nothing happens.

Setup:

  • Device:
  • OS: Ubuntu 22.04
  • ROS-Distro: Humble
  • Branch/Commit: Humble
  • can: real can

bus.yml

options:
  dcf_path: "@BUS_CONFIG_PATH@"

master:
  node_id: 1
  driver: "ros2_canopen::MasterDriver"
  package: "canopen_master_driver"

defaults:
  dcf: "CANedsGoldV005_0_without_buffer_overflow.dcf"
  driver: "ros2_canopen::Cia402Driver"
  package: "canopen_402_driver"
  scale_pos_to_dev: "rint(pos*31831)"
  scale_pos_from_dev: "obj6064/31831"
  scale_vel_to_dev: "rint(vel*31831)"
  scale_vel_from_dev: "obj606C/31831"

nodes:
  front_left_steer_joint:
    node_id: 2

  front_right_steer_joint:
    node_id: 3

Question

Do you have an idea where this problem is come from or a stable solution to control slave motors?

@cschindlbeck cschindlbeck added the bug Something isn't working label Aug 8, 2024
@hellantos
Copy link
Member

hellantos commented Aug 8, 2024

Hi @cschindlbeck

The problem you describe occurs when the eds/dcf you feed to cogen or dcfgen has different values indicated for object 1018 s3. This indicated your drive has another Revision than the eds. You can omit the check by adding revision_number: 0x0 to the slave in bus.yml. Then rebuild.

By the way, we do not support math Operations in the scaling factors yet, it needs to be a plain factor.

@cschindlbeck
Copy link
Contributor Author

Thanks @hellantos

The problem you describe occurs when the eds/dcf you feed to cogen or dcfgen has different values indicated for object 1018 s3. This indicated your drive has another Revision than the eds. You can omit the check by adding revision_number: 0x0 to the slave in bus.yml. Then rebuild.

We added these lines in the bus.yaml:

defaults:
  ...
  revision_number: 0
  period: 100000
  polling: true
  switching_state: 5
  scale_pos_to_dev: 31831
  scale_pos_from_dev: 0.00003141
  scale_vel_to_dev: 31831
  scale_vel_from_dev: 0.00003141

And we got the same error with 1F88, so we added serial_number to the nodes to resolve this one.

By the way, we do not support math Operations in the scaling factors yet, it needs to be a plain factor.

That was a copy-paste issue when migrating from ROS1 canopen to ROS2 canopen 😸

We are now experiencing a problem that is the same as discussed in #298

I will close this one.

@MithraGhlm
Copy link

MithraGhlm commented Aug 18, 2024

I have the same problem. The setup is as OP wrote, only the device is different (Nanotec PD4E motor).
In my case adding revision_number: 0 causes a crash with error: Device: No such file or directory. Full log:

[INFO] [launch]: All log files can be found below /root/.ros/log/2024-08-18-17-45-45-240494-karbon700-15691
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [launch.user]: /ros2_ws/install/pd4e_can/share/pd4e_can/config/single-pd42/bus.yml
[INFO] [launch.user]: /ros2_ws/install/pd4e_can/share/pd4e_can/config/single-pd42/master.dcf
[INFO] [launch.user]: /ros2_ws/install/pd4e_can/share/pd4e_can/config/single-pd42/master.bin
[INFO] [launch.user]: can0
[INFO] [device_container_node-1]: process started with pid [15702]
[device_container_node-1] [INFO] [1724003145.345405439] [device_container_node]: Starting Device Container with:
[device_container_node-1] [INFO] [1724003145.345602317] [device_container_node]: 	 master_config /ros2_ws/install/pd4e_can/share/pd4e_can/config/single-pd42/master.dcf
[device_container_node-1] [INFO] [1724003145.345615767] [device_container_node]: 	 bus_config /ros2_ws/install/pd4e_can/share/pd4e_can/config/single-pd42/bus.yml
[device_container_node-1] [INFO] [1724003145.345623315] [device_container_node]: 	 can_interface_name can0
[device_container_node-1] [INFO] [1724003145.346685544] [device_container_node]: Loading Master Configuration.
[device_container_node-1] [INFO] [1724003145.347298215] [device_container_node]: Load Library: /ros2_ws/install/canopen_master_driver/lib/libmaster_driver.so
[device_container_node-1] [INFO] [1724003145.349919514] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[device_container_node-1] [INFO] [1724003145.349938422] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[device_container_node-1] [INFO] [1724003145.354120855] [master]: NodeCanopenBasicMaster
[device_container_node-1] [INFO] [1724003145.354244431] [device_container_node]: Load master component.
[device_container_node-1] [INFO] [1724003145.354298487] [device_container_node]: Added /master to executor
[device_container_node-1] [WARN] [1724003145.356204257] [master]: No timeout parameter found in config file. Using default value of 100ms.
[device_container_node-1] [INFO] [1724003145.356235592] [master]: Master boot timeout set to 2000ms.
[device_container_node-1] terminate called after throwing an instance of 'std::system_error'
[device_container_node-1]   what():  Device: No such file or directory
[ERROR] [device_container_node-1]: process has died [pid 15702, exit code -6, cmd '/ros2_ws/install/canopen_core/lib/canopen_core/device_container_node --ros-args -r __node:=device_container_node -r __ns:=/ --params-file /tmp/launch_params_dawlijm4 --params-file /tmp/launch_params_3fdr2iof --params-file /tmp/launch_params_2j7zt6w4 --params-file /tmp/launch_params_9ws6vs8w'].

Also, I see during the build cogen or dcfgen throws a warning:

--- stderr: pd4e_can                                                                                                             
/ros2_ws/install/lely_core_libraries/lib/python3.10/site-packages/dcfgen/cli.py:636: UserWarning: pd4e_wheel_l: specified revision number differs from DCF
  slave = Slave.from_config(name, cfg[name], options, args)
---

I worked around this problem by manually reading the 1018:03 object from motor and correcting it in the EDS.
Now, I have the problem same as #298

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
None yet
Development

No branches or pull requests

3 participants