ROS 파라미터

2024. 4. 17. 20:41ROS

  • 기존 서비스에 변수 입력값을 추가로 줄 수 있는 것을 ROS에서 파라미터(parameter)라고 함
  • 이번 실습에서는 두개의 숫자를 계산하는 서비스 서버와 클라이언트를 만들고,
  • 파라미터로 사칙연산 연산자를 정해주는 실습을 수행함

package.xml
CMakeLists.txt

//service_server_param
#include "ros/ros.h" // ROS Default Header File
#include "ros_param/SrvTutorial.h"// action Library Header File

#define PLUS 1 // Addition
#define MINUS 2 // Subtraction
#define MULTIPLICATION 3 // Multiplication
#define DIVISION 4 // Division
#define SQUARE 5
int g_operator = PLUS;

// The process below is performed if there is a service request
// The service request is declared as 'req', and the service response is declared as 'res'
bool calculation(ros_param::SrvTutorial::Request &req,
ros_param::SrvTutorial::Response &res)
{
// The operator will be selected according to the parameter value and calculate 'a' and 'b',
// which were received upon the service request.
// The result is stored as the Response value.
switch(g_operator)
{
case PLUS:
res.result = req.a + req.b; break;
case MINUS:
res.result = req.a - req.b; break;
case MULTIPLICATION:
res.result = req.a * req.b; break;
case DIVISION:
if(req.b == 0)
{
res.result = 0; break;
}
else
{
res.result = req.a / req.b; break;
}
case SQUARE:
res.result = req.a;
for (int i = 0; i < req.b - 1; i++)
{
res.result *= req.a;
}
break;
default:
res.result = req.a + req.b; break;
}

// Displays the values of 'a' and 'b' used in the service request, and the 'result' value
// corresponding to the service response.
ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b);
ROS_INFO("sending back response: [%ld]", (long int)res.result);

return true;
}

int main(int argc, char **argv) // Node Main Function
{
ros::init(argc, argv, "service_server_param"); // Initializes Node Name
ros::NodeHandle nh; // Node handle declaration

nh.setParam("calculation_method", PLUS); // Reset Parameter Settings

// Declare service server 'service_server_param' using the 'SrvTutorial' service file
// in the 'ros_param' package. The service name is 'ros_param_srv' and
// it is set to execute a 'calculation' function when a service is requested.
ros::ServiceServer ros_tutorials_service_server = nh.advertiseService("ros_param_srv", calculation);

ROS_INFO("ready srv server!");

ros::Rate r(10); // 10 hz

while (ros::ok())
{
nh.getParam("calculation_method", g_operator); // Select the operator according to the value received from the parameter.
ros::spinOnce(); // Callback function process routine
r.sleep(); // Sleep for routine iteration
}

return 0;
}
//service_client_param
#include "ros/ros.h" // ROS Default Header File
#include "ros_param/SrvTutorial.h"// SrvTutorial Service File Header (Automatically created after build)
#include <cstdlib> // Library for using the "atoll" function

int main(int argc, char **argv) // Node Main Function
{
ros::init(argc, argv, "service_client"); // Initializes Node Name

if (argc != 3) // Input value error handling
{
ROS_INFO("cmd : rosrun ros_param service_client_param arg0 arg1");
ROS_INFO("arg0: double number, arg1: double number");
return 1;
}

ros::NodeHandle nh; // Node handle declaration for communication with ROS system

// Declares service client 'service_client_param'
// using the 'SrvTutorial' service file in the 'ros_param' package.
// The service name is 'ros_param_srv'
ros::ServiceClient ros_param_client = nh.serviceClient<ros_param::SrvTutorial>("ros_param_srv");

// Declares the 'srv' service that uses the 'SrvTutorial' service file
ros_param::SrvTutorial srv;

// Parameters entered when the node is executed as a service request value are stored at 'a' and 'b'
srv.request.a = atoll(argv[1]);
srv.request.b = atoll(argv[2]);

// Request the service. If the request is accepted, display the response value
if (ros_param_client.call(srv))
{
ROS_INFO("send srv, srv.Request.a and b: %ld, %ld", (long int)srv.request.a, (long int)srv.request.b);
ROS_INFO("receive srv, srv.Response.result: %ld", (long int)srv.response.result);
}
else
{
ROS_ERROR("Failed to call service ros_param_srv");
return 1;
}
return 0;
}

ros_param 폴더 안에 srv 폴더 생성 후 SrvTutorial.srv nano에디터로 생성

int64 a

int64 b

---

int64 result

 

'ROS' 카테고리의 다른 글

ROS opencv  (0) 2024.04.17
ROS roslaunch  (0) 2024.04.17
ROS 서비스  (0) 2024.04.17
ROS 토픽  (0) 2024.04.08
ROS 기본(20.04)  (0) 2024.04.02