Class LifecycleManager

Inheritance Relationships

Base Type

  • public rclcpp_lifecycle::LifecycleNode

Class Documentation

class LifecycleManager : public rclcpp_lifecycle::LifecycleNode

Lifecycle Device Manager Node.

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

Public Functions

inline LifecycleManager(const rclcpp::NodeOptions &node_options)

Construct a new Lifecycle Device Manager Node object.

Parameters:

node_options

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

Protected Functions

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

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

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

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

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

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

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

Callback for the Cleanup Transition.

Does nothing.

Parameters:

state

Returns:

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

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

Callback for the Shutdown Transition.

Does nothing.

Parameters:

state

Returns:

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

template<typename FutureT, typename WaitTimeT>
inline 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.

Parameters:
  • node_id[in]

  • time_out[in]

Returns:

unsigned int

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

Change the lifecycle state of a driver node.

Parameters:
  • node_id[in] CANopen node id of the driver

  • transition[in] Lifecycle transition to trigger

  • time_out[in] Timeout

Returns:

true

Returns:

false

virtual bool bring_up_all()

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

Returns:

false

virtual bool bring_down_all()

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

Returns:

false

virtual bool bring_up_master()

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

Returns:

false

virtual bool bring_down_master()

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

Returns:

false

virtual bool bring_up_driver(std::string device_name)

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

Returns:

false

virtual bool bring_down_driver(std::string device_name)

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

Returns:

false

virtual bool load_from_config()

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

Returns:

false

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

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

stores node_id and change_state client

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.

Todo:

Remove relicts?

rclcpp::Client<canopen_interfaces::srv::CONode>::SharedPtr remove_driver_client_

Service client object for removing a driver.

uint8_t master_id_

Stores master id.

std::string container_name_

Stores name of the associated device_container.