Describe the question
I am using the library on an Embedded onboard PC the problem is if I send a non-zero command to my motors and for one reason or other the ROS application is shut down the robot keep moving with this command, very risky business.
So I want to set the motors (the slaves) to be consumers of a Heartbeat, the supplier already showed me how to activate it on their controllers so that is done. Now I need my master to send it.
I started following the exercise here with the virtual CAN to have a prove of concept. So I focused on the Service Interface with ros2 launch canopen_tests cia402_setup.launch.py and did the following:
In ros2_canopen/canopen_tests/config/cia402/bus.yml set the master heartbeat to 1000 ms
So we can see there no heartbeat service nor in the can trace, What I am missing here ? I expected the presence of the service and a continuous can trace every second, did I misunderstood that ?
**Logs**
- Launch log of `cia402_setup.launch.py`:
[cia402_setup_launch_output.txt](https://github.com/ros-industrial/ros2_canopen/files/15435018/cia402_setup_launch_output.txt)
- Candump of vcan0:
[candump_vcan0.txt](https://github.com/ros-industrial/ros2_canopen/files/15435021/candump_vcan0.txt)
**Setup:**
- Device: EAC-3000 with processor: ARMv8 Processor rev 0 (v8l) × 8
- OS: Native is: Ubuntu 20.04.5 LTS, but the application running on Docker container based on ros:humble-ros-base-jammy
- ROS-Distro: humble
- Branch/Commit: humble
**Additional context**
I tried to look up the code on my side and I was surprised to see that in neither:
- `canopen_master_driver/include/canopen_master_driver/node_interfaces/node_canopen_basic_master.hpp` [here](https://github.com/ros-industrial/ros2_canopen/blob/humble/canopen_master_driver/include/canopen_master_driver/node_interfaces/node_canopen_basic_master.hpp), nor
- `canopen_master_driver/include/canopen_master_driver/node_interfaces/node_canopen_basic_master_impl.hpp` [here](https://github.com/ros-industrial/ros2_canopen/blob/humble/canopen_master_driver/include/canopen_master_driver/node_interfaces/node_canopen_basic_master_impl.hpp)
There is no use of `canopen_interfaces/srv/co_heartbeat_id.hpp`, and I even look through the whole repos and it is not used anywhere. I mean it is defined and built as we can see in `canopen_interface` [here](https://github.com/ros-industrial/ros2_canopen/blob/humble/canopen_interfaces/srv/COHeartbeatID.srv) but not used afterwards.
Does this mean that I need to write the service myself?
Describe the question I am using the library on an Embedded onboard PC the problem is if I send a non-zero command to my motors and for one reason or other the ROS application is shut down the robot keep moving with this command, very risky business.
So I want to set the motors (the slaves) to be consumers of a Heartbeat, the supplier already showed me how to activate it on their controllers so that is done. Now I need my master to send it.
I started following the exercise here with the virtual CAN to have a prove of concept. So I focused on the
Service Interface
withros2 launch canopen_tests cia402_setup.launch.py
and did the following:In
ros2_canopen/canopen_tests/config/cia402/bus.yml
set themaster
heartbeat to 1000 msWhich according to here should have the service:
~/set_heartbeat
Same file, set the slaves to be heartbeat consumers:
Which according to here After that I checked:
Running nodes:
Status of
/cia402_node_1
:response: lifecycle_msgs.srv.GetState_Response(current_state=lifecycle_msgs.msg.State(id=3, label='active'))
$ ros2 node info /cia402_node_1 /cia402_node_1 Subscribers: /parameter_events: rcl_interfaces/msg/ParameterEvent Publishers: /cia402_node_1/transition_event: lifecycle_msgs/msg/TransitionEvent /parameter_events: rcl_interfaces/msg/ParameterEvent /rosout: rcl_interfaces/msg/Log Service Servers: /cia402_node_1/change_state: lifecycle_msgs/srv/ChangeState /cia402_node_1/describe_parameters: rcl_interfaces/srv/DescribeParameters /cia402_node_1/get_available_states: lifecycle_msgs/srv/GetAvailableStates /cia402_node_1/get_available_transitions: lifecycle_msgs/srv/GetAvailableTransitions /cia402_node_1/get_parameter_types: rcl_interfaces/srv/GetParameterTypes /cia402_node_1/get_parameters: rcl_interfaces/srv/GetParameters /cia402_node_1/get_state: lifecycle_msgs/srv/GetState /cia402_node_1/get_transition_graph: lifecycle_msgs/srv/GetAvailableTransitions /cia402_node_1/list_parameters: rcl_interfaces/srv/ListParameters /cia402_node_1/set_parameters: rcl_interfaces/srv/SetParameters /cia402_node_1/set_parameters_atomically: rcl_interfaces/srv/SetParametersAtomically Service Clients:
Action Servers:
Action Clients: