ros2_canopen
master
C++ ROS CANopen Library
|
Node Canopen Driver. More...
#include <node_canopen_driver.hpp>
Public Member Functions | |
NodeCanopenDriver (NODETYPE *node) | |
virtual void | set_master (std::shared_ptr< lely::ev::Executor > exec, std::shared_ptr< lely::canopen::AsyncMaster > master) |
Set Master. More... | |
void | init () |
Initialise the driver. More... | |
virtual void | init (bool called_from_base) |
Initialises the driver. More... | |
void | configure () |
Configure the driver. More... | |
virtual void | configure (bool called_from_base) |
Configure the driver. More... | |
void | activate () |
Activate the driver. More... | |
virtual void | activate (bool called_from_base) |
Activates the driver. More... | |
void | deactivate () |
Deactivate the driver. More... | |
virtual void | deactivate (bool called_from_base) |
Deactivates the driver. More... | |
void | cleanup () |
Cleanup the driver. More... | |
virtual void | cleanup (bool called_from_base) |
Cleanup the driver. More... | |
void | shutdown () |
Shutdown the driver. More... | |
virtual void | shutdown (bool called_from_base) |
Shuts down the driver. More... | |
virtual void | demand_set_master () |
Demand set Master. More... | |
![]() | |
NodeCanopenDriverInterface () | |
Protected Member Functions | |
virtual void | add_to_master () |
Add the driver to master. More... | |
virtual void | remove_from_master () |
Remove the driver from master. More... | |
Protected Attributes | |
NODETYPE * | node_ |
std::shared_ptr< lely::ev::Executor > | exec_ |
std::shared_ptr< lely::canopen::AsyncMaster > | master_ |
std::shared_ptr< lely::canopen::BasicDriver > | driver_ |
std::chrono::milliseconds | non_transmit_timeout_ |
YAML::Node | config_ |
uint8_t | node_id_ |
std::string | container_name_ |
std::string | eds_ |
std::string | bin_ |
rclcpp::CallbackGroup::SharedPtr | client_cbg_ |
rclcpp::CallbackGroup::SharedPtr | timer_cbg_ |
std::atomic< bool > | master_set_ |
std::atomic< bool > | initialised_ |
std::atomic< bool > | configured_ |
std::atomic< bool > | activated_ |
Node Canopen Driver.
This class implements the NodeCanopenDriverInterface. It provides core functionality and logic for CanopenDriver, indepentently of the ROS node type. Currently rclcpp::Node and rclcpp_lifecycle::LifecycleNode and derived classes are supported. Other node types will lead to compile time error.
NODETYPE |
|
inline |
|
inlinevirtual |
Set Master.
Sets the Lely Canopen Master Objects needed by the driver to add itself to the master.
Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.
|
inlinevirtual |
Initialise the driver.
In this function the ROS interface should be created and potentially necessary callback groups.
Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.
|
inlinevirtual |
Initialises the driver.
This does not do anything, it is an empty function. it should be overridden by derived classes.
called_from_base |
Reimplemented in ros2_canopen::node_interfaces::NodeCanopenProxyDriver< NODETYPE >, ros2_canopen::node_interfaces::NodeCanopen402Driver< NODETYPE >, and ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.
|
inlinevirtual |
Configure the driver.
This function should contain the configuration related things, such as reading parameter data or configuration data from files.
This function reads the parameters container_name, non_transmit_timeout, node_id and config. Once done it will call the configure(bool) function that should be over
Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.
|
inlinevirtual |
Configure the driver.
This function should be overridden by derived classes.
called_from_base |
Reimplemented in ros2_canopen::node_interfaces::NodeCanopen402Driver< NODETYPE >, and ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.
|
inlinevirtual |
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.
Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.
|
inlinevirtual |
Activates the driver.
This function should be overridden by derived classes.
called_from_base |
Reimplemented in ros2_canopen::node_interfaces::NodeCanopen402Driver< NODETYPE >, and ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.
|
inlinevirtual |
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.
Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.
|
inlinevirtual |
Deactivates the driver.
This function should be overridden by derived classes.
called_from_base |
Reimplemented in ros2_canopen::node_interfaces::NodeCanopen402Driver< NODETYPE >, and ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.
|
inlinevirtual |
Cleanup the driver.
This function needs to clean the internal state of the driver. This means all data should be deleted.
Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.
|
inlinevirtual |
Cleanup the driver.
This function should be overridden by derived classes.
called_from_base |
Reimplemented in ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.
|
inlinevirtual |
Shutdown the driver.
This function should shutdown the driver.
Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.
|
inlinevirtual |
Shuts down the driver.
This function should be overridden by derived classes.
called_from_base |
Reimplemented in ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.
|
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.
Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.
|
inlineprotectedvirtual |
Add the driver to master.
Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.
Reimplemented in ros2_canopen::node_interfaces::NodeCanopen402Driver< NODETYPE >, and ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.
|
inlineprotectedvirtual |
Remove the driver from master.
Implements ros2_canopen::node_interfaces::NodeCanopenDriverInterface.
Reimplemented in ros2_canopen::node_interfaces::NodeCanopenBaseDriver< NODETYPE >.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |