- ubuntu 20.04, ROS noetic 기준 포스팅
XmlRpc란?
ROS launch file에서 yaml file을 load해주는 편리한 도구이다.
사용법
1. launch file에 yaml file load
- launch/test.launch
<launch>
<node pkg="xmlrpc_study" type="xmlrpc_study" name="xmlrpc_test" output="screen">
</node>
<rosparam file="$(find plugin_study)/param/test.yaml" command="load"/>
</launch>
- param/test.yaml
xml_params:
value: "what"
type: "test"
list: [
"1", "2", "3"
]
2. main.cpp code 작성
#include <ros/ros.h>
int main(int argc, char **argv)
{
ros::init(argc, argv, "xml_study");
ros::NodeHandle nh;
XmlRpc::XmlRpcValue params;
nh.getParam("xml_params", params);
std::string value = static_cast<std::string>(params["value"]);
ROS_INFO("value %s", value.c_str());
std::string type = static_cast<std::string>(params["type"]);
ROS_INFO("type %s", type.c_str());
XmlRpc::XmlRpcValue list = static_cast<XmlRpc::XmlRpcValue>(params["list"]);
for (int i = 0; i < list.size(); i++)
{
std::string list_value = static_cast<std::string>(list[i]);
ROS_INFO("list %dth : %s", i + 1, list_value.c_str());
}
return 0;
}
- 설명
- XmlRpc::XmlRpcValue : yaml file이 읽혀서 들어갈 변수
- nh.getParma(string, XmlRpc::XmlRpcValue): 설정한 변수에 맞는 걸 불러온다.
- XmlRcp::XmlRpcValue에서 값을 얻어 오려면 기본적으로 static_cast를 해줘야 한다.
- 만약 불러올 값이 array일 경우, XmlRcp::XmlRpcValue로 먼더 static_cast후 for문으로 다시 한번 static_cast를 해주면 된다.
결과
728x90
'ROS' 카테고리의 다른 글
[ROS] Move Base (3) Move Base Code 분석 (0) | 2022.02.21 |
---|---|
[ROS] Move Base (2) Velocity & Acceleration (0) | 2022.02.18 |
[ROS] Move Base (1) Navigation Stack (2) | 2022.02.18 |
[ROS] plugin 사용법 (0) | 2022.02.14 |
[ Server / Client ] 서버 클라이언트 작성법 + Custom service file 작성법 (1) | 2021.01.30 |