Closed ghanim-mukhtar closed 3 months ago
Hi, thanks for the comment and sorry for the confusion. We removed the service at some point because the possibility to fix heartbeat settings in the yaml for master and devices seemed sufficient. Actually this is a problem in the documentation. I have created PR #294 for adjusting this.
Hi, thanks for the comment and sorry for the confusion. We removed the service at some point because the possibility to fix heartbeat settings in the yaml for master and devices seemed sufficient. Actually this is a problem in the documentation. I have created PR #294 for adjusting this.
Thanks for the reply and the correction, but still for me I am a bit confused about how to set the heartbeat in such a way that the PC is producer and the motors are consumers. Can you provide yaml examples please ?
You would need to add heartbeat_producer: 1000
to master node and heartbeat_consumer: true
to driver node in bus.yml.
Thanks for the tip, I will check and get back to you ASAP to conclude the issue
I did the test today and just wanted to double check something because I didn't get the behavior expected. I am in contact with our CANOpen motor controller to see if the error is in their side (most likely), meanwhile I have a small doubt about lily_core_libraries
that I want to clear up with you.
Basically the bus.yml
is configured as indicated above.
But after compiling I checked the resulting file cli.py
in ~my_workspace/install/lely_core_libraries/lib/python3.10/site-packages/dcfgen/
and these caught my eyes (i attached it as .txt for your convenience):
So my question is: Is this normal ? I mean the fact that in this autogenerated cli.py
in lily_core_libraries
the slave class is set as not a consumer of heartbeat and master class is set as non producer of heartbeat ?
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: