ros2_canopen
master
C++ ROS CANopen Library
|
Node Canopen Driver Interface. More...
#include <node_canopen_driver_interface.hpp>
Public Member Functions | |
NodeCanopenDriverInterface () | |
virtual void | set_master (std::shared_ptr< lely::ev::Executor > exec, std::shared_ptr< lely::canopen::AsyncMaster > master)=0 |
Set Master. More... | |
virtual void | demand_set_master ()=0 |
Demand set Master. More... | |
virtual void | init ()=0 |
Initialise the driver. More... | |
virtual void | configure ()=0 |
Configure the driver. More... | |
virtual void | activate ()=0 |
Activate the driver. More... | |
virtual void | deactivate ()=0 |
Deactivate the driver. More... | |
virtual void | cleanup ()=0 |
Cleanup the driver. More... | |
virtual void | shutdown ()=0 |
Shutdown the driver. More... | |
virtual void | add_to_master ()=0 |
Add the driver to master. More... | |
virtual void | remove_from_master ()=0 |
Remove the driver from master. More... | |
Node Canopen Driver Interface.
This node provides the interface for NodeCanopenDriver classes that provide ROS node independent CANopen functionality.
|
inline |
|
pure virtual |
Set Master.
Sets the Lely Canopen Master Objects needed by the driver to add itself to the master.
Implemented in ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >.
|
pure virtual |
Demand set Master.
This function should ask the drivers parent container to set the master objects. This should result in a call to set_master function.
Implemented in ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >.
|
pure virtual |
Initialise the driver.
In this function the ROS interface should be created and potentially necessary callback groups.
Implemented in ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >.
|
pure virtual |
Configure the driver.
This function should contain the configuration related things, such as reading parameter data or configuration data from files.
Implemented in ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >.
|
pure virtual |
Activate the driver.
This function should activate the driver, consequently it needs to start all timers and threads necessary for the operation of the driver.
Implemented in ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >.
|
pure virtual |
Deactivate the driver.
This function should deactivate the driver, consequently it needs to stop all timers and threads that are related to the operation of the diver.
Implemented in ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >.
|
pure virtual |
Cleanup the driver.
This function needs to clean the internal state of the driver. This means all data should be deleted.
Implemented in ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >.
|
pure virtual |
Shutdown the driver.
This function should shutdown the driver.
Implemented in ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >.
|
pure virtual |
Add the driver to master.
Implemented in ros2_canopen::node_interfaces::NodeCanopen402Driver< NODETYPE >, ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >, and ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.
|
pure virtual |
Remove the driver from master.
Implemented in ros2_canopen::node_interfaces::NodeCanopenDriver< NODETYPE >, and ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.