지난 예제코드(https://robocoder.tistory.com/7)에 이어서 설명한다.
타이머 두개로 하나는 파라미터를 읽고, 하나는 출력하는 예제이다.
#include "rclcpp/rclcpp.hpp"
class myParamNode : public rclcpp::Node
{
public:
myParamNode() : Node("param_node")
{
RCLCPP_INFO(this->get_logger(), "param_node의 기본생성자");
timer1_ = this->create_wall_timer(std::chrono::milliseconds(200),
std::bind(&myParamNode::timerCallBack,this));
timer2_ = this->create_wall_timer(std::chrono::milliseconds(100),
std::bind(&myParamNode::paramCallBack,this));
this->declare_parameter<std::string>("my_string","");
this->declare_parameter<int>("my_integer",0);
this->declare_parameter<bool>("my_bool",false);
this->declare_parameter<std::vector<double>>("my_arr",{});
this->declare_parameter<std::vector<std::string>>("my_str_arr",{});
this->declare_parameter<int>("my_nest.integer",0);
}
void paramCallBack(){
this->get_parameter("my_string",param_string);
this->get_parameter("my_integer",param_integer);
this->get_parameter("my_bool",param_bool);
this->get_parameter("my_arr",param_arr);
this->get_parameter("my_str_arr",param_str_arr);
this->get_parameter("my_nest.integer",param_nest);
}
void timerCallBack(){
RCLCPP_INFO(this->get_logger(),"-*-*-*-*-the parameters-*-*-*-*-");
RCLCPP_INFO(this->get_logger(),"my_string : %s",param_string.c_str());
RCLCPP_INFO(this->get_logger(),"my_integer : %d",param_integer);
RCLCPP_INFO(this->get_logger(),"my_bool : %d",param_bool);
RCLCPP_INFO(this->get_logger(),"my_arr : ");
for(auto itr=param_str_arr.begin();itr != param_str_arr.end();++itr){
RCLCPP_INFO(this->get_logger()," index %d : %s ",std::distance(param_str_arr.begin(),itr),itr->c_str());
}
RCLCPP_INFO(this->get_logger(),"my_str_arr : ");
for(auto itr=param_arr.begin();itr != param_arr.end();++itr){
RCLCPP_INFO(this->get_logger()," index %d : %lf ",std::distance(param_arr.begin(),itr),*itr);
}
RCLCPP_INFO(this->get_logger(),"my_nest.integer : %d",param_nest);
}
private:
std::string param_string;
int param_integer;
bool param_bool;
int param_nest;
std::vector<double> param_arr;
std::vector<std::string> param_str_arr;
rclcpp::TimerBase::SharedPtr timer1_;
rclcpp::TimerBase::SharedPtr timer2_;
};
int main(int argc, char** argv){
rclcpp::init(argc,argv);
auto node = std::make_shared<myParamNode>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
아래와 같이 std::vector 와 nested integer가 파라미터로 추가된 점이 다르다.
...
this->declare_parameter<std::vector<double>>("my_arr",{});
this->declare_parameter<std::vector<std::string>>("my_str_arr",{});
this->declare_parameter<int>("my_nest.integer",0);
...
배열의 경우 std::vector<double>, std::vector<int> 등 익히 아는 벡터 자료형을 넣으면 된다.이 때, std::vector<float>은 안된다. 파라미터가 실수형으로 float64만 지원하기 때문... 왜 이렇게 만들었는지 아시는 분은 댓글 남겨주시면 감사하겠습니다.
nested된 파라미터도 추가되었다. nested가 무엇일까? ROS2에서 파라미터는 구조체처럼 nested로 구성하는 것이 가능하다. 파라미터에서 my_nest.integer1 my_nest.integer2, my_nest.mynum1, ... 이런식으로 선언해서 my_nest라는 파라미터 안에 새끼파라미터를 넣는 것이 가능하다. 코드가 복잡해지고 파라미터가 많아지면 구분에 유용할 것이다.
나머지는 이전 코드와 똑같이 get_parameter를 이용해서 따로 선언된 변수로 값을 받을 수 있다.
yaml파일로 파라미터 받기
근데, 위에처럼 파라미터가 한두개가 아니고, 수십 수백개인 경우에는 어떻게 할까? 코드에서 바꿀때마다 빌드해야 될까? 로봇을 만들다 보면 파라미터를 수시로 바꿔가며 디버깅해야할 때가 많고 실험적으로 값을 찾아야하는 경우도 많다. 그 수많은 조합 하나하나 당 모두 빌드를 동반한다면 무척 피곤해질 것이다. 파일 하나에 파라미터를 몰아놓고 파일만 수정, 저장하면 파라미터 변화가 코드에 반영되게 해보자.
우선 다음과 같이 my_config.yaml파일을 만들어보자. 만드는 위치는 패키지 내 어디에 해도 되지만 패키지 폴더에 config(또는 cfg)라는 폴더를 하나 만들고 그 안에 my_config.yaml 파일을 넣는 것이 좋다. 왜 좋은지는 다음 포스팅에서 설명할 것이다. my_config.yaml을 만들고 나면 패키지(~/my_ws/src/my_pkg) 내 폴더 구성은 다음과 같은 상태가 될 것이다.
.
├── cfg
│ └── my_config.yaml
├── CMakeLists.txt
├── include
│ └── my_param_pkg
├── package.xml
└── src
└── my_param.cpp
cfg안에 my_config.yaml이 들어있다. my_config.yaml에 아래의 내용을 넣는다.
param_node:
ros__parameters:
my_bool: True
my_integer: 5
my_string: "Hello World"
my_arr: [7.5, 4.4, 3.3]
my_str_arr: ['mini', 'mani', 'moe']
my_nest:
integer: 7
param_node 부분에는 해당 파라미터를 사용할 노드의 이름을 넣어준다. 필자는 코드에서 "param_node"로 노드의 이름을 정했기 때문에 param_node로 했다. ( yaml 파일 하나에 노드 여러개를 지정하여 각각의 파라미터를 정의하는 것도 가능하다!)
ros__parameters: 는 고정으로 둔다. 이걸 기준으로 파라미터를 읽는다. 그 아래에 우리가 쓸 파라미터들을 정의한다.
파라미터이름 : 값 형식으로 정의하면 된다. 배열은 대괄호 안에 값을 넣어 정의, nested형은 파라미터이름 아래에 새끼 파라미터를 indent 해서 정의해놓는다.
ros2 run my_param_pkg my_param_node --ros-args --params-file ~/ros2_ws/src/my_param_pkg/cfg/my_config.yaml
이제 프로젝트를 빌드하고 위의 커맨드로 실행한다. ' ros2 run 패키지이름 익스큐터블 ' 뒤에 옵션과 yaml파일 위치가 지정되어 있다.
결과
[INFO] [1709646333.310655072] [param_node]: -*-*-*-*-the parameters-*-*-*-*-
[INFO] [1709646333.310780086] [param_node]: my_string : Hello World
[INFO] [1709646333.310816908] [param_node]: my_integer : 5
[INFO] [1709646333.310844641] [param_node]: my_bool : 1
[INFO] [1709646333.310864552] [param_node]: my_arr :
[INFO] [1709646333.310890741] [param_node]: index 0 : mini
[INFO] [1709646333.310983106] [param_node]: index 1 : mani
[INFO] [1709646333.311017806] [param_node]: index 2 : moe
[INFO] [1709646333.311046534] [param_node]: my_str_arr :
[INFO] [1709646333.311073933] [param_node]: index 0 : 7.500000
[INFO] [1709646333.311109776] [param_node]: index 1 : 4.400000
[INFO] [1709646333.311138584] [param_node]: index 2 : 3.300000
my_config.yaml 파일에서 지정한 대로 파라미터가 잘 전달되어 출력된 것을 확인할 수 있다. 이제 yaml파일만 수정하면 빌드 없이 파라미터 변화를 반영할 수 있게 되었다. 다음 포스팅에서는 launch파일에 대한 설명과 그 안에서 파라미터 파일을 불러오는법에 대한 포스팅을 하겠다.
'로보틱스' 카테고리의 다른 글
ROS2 cpp 커스텀 메세지 및 서비스 작성 (custom msgs & srv) (0) | 2024.04.07 |
---|---|
ROS2 cpp 파라미터 선언 및 코드 내 활용(1) (0) | 2024.02.24 |
ROS2 cpp 패키지 만들기 (0) | 2024.02.19 |
Ubuntu 20.04(우분투 20.04) ROS2(foxy)설치 (0) | 2024.02.19 |