大纲
- 初始化环境
- 生成自定义消息的工程
- 创建包
- 自定义消息
- package.xml
- 完整文件
- CMakeLists.txt
- 完整文件
- 编译
- 注册
- 使用自定义消息的工程
- 创建包
- 代码
- CMakeLists.txt
- 编译
- 运行
- 工程地址
- 参考资料
在之前的案例中我们订阅/发布之间传递的消息都是ROS2的标准类型。本文我们将讨论如何自定义一个消息类型。
初始化环境
在《Robot Operating System——深度解析自动隐式加载动态库的运行模式》一文中,我们展现了ROS2可执行文件的链接指令。可以看到它依赖了很多ROS2环境相关的动态库,所以我们在创建工程之前也要初始化环境。
source /opt/ros/jazzy/setup.bash
关于环境的安装可以参见《Robot Operating System——Ubuntu上以二进制形式安装环境》。
生成自定义消息的工程
创建包
ros2 pkg create --build-type ament_cmake --license Apache-2.0 custom_msg
其目录结构如下
自定义消息
我们使用《Robot Operating System——导航卫星(如 GPS)状态信息》中介绍的sensor_msgs::msg::NavSatStatus、《Robot Operating System——带有协方差矩阵的三维空间中的位姿(位置和方向)》中介绍的geometry_msgs::msg::PoseWithCovariance以及《Robot Operating System——std_msgs消息类型说明和使用》中介绍的std_msgs::msg::Bool来组织一个自定义消息体。
我们创建一个目录,叫做msg,然后在这个目录下创建文件NavSatPoseBool.msg,填入以下内容
sensor_msgs/NavSatStatus nav
geometry_msgs/PoseWithCovariance pose
std_msgs/Bool boolvalue
此时目录结构如下
package.xml
在该文件中新增如下内容
<depend>sensor_msgs</depend>
<depend>geometry_msgs</depend>
<depend>std_msgs</depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
sensor_msgs、geometry_msgs和std_msgs是消息体中用的三种ROS2提供的基础消息类型;
rosidl_default_generators用于将上述msg文件生成代码;
rosidl_default_runtime是运行时依赖;
后三者是一定要加的,前面的三个根据自定义消息的类型酌情添加。
完整文件
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>custom_msg</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="f304646673@gmail.com">fangliang</maintainer>
<license>Apache-2.0</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>sensor_msgs</depend>
<depend>geometry_msgs</depend>
<depend>std_msgs</depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
CMakeLists.txt
新增如下内容
find_package(sensor_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/NavSatPoseBool.msg"
DEPENDENCIES sensor_msgs geometry_msgs std_msgs
)
DEPENDENCIES 中添加的是我们自定义消息的基础类型。
完整文件
cmake_minimum_required(VERSION 3.8)
project(custom_msg)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/NavSatPoseBool.msg"
DEPENDENCIES sensor_msgs geometry_msgs std_msgs
)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()
编译
colcon build --packages-select custom_msg
注册
source install/setup.sh
经过注册后,我们可以在ROS2中查看这个自定义消息
ros2 interface show custom_msg/msg/NavSatPoseBool
使用自定义消息的工程
创建包
ros2 pkg create --build-type ament_cmake --license Apache-2.0 custom_msg_topic --dependencies rclcpp custom_msg
–dependencies参数可以帮我们在package.xml和CMakeLists.txt中自动添加相应依赖。此时我们添加上一步创建的custom_msg。
代码
我们在src目录下创建talker.cpp和listener.cpp两个文件,然后分别填入下面的代码:
// Copyright 2014 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <chrono>
#include <cstdio>
#include <memory>
#include <utility>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "custom_msg/msg/nav_sat_pose_bool.hpp"
using namespace std::chrono_literals;
class Talker : public rclcpp::Node
{
public:
explicit Talker() : Node("talker")
{
// Create a function for when messages are to be sent.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
auto publish_message =
[this]() -> void
{
msg_ = std::make_unique<custom_msg::msg::NavSatPoseBool>();
msg_->nav.service = 1;
msg_->nav.status = 2;
msg_->pose.pose.position.x = 1.0;
msg_->pose.pose.position.y = 2.0;
msg_->pose.pose.position.z = 3.0;
msg_->pose.pose.orientation.x = 0.0;
msg_->pose.pose.orientation.y = 0.0;
msg_->pose.pose.orientation.z = 0.0;
msg_->pose.pose.orientation.w = 1.0;
msg_->boolvalue.data = false;
RCLCPP_INFO(this->get_logger(), "Publishing: [%s]", serializeNavSatPoseBool(*msg_).c_str());
// Put the message into a queue to be processed by the middleware.
// This call is non-blocking.
pub_->publish(std::move(msg_));
};
// Create a publisher with a custom Quality of Service profile.
// Uniform initialization is suggested so it can be trivially changed to
// rclcpp::KeepAll{} if the user wishes.
// (rclcpp::KeepLast(7) -> rclcpp::KeepAll() fails to compile)
rclcpp::QoS qos(rclcpp::KeepLast{7});
pub_ = this->create_publisher<custom_msg::msg::NavSatPoseBool>("chatter", qos);
// Use a timer to schedule periodic message publishing.
timer_ = this->create_wall_timer(1s, publish_message);
}
private :std::string serializeNavSatPoseBool(const custom_msg::msg::NavSatPoseBool &msg) {
std::ostringstream oss;
oss << msg.nav.service << " "
<< msg.nav.status << " "
<< msg.pose.pose.position.x << " "
<< msg.pose.pose.position.y << " "
<< msg.pose.pose.position.z << " "
<< msg.pose.pose.orientation.x << " "
<< msg.pose.pose.orientation.y << " "
<< msg.pose.pose.orientation.z << " "
<< msg.pose.pose.orientation.w << " "
<< msg.boolvalue.data;
return oss.str();
}
private:
size_t count_ = 1;
std::unique_ptr<custom_msg::msg::NavSatPoseBool> msg_;
rclcpp::Publisher<custom_msg::msg::NavSatPoseBool>::SharedPtr pub_;
rclcpp::TimerBase::SharedPtr timer_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<Talker>());
rclcpp::shutdown();
return 0;
}
// Copyright 2014 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "custom_msg/msg/nav_sat_pose_bool.hpp"
#include <sstream>
#include <string>
class Listener : public rclcpp::Node
{
public:
explicit Listener() : Node("listener")
{
// Create a callback function for when messages are received.
// Variations of this function also exist using, for example UniquePtr for zero-copy transport.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
auto callback =
[this](custom_msg::msg::NavSatPoseBool::ConstSharedPtr msg) -> void
{
RCLCPP_INFO(this->get_logger(), "I heard: [%s]", serializeNavSatPoseBool(*msg).c_str());
};
// Create a subscription to the topic which can be matched with one or more compatible ROS
// publishers.
// Note that not all publishers on the same topic with the same type will be compatible:
// they must have compatible Quality of Service policies.
sub_ = create_subscription<custom_msg::msg::NavSatPoseBool>("chatter", 10, callback);
}
private :std::string serializeNavSatPoseBool(const custom_msg::msg::NavSatPoseBool &msg) {
std::ostringstream oss;
oss << msg.nav.service << " "
<< msg.nav.status << " "
<< msg.pose.pose.position.x << " "
<< msg.pose.pose.position.y << " "
<< msg.pose.pose.position.z << " "
<< msg.pose.pose.orientation.x << " "
<< msg.pose.pose.orientation.y << " "
<< msg.pose.pose.orientation.z << " "
<< msg.pose.pose.orientation.w << " "
<< msg.boolvalue.data;
return oss.str();
}
private:
rclcpp::Subscription<custom_msg::msg::NavSatPoseBool>::SharedPtr sub_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<Listener>());
rclcpp::shutdown();
return 0;
}
CMakeLists.txt
然后分别编译这两个文件成为可执行文件。
add_executable(talker src/talker.cpp)
ament_target_dependencies(talker rclcpp custom_msg)
add_executable(listener src/listener.cpp)
ament_target_dependencies(listener rclcpp custom_msg)
编译
colcon build --packages-select custom_msg_topic
运行
在新的终端中,需要先初始化环境
source custom_msg/install/setup.sh
然后执行listen和talker。
工程地址
- https://github.com/f304646673/ros2-examples/tree/main/custom_msg
- https://github.com/f304646673/ros2-examples/tree/main/custom_msg_topic
参考资料
- https://docs.ros.org/en/jazzy/Tutorials/Beginner-Client-Libraries/Custom-ROS2-Interfaces.html