延續昨天的workspace、package、publisher/subscriber node,今天針對publisher node來增加一個Parameter吧~~
先把昨天完整版的publisher程式放在下方,可以看到這個publisher的任務是每秒發布兩次的message.data = "Hello, world! " + std::to_string(count_++),那我希望現在能把"Hello, world! "的world任意修改成我想要的文字,而且不需要每改一次就重新編譯。
#include <chrono>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.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));
  }
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);
  }
  rclcpp::TimerBase::SharedPtr timer_;
  rclcpp::Publisher<std_msgs::msg::String>::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;
}
那就開始來使用Parameter吧~~
在ROS2中宣告Parameter 字串變數的方法是用declare_parameter(),裡面放變數的名稱與預設值
this->declare_parameter("my_parameter", "world");
那它應該放在節點的預設建構函式中
class MinimalPublisher : public rclcpp::Node
{
public:
  MinimalPublisher()
  : Node("minimal_publisher"), count_(0)
  {
    //宣告底家!!!!
    this->declare_parameter("my_parameter", "world");
  
    publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
    timer_ = this->create_wall_timer(
      500ms, std::bind(&MinimalPublisher::timer_callback, this));
  }
接下來可以看到MinimalPublisher()有個函式timer_callback()會去負責不斷執行直到程式中止,那"Hello, world! "的發布也是由這裡在編輯,也就是說Parameter要在這個函式中被使用,在那之前要先get_parameter()取得現在parameter的值。
std::string my_param = this->get_parameter("my_parameter").as_string();
//如果是整數或浮點數的話就可以用
get_parameter("my_parameter").as_int();
get_parameter("my_parameter").as_double();
接下來就可以如同一般使用c++變數一樣使用my_param變數了
//可以把舊的
message.data = "Hello, world! " + std::to_string(count_++);
//替換成
message.data = "Hello, "+ my_param +"! "+ std::to_string(count_++);
完整的timer_callback()長這樣
  void timer_callback()
  {
    //取得my_parameter
    std::string my_param = this->get_parameter("my_parameter").as_string();
    auto message = std_msgs::msg::String();
    
    //使用my_parameter
    message.data = "Hello, " + my_param +" ! "+ std::to_string(count_++);
    RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
    publisher_->publish(message);
  }
程式碼的部份就完成了,接下來就可以
colcon build && . install/setup.bash 
os2 run cpp_pubsub talker #預設是world
!
那有幾個方式可以修改成指定的Parameter
# 1.直接用新的run
ros2 run cpp_pubsub talker --ros-args -p my_parameter:=EJ
# count被影響,歸0了
# 2.執行中的node 設置新變數
ros2 param set /minimal_publisher my_parameter earth
# count不會被影響
https://ithelp.ithome.com.tw/upload/images/20231003/20140433amHdaRQI4e.png
[INFO] [1696338186.994345376] [minimal_publisher]: Publishing: 'Hello, EJ ! 9'
[INFO] [1696338187.494316111] [minimal_publisher]: Publishing: 'Hello, EJ ! 10'
[INFO] [1696338187.994306081] [minimal_publisher]: Publishing: 'Hello, earth ! 11'
[INFO] [1696338188.494302361] [minimal_publisher]: Publishing: 'Hello, earth ! 12'
[INFO] [1696338188.994287811] [minimal_publisher]: Publishing: 'Hello, earth ! 13'
那用我習慣的寫法來把所有東西都寫成Launch文件,Launch細節可以看DAY14和DAY15,不贅述了~
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
    ld = LaunchDescription()
    publisher=Node(
            package="cpp_pubsub",
            executable="talker",
            name="custom_minimal_publisher",
            output="screen",
            emulate_tty=True,
            parameters=[
                {"my_parameter": "earth"}
            ]
        )
    subscriber=Node(
            package="cpp_pubsub",
            executable="listener",
            output="screen"
        )
    ld.add_action(publisher)
    ld.add_action(subscriber)
    return ld

這樣就能同時在terminal裡發布和接收啦~~~
寫package真的要多練習呢...