iT邦幫忙

2023 iThome 鐵人賽

DAY 17
0
自我挑戰組

一個營建系學生的韌體之路-自走車篇系列 第 17

【AMR_Day17】ROS2 基本功- 用c++寫個綜合練習(上)

  • 分享至 

  • xImage
  •  

從0開始建自己的cpp專案

基於我自己的使用經驗,來練習如何在ROS2寫一個間單且包含Topic(publisher node)、Topic(subscriber node)、Parameter、launch的練習吧。
今天先處理workspace、package、publisher/subscriber node各寫一個cpp,按照官網步驟教學,但會帶入一些我的使用經驗。

workspace

開一個terminal

# 設定環境變數
source /opt/ros/foxy/setup.bash

mkdir -p ~/ej_ros2_ws/src
cd ~/ej_ros2_ws/src

package

ros2 pkg create --build-type ament_cmake cpp_pubsub

https://ithelp.ithome.com.tw/upload/images/20231002/20140433ZGPNKm67Wd.png

publisher node

cd ~/ej_ros2_ws/src/cpp_pubsub/src
# 抓取官方提供的publisher 
# 也可以自己新建一個cpp檔複製貼上程式碼,一樣意思
wget -O publisher_member_function.cpp https://raw.githubusercontent.com/ros2/examples/foxy/rclcpp/topics/minimal_publisher/member_function.cpp

https://ithelp.ithome.com.tw/upload/images/20231002/20140433MdygiPIZQ2.png

看看程式碼

先蕪存菁一下,非原始程式碼~~只留下我想補充的地方。刪除的地方用//...帶過

//...
#include "rclcpp/rclcpp.hpp"  # ROS2 C++ 標準函式庫
#include "std_msgs/msg/string.hpp"  # ROS2 標準訊息函式庫—字串格式
// 如果要發布或訂閱別的格式,就要#include 指定格式,例如:
#include "sensor_msgs/msg/point_cloud2.hpp" # ROS2 感測器函式庫—點雲格式

//...
// ROS2用物件導向形式作為一個節點,都基於rclcpp::Node
class MinimalPublisher : public rclcpp::Node
{
public:
  //物件導向預設建構函式,這裡有預設節點的名字minimal_publisher
  MinimalPublisher() 
  : Node("minimal_publisher"), count_(0) 
  {
    publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);//topic是話題名稱,10是備份訊息的儲存佇列大小
    timer_ = this->create_wall_timer(
      500ms, std::bind(&MinimalPublisher::timer_callback, this));
      //每500毫秒送一次訊息
  }

private:
  //timer_callback() 會在timer_不斷被呼叫直到程式中止
  void timer_callback()
  {
    auto message = std_msgs::msg::String();
    //...
    //ROS2 輸出文字在terminal上的方法
    RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", 'str');
    
    // 將訊息發布出去
    publisher_->publish(message);
  }
  
  //timer_和publisher_宣告於此
  rclcpp::TimerBase::SharedPtr timer_;
  
  
  //publisher_傳送的訊息格式在這被宣告~~~<std_msgs::msg::String>
  //如果是點雲的話以此類推<sensor_msgs::msg::PointCloud2>
  rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
  //...
};

//昨天提到的arguments 就是這裡的int argc, char * argv[] 提到而已~
int main(int argc, char * argv[])
{
  // 主程式內基本上就是長這樣而已,除非想寫arguments?但個人習慣用Parameter
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalPublisher>());
  rclcpp::shutdown();
  return 0;
}

subscriber nodepart 1

先把subscriber node也補上

wget -O subscriber_member_function.cpp https://raw.githubusercontent.com/ros2/examples/foxy/rclcpp/topics/minimal_subscriber/member_function.cpp

https://ithelp.ithome.com.tw/upload/images/20231002/201404330fxV69BUSo.png

看看程式碼

提過得就跳過~~

//...
//這個參數(?)在我用pcl時會出錯 error: reference to '_1' is ambiguous
using std::placeholders::_1;
//在include <pcl>眾多函式庫前先放這段,應該就可以解決了
//#define BOOST_BIND_NO_PLACEHOLDERS
//我沒理解錯的話是'_1'和pcl中的衝突了

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));
      //topic 是話題名稱,10 是保留訊息的儲存佇列大小
  }

private:
  void topic_callback(const std_msgs::msg::String::SharedPtr msg) const
  {
    //可以上網搜尋std_msgs::msg::String 有哪些內容可以用
    RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
  }
  
  //相較發布者 rclcpp::Publisher
  rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
};
  //...

std_msgs/String Message

只有data變數~
https://ithelp.ithome.com.tw/upload/images/20231002/201404334zU1a6KsSL.png

sensor_msgs/PointCloud2 Message

之後pcl實作時在詳細介紹~先放給大家比較!
https://ithelp.ithome.com.tw/upload/images/20231002/20140433W08nsoi7jl.png

修改依賴檔

檢查一下兩個節點用到了哪些函式庫,記得新增進package.xml和CMakeLists.txt
這次兩個節點用到了rclcpp和std_msgs~

package.xml

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

舉一反三,如果用到點雲格式的話就需要<depend>sensor_msgs</depend>

CMakeLists.txt

find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)

#可以幫cpp檔新增進executable
#有加可以:  ros2 run cpp_pubsub talker
add_executable(talker src/publisher_member_function.cpp)

# executable依賴函式庫
ament_target_dependencies(talker rclcpp std_msgs)

# 有新增executable記得這樣才找的到!
install(TARGETS
  talker
  DESTINATION lib/${PROJECT_NAME})
  
# 以此類推 subscriber
add_executable(listener src/subscriber_member_function.cpp)
ament_target_dependencies(listener rclcpp std_msgs)

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

編譯

cd ~/ej_ros2_ws
# 檢查依賴
rosdep install -i --from-path src --rosdistro foxy -y

# 編譯指定package
colcon build --packages-select cpp_pubsub

# 開兩個~/ej_ros2_ws terminal
. install/setup.bash

#1
ros2 run cpp_pubsub talker
#2
ros2 run cpp_pubsub listener

https://ithelp.ithome.com.tw/upload/images/20231002/20140433aIW5287cqR.png


上一篇
【AMR_Day16】ROS2 基本功-Parameter
下一篇
【AMR_Day18】ROS2 基本功- 用c++寫個綜合練習(下)
系列文
一個營建系學生的韌體之路-自走車篇30
圖片
  直播研討會
圖片
{{ item.channelVendor }} {{ item.webinarstarted }} |
{{ formatDate(item.duration) }}
直播中

尚未有邦友留言

立即登入留言