ROS2与C++入门教程-生命周期节点演示
ROS2与C++入门教程-生命周期节点演示
说明:
- 介绍ros2下实现生命周期节点,通过服务来切换不通过的周期状态
步骤:
- 安装依赖
sudo apt install ros-galactic-lifecycle-msgs
- 或源码编译lifecycle-msgs,来自rcl_interfaces
- 新建一个包cpp_lifecycle
cd ~/dev_ws/src
ros2 pkg create --build-type ament_cmake cpp_lifecycle
- 进入src目录,新建文件lifecycle_listener.cpp
cd ~/dev_ws/src/cpp_lifecycle/src
touch lifecycle_listener.cpp
- 内容如下:
#include <memory>
#include <string>
#include "lifecycle_msgs/msg/transition_event.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rcutils/logging_macros.h"
#include "std_msgs/msg/string.hpp"
/// LifecycleListener class as a simple listener node
/**
* We subscribe to two topics
* - lifecycle_chatter: The data topic from the talker
* - lc_talker__transition_event: The topic publishing
* notifications about state changes of the node
* lc_talker
*/
class LifecycleListener : public rclcpp::Node
{
public:
explicit LifecycleListener(const std::string & node_name)
: Node(node_name)
{
// Data topic from the lc_talker node
sub_data_ = this->create_subscription<std_msgs::msg::String>(
"lifecycle_chatter", 10,
std::bind(&LifecycleListener::data_callback, this, std::placeholders::_1));
// Notification event topic. All state changes
// are published here as TransitionEvents with
// a start and goal state indicating the transition
sub_notification_ = this->create_subscription<lifecycle_msgs::msg::TransitionEvent>(
"/lc_talker/transition_event",
10,
std::bind(&LifecycleListener::notification_callback, this, std::placeholders::_1));
}
void data_callback(std_msgs::msg::String::ConstSharedPtr msg)
{
RCLCPP_INFO(get_logger(), "data_callback: %s", msg->data.c_str());
}
void notification_callback(lifecycle_msgs::msg::TransitionEvent::ConstSharedPtr msg)
{
RCLCPP_INFO(
get_logger(), "notify callback: Transition from state %s to %s",
msg->start_state.label.c_str(), msg->goal_state.label.c_str());
}
private:
std::shared_ptr<rclcpp::Subscription<std_msgs::msg::String>> sub_data_;
std::shared_ptr<rclcpp::Subscription<lifecycle_msgs::msg::TransitionEvent>>
sub_notification_;
};
int main(int argc, char ** argv)
{
// force flush of the stdout buffer.
// this ensures a correct sync of all prints
// even when executed simultaneously within the launch file.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
rclcpp::init(argc, argv);
auto lc_listener = std::make_shared<LifecycleListener>("lc_listener");
rclcpp::spin(lc_listener);
rclcpp::shutdown();
return 0;
}
- 进入src目录,新建文件lifecycle_talker.cpp
cd ~/dev_ws/src/cpp_lifecycle/src
touch lifecycle_talker.cpp
- 内容如下:
#include <chrono>
#include <iostream>
#include <memory>
#include <string>
#include <thread>
#include <utility>
#include "lifecycle_msgs/msg/transition.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/publisher.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
#include "rcutils/logging_macros.h"
#include "std_msgs/msg/string.hpp"
using namespace std::chrono_literals;
/// LifecycleTalker inheriting from rclcpp_lifecycle::LifecycleNode
/**
* The lifecycle talker does not like the regular "talker" node
* inherit from node, but rather from lifecyclenode. This brings
* in a set of callbacks which are getting invoked depending on
* the current state of the node.
* Every lifecycle node has a set of services attached to it
* which make it controllable from the outside and invoke state
* changes.
* Available Services as for Beta1:
* - <node_name>__get_state
* - <node_name>__change_state
* - <node_name>__get_available_states
* - <node_name>__get_available_transitions
* Additionally, a publisher for state change notifications is
* created:
* - <node_name>__transition_event
*/
class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode
{
public:
/// LifecycleTalker constructor
/**
* The lifecycletalker/lifecyclenode constructor has the same
* arguments a regular node.
*/
explicit LifecycleTalker(const std::string & node_name, bool intra_process_comms = false)
: rclcpp_lifecycle::LifecycleNode(node_name,
rclcpp::NodeOptions().use_intra_process_comms(intra_process_comms))
{}
/// Callback for walltimer in order to publish the message.
/**
* Callback for walltimer. This function gets invoked by the timer
* and executes the publishing.
* For this demo, we ask the node for its current state. If the
* lifecycle publisher is not activate, we still invoke publish, but
* the communication is blocked so that no messages is actually transferred.
*/
void
publish()
{
static size_t count = 0;
auto msg = std::make_unique<std_msgs::msg::String>();
msg->data = "Lifecycle HelloWorld #" + std::to_string(++count);
// Print the current state for demo purposes
if (!pub_->is_activated()) {
RCLCPP_INFO(
get_logger(), "Lifecycle publisher is currently inactive. Messages are not published.");
} else {
RCLCPP_INFO(
get_logger(), "Lifecycle publisher is active. Publishing: [%s]", msg->data.c_str());
}
// We independently from the current state call publish on the lifecycle
// publisher.
// Only if the publisher is in an active state, the message transfer is
// enabled and the message actually published.
pub_->publish(std::move(msg));
}
/// Transition callback for state configuring
/**
* on_configure callback is being called when the lifecycle node
* enters the "configuring" state.
* Depending on the return value of this function, the state machine
* either invokes a transition to the "inactive" state or stays
* in "unconfigured".
* TRANSITION_CALLBACK_SUCCESS transitions to "inactive"
* TRANSITION_CALLBACK_FAILURE transitions to "unconfigured"
* TRANSITION_CALLBACK_ERROR or any uncaught exceptions to "errorprocessing"
*/
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_configure(const rclcpp_lifecycle::State &)
{
// This callback is supposed to be used for initialization and
// configuring purposes.
// We thus initialize and configure our publishers and timers.
// The lifecycle node API does return lifecycle components such as
// lifecycle publishers. These entities obey the lifecycle and
// can comply to the current state of the node.
// As of the beta version, there is only a lifecycle publisher
// available.
pub_ = this->create_publisher<std_msgs::msg::String>("lifecycle_chatter", 10);
timer_ = this->create_wall_timer(
1s, std::bind(&LifecycleTalker::publish, this));
RCLCPP_INFO(get_logger(), "on_configure() is called.");
// We return a success and hence invoke the transition to the next
// step: "inactive".
// If we returned TRANSITION_CALLBACK_FAILURE instead, the state machine
// would stay in the "unconfigured" state.
// In case of TRANSITION_CALLBACK_ERROR or any thrown exception within
// this callback, the state machine transitions to state "errorprocessing".
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
/// Transition callback for state activating
/**
* on_activate callback is being called when the lifecycle node
* enters the "activating" state.
* Depending on the return value of this function, the state machine
* either invokes a transition to the "active" state or stays
* in "inactive".
* TRANSITION_CALLBACK_SUCCESS transitions to "active"
* TRANSITION_CALLBACK_FAILURE transitions to "inactive"
* TRANSITION_CALLBACK_ERROR or any uncaught exceptions to "errorprocessing"
*/
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_activate(const rclcpp_lifecycle::State & state)
{
// The parent class method automatically transition on managed entities
// (currently, LifecyclePublisher).
// pub_->on_activate() could also be called manually here.
// Overriding this method is optional, a lot of times the default is enough.
LifecycleNode::on_activate(state);
pub_->on_activate();
RCUTILS_LOG_INFO_NAMED(get_name(), "on_activate() is called.");
// Let's sleep for 2 seconds.
// We emulate we are doing important
// work in the activating phase.
std::this_thread::sleep_for(2s);
// We return a success and hence invoke the transition to the next
// step: "active".
// If we returned TRANSITION_CALLBACK_FAILURE instead, the state machine
// would stay in the "inactive" state.
// In case of TRANSITION_CALLBACK_ERROR or any thrown exception within
// this callback, the state machine transitions to state "errorprocessing".
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
/// Transition callback for state deactivating
/**
* on_deactivate callback is being called when the lifecycle node
* enters the "deactivating" state.
* Depending on the return value of this function, the state machine
* either invokes a transition to the "inactive" state or stays
* in "active".
* TRANSITION_CALLBACK_SUCCESS transitions to "inactive"
* TRANSITION_CALLBACK_FAILURE transitions to "active"
* TRANSITION_CALLBACK_ERROR or any uncaught exceptions to "errorprocessing"
*/
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_deactivate(const rclcpp_lifecycle::State & state)
{
// The parent class method automatically transition on managed entities
// (currently, LifecyclePublisher).
// pub_->on_deactivate() could also be called manually here.
// Overriding this method is optional, a lot of times the default is enough.
LifecycleNode::on_deactivate(state);
RCUTILS_LOG_INFO_NAMED(get_name(), "on_deactivate() is called.");
// We return a success and hence invoke the transition to the next
// step: "inactive".
// If we returned TRANSITION_CALLBACK_FAILURE instead, the state machine
// would stay in the "active" state.
// In case of TRANSITION_CALLBACK_ERROR or any thrown exception within
// this callback, the state machine transitions to state "errorprocessing".
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
/// Transition callback for state cleaningup
/**
* on_cleanup callback is being called when the lifecycle node
* enters the "cleaningup" state.
* Depending on the return value of this function, the state machine
* either invokes a transition to the "unconfigured" state or stays
* in "inactive".
* TRANSITION_CALLBACK_SUCCESS transitions to "unconfigured"
* TRANSITION_CALLBACK_FAILURE transitions to "inactive"
* TRANSITION_CALLBACK_ERROR or any uncaught exceptions to "errorprocessing"
*/
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_cleanup(const rclcpp_lifecycle::State &)
{
// In our cleanup phase, we release the shared pointers to the
// timer and publisher. These entities are no longer available
// and our node is "clean".
timer_.reset();
pub_.reset();
RCUTILS_LOG_INFO_NAMED(get_name(), "on cleanup is called.");
// We return a success and hence invoke the transition to the next
// step: "unconfigured".
// If we returned TRANSITION_CALLBACK_FAILURE instead, the state machine
// would stay in the "inactive" state.
// In case of TRANSITION_CALLBACK_ERROR or any thrown exception within
// this callback, the state machine transitions to state "errorprocessing".
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
/// Transition callback for state shutting down
/**
* on_shutdown callback is being called when the lifecycle node
* enters the "shuttingdown" state.
* Depending on the return value of this function, the state machine
* either invokes a transition to the "finalized" state or stays
* in its current state.
* TRANSITION_CALLBACK_SUCCESS transitions to "finalized"
* TRANSITION_CALLBACK_FAILURE transitions to current state
* TRANSITION_CALLBACK_ERROR or any uncaught exceptions to "errorprocessing"
*/
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_shutdown(const rclcpp_lifecycle::State & state)
{
// In our shutdown phase, we release the shared pointers to the
// timer and publisher. These entities are no longer available
// and our node is "clean".
timer_.reset();
pub_.reset();
RCUTILS_LOG_INFO_NAMED(
get_name(),
"on shutdown is called from state %s.",
state.label().c_str());
// We return a success and hence invoke the transition to the next
// step: "finalized".
// If we returned TRANSITION_CALLBACK_FAILURE instead, the state machine
// would stay in the current state.
// In case of TRANSITION_CALLBACK_ERROR or any thrown exception within
// this callback, the state machine transitions to state "errorprocessing".
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
private:
// We hold an instance of a lifecycle publisher. This lifecycle publisher
// can be activated or deactivated regarding on which state the lifecycle node
// is in.
// By default, a lifecycle publisher is inactive by creation and has to be
// activated to publish messages into the ROS world.
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<std_msgs::msg::String>> pub_;
// We hold an instance of a timer which periodically triggers the publish function.
// As for the beta version, this is a regular timer. In a future version, a
// lifecycle timer will be created which obeys the same lifecycle management as the
// lifecycle publisher.
std::shared_ptr<rclcpp::TimerBase> timer_;
};
/**
* A lifecycle node has the same node API
* as a regular node. This means we can spawn a
* node, give it a name and add it to the executor.
*/
int main(int argc, char * argv[])
{
// force flush of the stdout buffer.
// this ensures a correct sync of all prints
// even when executed simultaneously within the launch file.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor exe;
std::shared_ptr<LifecycleTalker> lc_node =
std::make_shared<LifecycleTalker>("lc_talker");
exe.add_node(lc_node->get_node_base_interface());
exe.spin();
rclcpp::shutdown();
return 0;
}
- 进入src目录,新建文件lifecycle_service_client.cpp
cd ~/dev_ws/src/cpp_lifecycle/src
touch lifecycle_service_client.cpp
- 内容如下:
#include <chrono>
#include <memory>
#include <string>
#include <thread>
#include "lifecycle_msgs/msg/state.hpp"
#include "lifecycle_msgs/msg/transition.hpp"
#include "lifecycle_msgs/srv/change_state.hpp"
#include "lifecycle_msgs/srv/get_state.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rcutils/logging_macros.h"
using namespace std::chrono_literals;
// which node to handle
static constexpr char const * lifecycle_node = "lc_talker";
// Every lifecycle node has various services
// attached to it. By convention, we use the format of
// <node name>/<service name>.
// In this demo, we use get_state and change_state
// and thus the two service topics are:
// lc_talker/get_state
// lc_talker/change_state
static constexpr char const * node_get_state_topic = "lc_talker/get_state";
static constexpr char const * node_change_state_topic = "lc_talker/change_state";
template<typename FutureT, typename WaitTimeT>
std::future_status
wait_for_result(
FutureT & future,
WaitTimeT time_to_wait)
{
auto end = std::chrono::steady_clock::now() + time_to_wait;
std::chrono::milliseconds wait_period(100);
std::future_status status = std::future_status::timeout;
do {
auto now = std::chrono::steady_clock::now();
auto time_left = end - now;
if (time_left <= std::chrono::seconds(0)) {break;}
status = future.wait_for((time_left < wait_period) ? time_left : wait_period);
} while (rclcpp::ok() && status != std::future_status::ready);
return status;
}
class LifecycleServiceClient : public rclcpp::Node
{
public:
explicit LifecycleServiceClient(const std::string & node_name)
: Node(node_name)
{}
void
init()
{
// Every lifecycle node spawns automatically a couple
// of services which allow an external interaction with
// these nodes.
// The two main important ones are GetState and ChangeState.
client_get_state_ = this->create_client<lifecycle_msgs::srv::GetState>(
node_get_state_topic);
client_change_state_ = this->create_client<lifecycle_msgs::srv::ChangeState>(
node_change_state_topic);
}
/// Requests the current state of the node
/**
* In this function, we send a service request
* asking for the current state of the node
* lc_talker.
* If it does return within the given time_out,
* we return the current state of the node, if
* not, we return an unknown state.
* \param time_out Duration in seconds specifying
* how long we wait for a response before returning
* unknown state
*/
unsigned int
get_state(std::chrono::seconds time_out = 3s)
{
auto request = std::make_shared<lifecycle_msgs::srv::GetState::Request>();
if (!client_get_state_->wait_for_service(time_out)) {
RCLCPP_ERROR(
get_logger(),
"Service %s is not available.",
client_get_state_->get_service_name());
return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
}
// We send the service request for asking the current
// state of the lc_talker node.
auto future_result = client_get_state_->async_send_request(request);
// Let's wait until we have the answer from the node.
// If the request times out, we return an unknown state.
auto future_status = wait_for_result(future_result, time_out);
if (future_status != std::future_status::ready) {
RCLCPP_ERROR(
get_logger(), "Server time out while getting current state for node %s", lifecycle_node);
return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
}
// We have an succesful answer. So let's print the current state.
if (future_result.get()) {
RCLCPP_INFO(
get_logger(), "Node %s has current state %s.",
lifecycle_node, future_result.get()->current_state.label.c_str());
return future_result.get()->current_state.id;
} else {
RCLCPP_ERROR(
get_logger(), "Failed to get current state for node %s", lifecycle_node);
return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
}
}
/// Invokes a transition
/**
* We send a Service request and indicate
* that we want to invoke transition with
* the id "transition".
* By default, these transitions are
* - configure
* - activate
* - cleanup
* - shutdown
* \param transition id specifying which
* transition to invoke
* \param time_out Duration in seconds specifying
* how long we wait for a response before returning
* unknown state
*/
bool
change_state(std::uint8_t transition, std::chrono::seconds time_out = 3s)
{
auto request = std::make_shared<lifecycle_msgs::srv::ChangeState::Request>();
request->transition.id = transition;
if (!client_change_state_->wait_for_service(time_out)) {
RCLCPP_ERROR(
get_logger(),
"Service %s is not available.",
client_change_state_->get_service_name());
return false;
}
// We send the request with the transition we want to invoke.
auto future_result = client_change_state_->async_send_request(request);
// Let's wait until we have the answer from the node.
// If the request times out, we return an unknown state.
auto future_status = wait_for_result(future_result, time_out);
if (future_status != std::future_status::ready) {
RCLCPP_ERROR(
get_logger(), "Server time out while getting current state for node %s", lifecycle_node);
return false;
}
// We have an answer, let's print our success.
if (future_result.get()->success) {
RCLCPP_INFO(
get_logger(), "Transition %d successfully triggered.", static_cast<int>(transition));
return true;
} else {
RCLCPP_WARN(
get_logger(), "Failed to trigger transition %u", static_cast<unsigned int>(transition));
return false;
}
}
private:
std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::GetState>> client_get_state_;
std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::ChangeState>> client_change_state_;
};
/**
* This is a little independent
* script which triggers the
* default lifecycle of a node.
* It starts with configure, activate,
* deactivate, activate, deactivate,
* cleanup and finally shutdown
*/
void
callee_script(std::shared_ptr<LifecycleServiceClient> lc_client)
{
rclcpp::WallRate time_between_state_changes(0.1); // 10s
// configure
{
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE)) {
return;
}
if (!lc_client->get_state()) {
return;
}
}
// activate
{
time_between_state_changes.sleep();
if (!rclcpp::ok()) {
return;
}
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE)) {
return;
}
if (!lc_client->get_state()) {
return;
}
}
// deactivate
{
time_between_state_changes.sleep();
if (!rclcpp::ok()) {
return;
}
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE)) {
return;
}
if (!lc_client->get_state()) {
return;
}
}
// activate it again
{
time_between_state_changes.sleep();
if (!rclcpp::ok()) {
return;
}
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE)) {
return;
}
if (!lc_client->get_state()) {
return;
}
}
// and deactivate it again
{
time_between_state_changes.sleep();
if (!rclcpp::ok()) {
return;
}
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE)) {
return;
}
if (!lc_client->get_state()) {
return;
}
}
// we cleanup
{
time_between_state_changes.sleep();
if (!rclcpp::ok()) {
return;
}
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP)) {
return;
}
if (!lc_client->get_state()) {
return;
}
}
// and finally shutdown
// Note: We have to be precise here on which shutdown transition id to call
// We are currently in the unconfigured state and thus have to call
// TRANSITION_UNCONFIGURED_SHUTDOWN
{
time_between_state_changes.sleep();
if (!rclcpp::ok()) {
return;
}
if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_UNCONFIGURED_SHUTDOWN))
{
return;
}
if (!lc_client->get_state()) {
return;
}
}
}
void
wake_executor(std::shared_future<void> future, rclcpp::executors::SingleThreadedExecutor & exec)
{
future.wait();
// Wake the executor when the script is done
// https://github.com/ros2/rclcpp/issues/1916
exec.cancel();
}
int main(int argc, char ** argv)
{
// force flush of the stdout buffer.
// this ensures a correct sync of all prints
// even when executed simultaneously within the launch file.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
rclcpp::init(argc, argv);
auto lc_client = std::make_shared<LifecycleServiceClient>("lc_client");
lc_client->init();
rclcpp::executors::SingleThreadedExecutor exe;
exe.add_node(lc_client);
std::shared_future<void> script = std::async(
std::launch::async,
std::bind(callee_script, lc_client));
auto wake_exec = std::async(
std::launch::async,
std::bind(wake_executor, script, std::ref(exe)));
exe.spin_until_future_complete(script);
rclcpp::shutdown();
return 0;
}
- 编译package.xml
- 在<buildtool_depend>ament_cmake</buildtool_depend>后增加
<depend>lifecycle_msgs</depend>
<depend>rclcpp_lifecycle</depend>
<depend>std_msgs</depend>
- 编译CMakelist.txt
- 在project(cpp_lifecycle)后增加
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
- 在find_package(ament_cmake REQUIRED)后增加
find_package(rclcpp_lifecycle REQUIRED)
find_package(lifecycle_msgs REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
- 生成执行文件
### demos
add_executable(lifecycle_talker
src/lifecycle_talker.cpp)
ament_target_dependencies(lifecycle_talker
"lifecycle_msgs"
"rclcpp_lifecycle"
"std_msgs"
)
add_executable(lifecycle_listener
src/lifecycle_listener.cpp)
ament_target_dependencies(lifecycle_listener
"lifecycle_msgs"
"rclcpp_lifecycle"
"std_msgs"
)
add_executable(lifecycle_service_client
src/lifecycle_service_client.cpp)
ament_target_dependencies(lifecycle_service_client
"lifecycle_msgs"
"rclcpp_lifecycle"
"std_msgs"
)
- 安装相关库文件和执行文件
install(TARGETS
lifecycle_talker
lifecycle_listener
lifecycle_service_client
DESTINATION lib/${PROJECT_NAME})
- 编译包
colcon build --symlink-install --packages-select cpp_lifecycle
- 加载工作空间
. install/setup.bash
- 启动lifecycle_talker :
$ ros2 run cpp_lifecycle lifecycle_talker
[INFO] [1651922187.300843642] [lc_talker]: on_configure() is called.
[INFO] [1651922188.301031181] [lc_talker]: Lifecycle publisher is currently inactive. Messages are not published.
[WARN] [1651922188.301163661] [LifecyclePublisher]: Trying to publish message on the topic '/lifecycle_chatter', but the publisher is not activated
[INFO] [1651922189.301027201] [lc_talker]: Lifecycle publisher is currently inactive. Messages are not published.
[WARN] [1651922189.301151330] [LifecyclePublisher]: Trying to publish message on the topic '/lifecycle_chatter', but the publisher is not activated
[INFO] [1651922190.301018995] [lc_talker]: Lifecycle publisher is currently inactive. Messages are not published.
[WARN] [1651922190.301134320] [LifecyclePublisher]: Trying to publish message on the topic '/lifecycle_chatter', but the publisher is not activated
[INFO] [1651922191.301052527] [lc_talker]: Lifecycle publisher is currently inactive. Messages are not published.
[WARN] [1651922191.301172036] [LifecyclePublisher]: Trying to publish message on the topic '/lifecycle_chatter', but the publisher is not activated
[INFO] [1651922192.301064301] [lc_talker]: Lifecycle publisher is currently inactive. Messages are not published.
[WARN] [1651922192.301182779] [LifecyclePublisher]: Trying to publish message on the topic '/lifecycle_chatter', but the publisher is not activated
[INFO] [1651922193.301078819] [lc_talker]: Lifecycle publisher is currently inactive. Messages are not published.
[WARN] [1651922193.301201882] [LifecyclePublisher]: Trying to publish message on the topic '/lifecycle_chatter', but the publisher is not activated
[INFO] [1651922194.301090893] [lc_talker]: Lifecycle publisher is currently inactive. Messages are not published.
[WARN] [1651922194.301222935] [LifecyclePublisher]: Trying to publish message on the topic '/lifecycle_chatter', but the publisher is not activated
[INFO] [1651922195.301110449] [lc_talker]: Lifecycle publisher is currently inactive. Messages are not published.
[WARN] [1651922195.301263831] [LifecyclePublisher]: Trying to publish message on the topic '/lifecycle_chatter', but the publisher is not activated
[INFO] [1651922196.301121339] [lc_talker]: Lifecycle publisher is currently inactive. Messages are not published.
[WARN] [1651922196.301245088] [LifecyclePublisher]: Trying to publish message on the topic '/lifecycle_chatter', but the publisher is not activated
[INFO] [1651922197.300231541] [lc_talker]: on_activate() is called.
[INFO] [1651922199.300787838] [lc_talker]: Lifecycle publisher is active. Publishing: [Lifecycle HelloWorld #10]
[INFO] [1651922199.301023581] [lc_talker]: Lifecycle publisher is active. Publishing: [Lifecycle HelloWorld #11]
[INFO] [1651922200.301192129] [lc_talker]: Lifecycle publisher is active. Publishing: [Lifecycle HelloWorld #12]
[INFO] [1651922201.301188500] [lc_talker]: Lifecycle publisher is active. Publishing: [Lifecycle HelloWorld #13]
[INFO] [1651922202.301202422] [lc_talker]: Lifecycle publisher is active. Publishing: [Lifecycle HelloWorld #14]
- 启动lifecycle_listener :
$ ros2 run cpp_lifecycle lifecycle_listener
[INFO] [1651922187.300002881] [lc_listener]: notify callback: Transition from state unconfigured to configuring
[INFO] [1651922187.301119939] [lc_listener]: notify callback: Transition from state configuring to inactive
[INFO] [1651922197.300461413] [lc_listener]: notify callback: Transition from state inactive to activating
[INFO] [1651922199.300879849] [lc_listener]: notify callback: Transition from state activating to active
[INFO] [1651922199.301082054] [lc_listener]: data_callback: Lifecycle HelloWorld #10
[INFO] [1651922199.301243890] [lc_listener]: data_callback: Lifecycle HelloWorld #11
[INFO] [1651922200.301670082] [lc_listener]: data_callback: Lifecycle HelloWorld #12
[INFO] [1651922201.301684865] [lc_listener]: data_callback: Lifecycle HelloWorld #13
[INFO] [1651922202.301662502] [lc_listener]: data_callback: Lifecycle HelloWorld #14
- 启动lifecycle_service_client:
$ ros2 run cpp_lifecycle lifecycle_service_client
[INFO] [1651922187.301272269] [lc_client]: Transition 1 successfully triggered.
[INFO] [1651922187.301621397] [lc_client]: Node lc_talker has current state inactive.
[INFO] [1651922199.300992992] [lc_client]: Transition 3 successfully triggered.
[INFO] [1651922199.301809491] [lc_client]: Node lc_talker has current state active.
启动了lifecycle_service_client后才开始触发输出,并在切换到activate状态之后才会发布话题信息
稳定状态:
unconfigured #未配置
inactive #未激活
active #已激活
shutdown #已关闭
- 中间状态:
configuring #正在配置
activating #正在激活
deactivating #正在停用
cleaningup #正在清除
shuttingdown #正在关闭
可使用的转换是:
configure #配置
activate #激活
deactivate #停用
cleanup #清除
shutdown #关闭单独使用状态转换命令:
#设置为配置
ros2 lifecycle set /lc_talker configure
#设置为激活
ros2 lifecycle set /lc_talker activate
参考:
获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号