ROS2 Launch文件编辑及运行

在第一版的 ROS 中launch 一般使用 xml 文件的格式进行编写和运行,但从 ROS2 中增添了 py 的 python 的可执行文件


作用
  • 为了解决频繁的 ros2 run 命令,和多个节点之间的运行及关闭
特性
  • launch文件允许我们同时启动和配置多个包含 ROS 2 节点的可执行文件,设计了一套完整的语法和规则的文件来帮助我们组织节点的启动
编写

使用官方推荐的 python 的方式来编写 launch 文件(Python 拥有 xml 和 Yaml )

src 工程文件结构
在这里插入图片描述


步骤

  1. 创建 src 及功能包
  2. 创建 src 及功能包
  3. 在功能包内创建 launch 文件夹,编写 .py 文件
  4. CMakeLists.txt 文件的更改
  5. 编译运行


创建 src 及功能包

打开终端运行

ros2 pkg create robot_startup --build-type ament_cmake --destination-directory src


编写好 cpp 源文件

内容为以 500 ms 发布消息,内容为 “one

#include "rclcpp/rclcpp.hpp"
#include <iostream>
#include "std_msgs/msg/string.hpp"


class Publisher:public rclcpp::Node
{
public:
    Publisher(std::string name) : Node(name)
    {
        RCLCPP_INFO(this->get_logger(), "大家好,我是%s.", name.c_str());
        command_publisher_ = this->create_publisher<std_msgs::msg::String>("command", 10);
        // 创建定时器,500ms为周期,定时发布
        timer_ = this->create_wall_timer(std::chrono::milliseconds(500), std::bind(&Publisher::timer_callback, this));
    }
private:
    // 声明话题发布者
    rclcpp::Publisher<std_msgs::msg::String>::SharedPtr command_publisher_;
    void timer_callback()
    {
        // 创建消息
        std_msgs::msg::String message;
        message.data = "One";
        // 日志打印
        RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
        // 发布消息
        command_publisher_->publish(message);
    }
    // 声名定时器指针
    rclcpp::TimerBase::SharedPtr timer_;
};

int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<Publisher>("topic_One");
    rclcpp::spin(node);
    rclcpp::shutdown();
    return 0;

}
在功能包内创建 launch 文件夹,编写 .py 文件[重点]
mkdir launch
touch test.launch.py

然后在 .py 文件后键入

# 导入库
from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    """launch内容描述函数,由ros2 launch 扫描调用"""
    action_robot_01 = Node(
        package="robot_start_up",
        executable="action_robot_01"
    )
    # 创建LaunchDescription对象launch_description,用于描述launch文件
    launch_description = LaunchDescription(
        [action_robot_01])
    # 返回让ROS2根据launch描述执行节点
    return launch_description
  • 需要导入两个库(launch 描述文件的生成,Node打包)

LaunchDescription
launch_ros.actions 中的 Node

  • Node 节点打包

action_robot_01 = Node(
package=“robot_start_up”,
executable=“action_robot_01”
)

其中:
package 后面填写的内容为功能包的名字
executable 后面填写的内容为功能包中的 cpp文件生成的可执行文件名字
最后返回即可



CMakeLists.txt 文件的更改

添加以下几项

  • 寻找必要的包
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
  • 源文件生成可执行文件
add_executable(action_robot_01 src/action_robot_01.cpp)
ament_target_dependencies(action_robot_01 rclcpp std_msgs)

install(TARGETS
  action_robot_01
  DESTINATION lib/${PROJECT_NAME}
)
  • install py 文件
install(DIRECTORY launch
  DESTINATION 
  share/${PROJECT_NAME})


编译运行
colcon build
source install/build
ros2 run robot_start_up est.launch.py 

执行结果:
在这里插入图片描述


在执行 ‘colcon build’ 后就会发现,在自己创建的工程目录文件夹 ‘install/功能包/share/launch’下会拷贝原来编辑好的 .py 文件

在这里插入图片描述


🌸🌸🌸完结撒花🌸🌸🌸


🌈🌈Redamancy🌈🌈


  • 5
    点赞
  • 9
    收藏
    觉得还不错? 一键收藏
  • 2
    评论
评论 2
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值