ros2中测试生命周期节点中的转移状态函数

测试环境: Ubuntu22.04

测试平台: ROS2 humble

在ros2中可以调用的状态转换主要有以下五种:

  • 配置(configure)

  • 激活(activate)

  • 停用(deactivate)

  • 清理(cleanup)

  • 关闭(shutdown)

其中状态的转移可以通过以下五个函数进行:

  • on_configure():当节点从未配置状态转换到非激活状态时,此函数会被调用。

  • on_activate():当节点从非激活状态转换到激活状态时,此函数会被调用。

  • on_deactivate():当节点从激活状态转换到非激活状态时,此函数会被调用。

  • on_cleanup():当节点从非激活状态转换到未配置状态时,此函数会被调用。

  • on_shutdown():当节点从任何状态转换到关闭状态时,此函数会被调用。

下面演示这五个函数的具体用法以及转台转移过程。

1.在home下创建工作空间

mkdir lifecyclenode/
cd lifecyclenode/
mkdir src/
colcon build

2.在/src下创建功能包

cd src/
ros2 pkg create life --build-type ament_cmake --dependencies rclcpp std_msgs rclcpp_lifecycle --node-name test01

3.修改test01中的代码如下:

#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

class LifecycleNode:public rclcpp_lifecycle::LifecycleNode
{
public:
  LifecycleNode():rclcpp_lifecycle::LifecycleNode("lifecycle_node")
  {
  }

  //当节点从未配置状态转换到非激活状态时调用下面的函数
  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(const rclcpp_lifecycle::State & )
  {
    RCLCPP_INFO(this->get_logger(), "Configuring...");
    publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
    return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
  }

  //当节点从非激活状态转换到激活状态时会调用下面的函数
  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(const rclcpp_lifecycle::State & )
  {
    RCLCPP_INFO(this->get_logger(), "Activating...");
    publisher_->on_activate();
    return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
  }

  //当节点从激活状态转换到非激活状态时会调用下面的函数
  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & )
  {
    RCLCPP_INFO(this->get_logger(), "Deactivating...");
    publisher_->on_deactivate();
    return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
  }

  //当节点从非激活状态转换到未配置状态时调用下面的函数
  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & )
  {
    RCLCPP_INFO(this->get_logger(), "Cleanup...");
    publisher_.reset();
    return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
  }

  //当节点从任何状态转换到关闭状态时调用下面的函数
  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & )
  {
    RCLCPP_INFO(this->get_logger(), "Shutdown!");
    //进行关闭的具体
    rclcpp::shutdown();
    return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
  }

  //执行出现错误时调用下面的函数
  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_error(const rclcpp_lifecycle::State & )
  {
    RCLCPP_INFO(this->get_logger(), "Error!");
    //进行具体的错误处理
    return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
  }

private:
  rclcpp_lifecycle::LifecyclePublisher<std_msgs::msg::String>::SharedPtr publisher_;
};

int main(int argc, char ** argv)
{
  rclcpp::init(argc, argv);
  auto node = std::make_shared<LifecycleNode>();
  rclcpp::spin(node->get_node_base_interface());
  rclcpp::shutdown();
  return 0;
}

        上面的代码的节点在创建时会自动进入unconfigured状态。可以通过在命令行界面输入指令来控制其状态的转换。每个状态转换都会触发相应的回调函数。

4.通过命令行切换其状态

首先在lifecyclenode目录下编译功能包

colcon build --packages-select life

 接着执行文件

. install/setup.bash
ros2 run life test01     

执行后会看到什么消息都没有,因为并没有发生状态转移,也就不会有输出,接下来就需要打开一个新的终端,在命令行中输入:

ros2 lifecycle set /lifecycle_node configure 

 这可以将节点从unconfigured转移至configure状态,同时可以看到文件执行下的输出:

 

接下来输入,将节点从configure转移至activate状态: 

 ros2 lifecycle set /lifecycle_node activate

同时获得以下输出:

 输入:

ros2 lifecycle set /lifecycle_node deactivate

将节点从activate转移至deactivate状态,获得以下输出:

 

 接着测试cleanup状态,转回到unconfigured状态:

ros2 lifecycle set /lifecycle_node cleanup

 

最后执行shutdown,看看是否能正常关闭:

ros2 lifecycle set /lifecycle_node shutdown 

可以看到虽然有错误,但确实可以关闭节点。 

  • 48
    点赞
  • 29
    收藏
    觉得还不错? 一键收藏
  • 1
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值