Class LifecycleManager

Inheritance Relationships

Base Type

  • public rclcpp::Node

Class Documentation

class LifecycleManager : public rclcpp::Node

Implements service interface to transition the lifecycle nodes of Nav2 stack. It receives transition request and then uses lifecycle interface to change lifecycle node’s state.

Public Functions

explicit LifecycleManager(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

A constructor for nav2_lifecycle_manager::LifecycleManager.

Parameters:

options – Additional options to control creation of the node.

~LifecycleManager()

A destructor for nav2_lifecycle_manager::LifecycleManager.

Protected Functions

void managerCallback(const std::shared_ptr<rmw_request_id_t> request_header, const std::shared_ptr<ManageLifecycleNodes::Request> request, std::shared_ptr<ManageLifecycleNodes::Response> response)

Lifecycle node manager callback function.

Parameters:
  • request_header – Header of the service request

  • request – Service request

  • reponse – Service response

void isActiveCallback(const std::shared_ptr<rmw_request_id_t> request_header, const std::shared_ptr<std_srvs::srv::Trigger::Request> request, std::shared_ptr<std_srvs::srv::Trigger::Response> response)

Trigger callback function checks if the managed nodes are in active state.

Parameters:
  • request_header – Header of the request

  • request – Service request

  • reponse – Service response

bool startup()

Start up managed nodes.

Returns:

true or false

bool shutdown()

Deactivate, clean up and shut down all the managed nodes.

Returns:

true or false

bool reset(bool hard_reset = false)

Reset all the managed nodes.

Returns:

true or false

bool pause()

Pause all the managed nodes.

Returns:

true or false

bool resume()

Resume all the managed nodes.

Returns:

true or false

void onRclPreshutdown()

Perform preshutdown activities before our Context is shutdown. Note that this is related to our Context’s shutdown sequence, not the lifecycle node state machine or shutdown().

void createLifecycleServiceClients()

Support function for creating service clients.

void shutdownAllNodes()

Support function for shutdown.

void destroyLifecycleServiceClients()

Destroy all the lifecycle service clients.

void createBondTimer()

Support function for creating bond timer.

bool createBondConnection(const std::string &node_name)

Support function for creating bond connections.

void destroyBondTimer()

Support function for killing bond connections.

void checkBondConnections()

@ brief Support function for checking on bond connections will take down system if there’s something non-responsive

void checkBondRespawnConnection()

@ brief Support function for checking on bond connections will bring back the system if something goes from non-responsive to responsive

bool changeStateForNode(const std::string &node_name, std::uint8_t transition)

For a node, transition to the new target state.

bool changeStateForAllNodes(std::uint8_t transition, bool hard_change = false)

For each node in the map, transition to the new target state.

void message(const std::string &msg)

Helper function to highlight the output on the console.

void CreateActiveDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)

function to check if the Nav2 system is active

void registerRclPreshutdownCallback()

Register our preshutdown callback for this Node’s rcl Context. The callback fires before this Node’s Context is shutdown. Note this is not directly related to the lifecycle state machine or the shutdown() instance function.

Protected Attributes

rclcpp::CallbackGroup::SharedPtr callback_group_
std::unique_ptr<nav2_util::NodeThread> service_thread_
rclcpp::Service<ManageLifecycleNodes>::SharedPtr manager_srv_
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr is_active_srv_
rclcpp::TimerBase::SharedPtr init_timer_
rclcpp::TimerBase::SharedPtr bond_timer_
rclcpp::TimerBase::SharedPtr bond_respawn_timer_
std::chrono::milliseconds bond_timeout_
std::map<std::string, std::shared_ptr<bond::Bond>> bond_map_
std::map<std::string, std::shared_ptr<nav2_util::LifecycleServiceClient>> node_map_
std::map<std::uint8_t, std::string> transition_label_map_
std::unordered_map<std::uint8_t, std::uint8_t> transition_state_map_
std::vector<std::string> node_names_
bool autostart_
bool attempt_respawn_reconnection_
bool system_active_ = {false}
diagnostic_updater::Updater diagnostics_updater_
rclcpp::Time bond_respawn_start_time_ = {0}
rclcpp::Duration bond_respawn_max_duration_ = {10s}