Class LifecycleManagerClient

Class Documentation

class LifecycleManagerClient

Public Functions

explicit LifecycleManagerClient(const std::string &name, std::shared_ptr<rclcpp::Node> parent_node)

A constructor for LifeCycleMangerClient.

Parameters:
  • name – Managed node name

  • parent_node – Node that execute the service calls

bool startup(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))

Make start up service call.

Returns:

true or false

bool shutdown(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))

Make shutdown service call.

Returns:

true or false

bool pause(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))

Make pause service call.

Returns:

true or false

bool resume(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))

Make resume service call.

Returns:

true or false

bool reset(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))

Make reset service call.

Returns:

true or false

SystemStatus is_active(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))

Check if lifecycle node manager server is active.

Returns:

ACTIVE or INACTIVE or TIMEOUT

void set_initial_pose(double x, double y, double theta)

Set initial pose with covariance.

Parameters:
  • x – X position

  • y – Y position

  • theta – orientation

bool navigate_to_pose(double x, double y, double theta)

Send goal pose to NavigationToPose action server.

Parameters:
  • x – X position

  • y – Y position

  • theta – orientation

Returns:

true or false

Protected Types

using ManageLifecycleNodes = nav2_msgs::srv::ManageLifecycleNodes

Protected Functions

bool callService(uint8_t command, const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))

A generic method used to call startup, shutdown, etc.

Parameters:

command

Protected Attributes

rclcpp::Node::SharedPtr node_
std::shared_ptr<nav2_util::ServiceClient<ManageLifecycleNodes>> manager_client_
std::shared_ptr<nav2_util::ServiceClient<std_srvs::srv::Trigger>> is_active_client_
std::string manage_service_name_
std::string active_service_name_