ros2_canopen  master
C++ ROS CANopen Library
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ros2_canopen::LifecycleManager Class Reference

Lifecycle Device Manager Node. More...

#include <lifecycle_manager.hpp>

Inheritance diagram for ros2_canopen::LifecycleManager:
Inheritance graph
[legend]
Collaboration diagram for ros2_canopen::LifecycleManager:
Collaboration graph
[legend]

Public Member Functions

 LifecycleManager (const rclcpp::NodeOptions &node_options)
 Construct a new Lifecycle Device Manager Node object. More...
 
void init (std::shared_ptr< ros2_canopen::ConfigurationManager > config)
 

Protected Member Functions

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure (const rclcpp_lifecycle::State &state)
 Callback for the Configure Transition. More...
 
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate (const rclcpp_lifecycle::State &state)
 Callback for the Activate Transition. More...
 
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &state)
 Callback for the Deactivate Transition. More...
 
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &state)
 Callback for the Cleanup Transition. More...
 
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &state)
 Callback for the Shutdown Transition. More...
 
template<typename FutureT , typename WaitTimeT >
std::future_status wait_for_result (FutureT &future, WaitTimeT time_to_wait)
 
virtual unsigned int get_state (uint8_t node_id, std::chrono::seconds time_out)
 Get the lifecycle state of a driver node. More...
 
virtual bool change_state (uint8_t node_id, uint8_t transition, std::chrono::seconds time_out)
 Change the lifecycle state of a driver node. More...
 
virtual bool bring_up_all ()
 Brings up master and all drivers. More...
 
virtual bool bring_down_all ()
 Brings down master and all drivers. More...
 
virtual bool bring_up_master ()
 Brings up master. More...
 
virtual bool bring_down_master ()
 Bring down master. More...
 
virtual bool bring_up_driver (std::string device_name)
 Brings up the drivers with specified node_id. More...
 
virtual bool bring_down_driver (std::string device_name)
 Brings down the driver with specified node_id. More...
 
virtual bool load_from_config ()
 Load information from configuration. More...
 

Protected Attributes

rclcpp::CallbackGroup::SharedPtr cbg_clients
 
std::shared_ptr< ros2_canopen::ConfigurationManagerconfig_
 
std::map< uint8_t, rclcpp::Client< lifecycle_msgs::srv::GetState >::SharedPtr > drivers_get_state_clients
 stores node_id and get_state client More...
 
std::map< uint8_t, rclcpp::Client< lifecycle_msgs::srv::ChangeState >::SharedPtr > drivers_change_state_clients
 stores node_id and change_state client More...
 
std::map< std::string, uint8_t > device_names_to_ids
 
rclcpp::Client< canopen_interfaces::srv::CONode >::SharedPtr add_driver_client_
 Service client object for adding a driver. More...
 
rclcpp::Client< canopen_interfaces::srv::CONode >::SharedPtr remove_driver_client_
 Service client object for removing a driver. More...
 
uint8_t master_id_
 Stores master id. More...
 
std::string container_name_
 Stores name of the associated device_container. More...
 

Detailed Description

Lifecycle Device Manager Node.

This class provides functionalities to coordinate the lifecycle of master and device drivers that are loaded into the executor.

Start-up sequence

master | unconfigured | x | | inactive | | x |

| active | | x | x | x | x | x |...

drv1 | unconfigured | x | x | x | | inactive | | x |

| active | | x | x | x |...

driv2 | unconfigured | x | x | x | x | x | | inactive | | x |

| active | | x |...

Constructor & Destructor Documentation

◆ LifecycleManager()

ros2_canopen::LifecycleManager::LifecycleManager ( const rclcpp::NodeOptions &  node_options)
inline

Construct a new Lifecycle Device Manager Node object.

Parameters
node_options

Member Function Documentation

◆ init()

void ros2_canopen::LifecycleManager::init ( std::shared_ptr< ros2_canopen::ConfigurationManager config)

◆ on_configure()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn ros2_canopen::LifecycleManager::on_configure ( const rclcpp_lifecycle::State &  state)
protected

Callback for the Configure Transition.

This will cause the device manager to load the configuration from the configuration file.

Parameters
state
Returns
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

◆ on_activate()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn ros2_canopen::LifecycleManager::on_activate ( const rclcpp_lifecycle::State &  state)
protected

Callback for the Activate Transition.

This will bringup master and device drivers using the bring_up_all function.

Parameters
state
Returns
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

◆ on_deactivate()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn ros2_canopen::LifecycleManager::on_deactivate ( const rclcpp_lifecycle::State &  state)
protected

Callback for the Deactivate Transition.

This will bring down master and device drivers using the bring_down_all function.

Parameters
state
Returns
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

◆ on_cleanup()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn ros2_canopen::LifecycleManager::on_cleanup ( const rclcpp_lifecycle::State &  state)
protected

Callback for the Cleanup Transition.

Does nothing.

Parameters
state
Returns
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

◆ on_shutdown()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn ros2_canopen::LifecycleManager::on_shutdown ( const rclcpp_lifecycle::State &  state)
protected

Callback for the Shutdown Transition.

Does nothing.

Parameters
state
Returns
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

◆ wait_for_result()

template<typename FutureT , typename WaitTimeT >
std::future_status ros2_canopen::LifecycleManager::wait_for_result ( FutureT &  future,
WaitTimeT  time_to_wait 
)
inlineprotected

◆ get_state()

virtual unsigned int ros2_canopen::LifecycleManager::get_state ( uint8_t  node_id,
std::chrono::seconds  time_out 
)
protectedvirtual

Get the lifecycle state of a driver node.

Parameters
[in]node_id
[in]time_out
Returns
unsigned int

◆ change_state()

virtual bool ros2_canopen::LifecycleManager::change_state ( uint8_t  node_id,
uint8_t  transition,
std::chrono::seconds  time_out 
)
protectedvirtual

Change the lifecycle state of a driver node.

Parameters
[in]node_idCANopen node id of the driver
[in]transitionLifecycle transition to trigger
[in]time_outTimeout
Returns
true
false

◆ bring_up_all()

virtual bool ros2_canopen::LifecycleManager::bring_up_all ( )
protectedvirtual

Brings up master and all drivers.

This funnnction brings up the CANopen master and all drivers that are defined in the configuration. The order of bringing up drivers is arbitrary.

Returns
true
false

◆ bring_down_all()

virtual bool ros2_canopen::LifecycleManager::bring_down_all ( )
protectedvirtual

Brings down master and all drivers.

This funnnction brings up the CANopen master and all drivers that are defined in the configuration. First all drivers are brought down, then the master.

Returns
true
false

◆ bring_up_master()

virtual bool ros2_canopen::LifecycleManager::bring_up_master ( )
protectedvirtual

Brings up master.

This function brings up the CANopen master. The master transitioned twice, first the configure transition is triggered. Once the transition is successfully finished, the activate transition is triggered.

Returns
true
false

◆ bring_down_master()

virtual bool ros2_canopen::LifecycleManager::bring_down_master ( )
protectedvirtual

Bring down master.

This function brrignsdown the CANopen master. The master transitioned twice, first the deactivate transition is triggered. Once the transition is successfully finished, the cleanup transition is triggered.

Returns
true
false

◆ bring_up_driver()

virtual bool ros2_canopen::LifecycleManager::bring_up_driver ( std::string  device_name)
protectedvirtual

Brings up the drivers with specified node_id.

This function bringsup the CANopen driver for the device with the specified node_id. The driver is transitioned twice, first the configure transition is triggered. Once the transition is successfully finished, the activate transition is triggered.

Parameters
device_name
Returns
true
false

◆ bring_down_driver()

virtual bool ros2_canopen::LifecycleManager::bring_down_driver ( std::string  device_name)
protectedvirtual

Brings down the driver with specified node_id.

This function brings down the CANopen driver for the device with the specified node_id. The driver is transitioned twice, first the deactivate transition is triggered. Once the transition is successfully finished, the cleanup transition is triggered.

Parameters
device_name
Returns
true
false

◆ load_from_config()

virtual bool ros2_canopen::LifecycleManager::load_from_config ( )
protectedvirtual

Load information from configuration.

This function loads the information about the CANopen Bus specified in the configuration file and creates the necessary ROS2 services and clients.

Returns
true
false

Member Data Documentation

◆ cbg_clients

rclcpp::CallbackGroup::SharedPtr ros2_canopen::LifecycleManager::cbg_clients
protected

◆ config_

std::shared_ptr<ros2_canopen::ConfigurationManager> ros2_canopen::LifecycleManager::config_
protected

◆ drivers_get_state_clients

std::map<uint8_t, rclcpp::Client<lifecycle_msgs::srv::GetState>::SharedPtr> ros2_canopen::LifecycleManager::drivers_get_state_clients
protected

stores node_id and get_state client

◆ drivers_change_state_clients

std::map<uint8_t, rclcpp::Client<lifecycle_msgs::srv::ChangeState>::SharedPtr> ros2_canopen::LifecycleManager::drivers_change_state_clients
protected

stores node_id and change_state client

◆ device_names_to_ids

std::map<std::string, uint8_t> ros2_canopen::LifecycleManager::device_names_to_ids
protected

◆ add_driver_client_

rclcpp::Client<canopen_interfaces::srv::CONode>::SharedPtr ros2_canopen::LifecycleManager::add_driver_client_
protected

Service client object for adding a driver.

Todo:
Remove relicts?

◆ remove_driver_client_

rclcpp::Client<canopen_interfaces::srv::CONode>::SharedPtr ros2_canopen::LifecycleManager::remove_driver_client_
protected

Service client object for removing a driver.

◆ master_id_

uint8_t ros2_canopen::LifecycleManager::master_id_
protected

Stores master id.

◆ container_name_

std::string ros2_canopen::LifecycleManager::container_name_
protected

Stores name of the associated device_container.


The documentation for this class was generated from the following file: