【ROS2】ROS2使用自定义msg文件创建发布节点和订阅节点

3 篇文章 0 订阅

UBUNTU 20.04 + ROS2 rolling
ROS+开发工具一键安装脚本
wget http://fishros.com/install -O fishros && bash fishros

创建名为cpp_pubsub的功能包

cd src
ros2 pkg creat --build-type ament_cmake cpp_pubsub
cd cpp_pubsub

在src内创建节点

名为publisher_member_function.cpp
和subscriber_member_function.cpp

#include <chrono>
#include <functional>
#include <memory>
#include <string>

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

#include "util/msg/num.hpp"

using namespace std::chrono_literals;

/* This example creates a subclass of Node and uses std::bind() to register a
 * member function as a callback from the timer. */

class MinimalPublisher : public rclcpp::Node
{
public:
  // MinimalPublisher()
  // : Node("minimal_publisher"), count_(0)
  // {
  //   publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
  //   timer_ = this->create_wall_timer(
  //   500ms, std::bind(&MinimalPublisher::timer_callback, this));
  // }

  MinimalPublisher()
      : Node("minimal_publisher"), count_(0)
  {
    publisher_ = this->create_publisher<util::msg::Num>("/test/NumMsg", 10);
    timer_ = this->create_wall_timer(
        500ms, std::bind(&MinimalPublisher::timer_callback, this));
  }

private:
  // void timer_callback()
  // {
  //   auto message = std_msgs::msg::String();
  //   message.data = "Hello, world! " + std::to_string(count_++);
  //   RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
  //   publisher_->publish(message);
  // }
  void timer_callback()
  {
    auto message = util::msg::Num();
    message.num_test = 3;
    // RCLCPP_INFO(this->get_logger(), "Publishing: '%f'", message.num_test.c_str());
    std::cout << "running talker" << std::endl;
    publisher_->publish(message);
  }
  rclcpp::TimerBase::SharedPtr timer_;
  // rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
  rclcpp::Publisher<util::msg::Num>::SharedPtr publisher_;
  size_t count_;
};

int main(int argc, char *argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalPublisher>());
  rclcpp::shutdown();
  return 0;
}
#include <memory>

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

#include "util/msg/num.hpp"
using std::placeholders::_1;

class MinimalSubscriber : public rclcpp::Node
{
  // public:
  //   MinimalSubscriber()
  //   : Node("minimal_subscriber")
  //   {
  //     subscription_ = this->create_subscription<std_msgs::msg::String>(
  //     "topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
  //   }

  // private:
  //   void topic_callback(const std_msgs::msg::String & msg) const
  //   {
  //     RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str());
  //   }
  //   rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;

public:
  MinimalSubscriber()
      : Node("minimal_subscriber")
  {
    subscription_ = this->create_subscription<util::msg::Num>(
        "/test/NumMsg", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
  }

private:
  void topic_callback(const util::msg::Num &msg) const
  {
    RCLCPP_INFO(this->get_logger(), "I heard: '%ld'", msg.num_test);
  }
  rclcpp::Subscription<util::msg::Num>::SharedPtr subscription_;
};

int main(int argc, char *argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalSubscriber>());
  rclcpp::shutdown();
  return 0;
}

修改xml和cmakelist

<?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>cpp_pubsub</name>
  <version>0.0.0</version>
  <description>TODO: Package description</description>
  <maintainer email="hbjzcrn@foxmail.com">crn</maintainer>
  <license>TODO: License declaration</license>

  <buildtool_depend>ament_cmake</buildtool_depend>

  <depend>rclcpp</depend>
<depend>std_msgs</depend>

  <test_depend>ament_lint_auto</test_depend>
  <test_depend>ament_lint_common</test_depend>
  <depend>util</depend>

  <export>
    <build_type>ament_cmake</build_type>
  </export>
</package>

cmake_minimum_required(VERSION 3.5)
project(cpp_pubsub)

# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
  set(CMAKE_CXX_STANDARD 14)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(util REQUIRED)

add_executable(talker src/publisher_member_function.cpp)
add_executable(listener src/subscriber_member_function.cpp)

ament_target_dependencies(listener rclcpp std_msgs util)
ament_target_dependencies(talker rclcpp std_msgs util)

install(TARGETS
  talker
  listener
  DESTINATION lib/${PROJECT_NAME})

ament_package()

编译后运行

colcon build --packages-select cpp_pubsub
. install/setup.bash
ros2 run cpp_pubsub talker

新建一个终端

. install/setup.bash
ros2 run cpp_pubsub listener
  • 2
    点赞
  • 3
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值