Template Class NodeCanopenDriver

Inheritance Relationships

Base Type

Class Documentation

template<class NODETYPE>
class NodeCanopenDriver : public ros2_canopen::node_interfaces::NodeCanopenDriverInterface

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.

Template Parameters:

NODETYPE

Public Functions

inline NodeCanopenDriver(NODETYPE *node)
inline virtual void set_master(std::shared_ptr<lely::ev::Executor> exec, std::shared_ptr<lely::canopen::AsyncMaster> master)

Set Master.

Sets the Lely Canopen Master Objects needed by the driver to add itself to the master.

inline virtual void init()

Initialise the driver.

In this function the ROS interface should be created and potentially necessary callback groups.

inline virtual void init(bool called_from_base)

Initialises the driver.

This does not do anything, it is an empty function. it should be overridden by derived classes.

Todo:

Potentially make this an abstract function. This is mainly for debugging purposes.

Parameters:

called_from_base

inline virtual void configure()

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

inline virtual void configure(bool called_from_base)

Configure the driver.

This function should be overridden by derived classes.

Parameters:

called_from_base

inline virtual void activate()

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.

inline virtual void activate(bool called_from_base)

Activates the driver.

This function should be overridden by derived classes.

Parameters:

called_from_base

inline virtual void deactivate()

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.

inline virtual void deactivate(bool called_from_base)

Deactivates the driver.

This function should be overridden by derived classes.

Parameters:

called_from_base

inline virtual void cleanup()

Cleanup the driver.

This function needs to clean the internal state of the driver. This means all data should be deleted.

inline virtual void cleanup(bool called_from_base)

Cleanup the driver.

This function should be overridden by derived classes.

Parameters:

called_from_base

inline virtual void shutdown()

Shutdown the driver.

This function should shutdown the driver.

inline virtual void shutdown(bool called_from_base)

Shuts down the driver.

This function should be overridden by derived classes.

Parameters:

called_from_base

virtual void demand_set_master()

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.

Protected Functions

inline virtual void add_to_master()

Add the driver to master.

inline virtual void remove_from_master()

Remove the driver from master.

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_