ros2_canopen
master
C++ ROS CANopen Library
|
Lifecycle Device Manager Node. More...
#include <lifecycle_manager.hpp>
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::ConfigurationManager > | config_ |
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... | |
Lifecycle Device Manager Node.
This class provides functionalities to coordinate the lifecycle of master and device drivers that are loaded into the executor.
master | unconfigured | x | | inactive | | x |
drv1 | unconfigured | x | x | x | | inactive | | x |
driv2 | unconfigured | x | x | x | x | x | | inactive | | x |
|
inline |
Construct a new Lifecycle Device Manager Node object.
node_options |
void ros2_canopen::LifecycleManager::init | ( | std::shared_ptr< ros2_canopen::ConfigurationManager > | config | ) |
|
protected |
Callback for the Configure Transition.
This will cause the device manager to load the configuration from the configuration file.
state |
|
protected |
Callback for the Activate Transition.
This will bringup master and device drivers using the bring_up_all function.
state |
|
protected |
Callback for the Deactivate Transition.
This will bring down master and device drivers using the bring_down_all function.
state |
|
protected |
Callback for the Cleanup Transition.
Does nothing.
state |
|
protected |
Callback for the Shutdown Transition.
Does nothing.
state |
|
inlineprotected |
|
protectedvirtual |
Get the lifecycle state of a driver node.
[in] | node_id | |
[in] | time_out |
|
protectedvirtual |
Change the lifecycle state of a driver node.
[in] | node_id | CANopen node id of the driver |
[in] | transition | Lifecycle transition to trigger |
[in] | time_out | Timeout |
|
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.
|
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.
|
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.
|
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.
|
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.
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.
device_name |
|
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.
|
protected |
|
protected |
|
protected |
stores node_id and get_state client
|
protected |
stores node_id and change_state client
|
protected |
|
protected |
Service client object for adding a driver.
|
protected |
Service client object for removing a driver.
|
protected |
Stores master id.
|
protected |
Stores name of the associated device_container.