======ROS 스터디 #5: ROS 기초 프로그래밍======
2020년 11월 27일 금요일 13:30\\
ZOOM 화상회의
{{youtube>LnEPRBnZ5eg?medium}}
=====3. 서비스(Service) 서버 <-> 클라이언트 노드=====
====3.1. 패키지 생성====
$cd ~/catkin_ws/src
$catkin_create_pkg ros_tutorials_service message_generation std_msgs roscpp
====3.2. 패키지 설정 파일(package.xml) 수정====
$ gedit package.xml
ros_tutorials_topic
0.1.0
ROS turtorial package to learn the topic
Apache License 2.0
Yoonseok Pyo
Yoonseok Pyo
https://github.com/ROBOTIS-GIT/ros_tutorials/issues
https://github.com/ROBOTIS-GIT/ros_tutorials.git
http://www.robotis.com
catkin
roscpp
std_msgs
message_generation
roscpp
std_msgs
message_runtime
====3.3. 빌드 설정 파일(CMakeLists.txt) 수정====
$ gedit CMakeLists.txt
cmake_minimum_required(VERSION 2.8.3)
project(ros_tutorials_service)
find_package(catkin REQUIRED COMPONENTS message_generation std_msgs roscpp)
add_service_files(FILES SrvTutorial.srv)
generate_messages(DEPENDENCIES std_msgs)
catkin_package(
LIBRARIES ros_tutorials_service
CATKIN_DEPENDS std_msgs roscpp
)
include_directories(${catkin_INCLUDE_DIRS})
add_executable(service_server src/service_server.cpp)
add_dependencies(service_server${${PROJECT_NAME}_EXPORTED_TARGETS}${catkin_EXPORTED_TARGETS)
target_link_libraries(topic_publisher ${catkin_LIBRARIES})
add_executable(service_client src/service_client.cpp)
add_dependencies(service_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(service_client ${catkin_LIBRARIES})
====3.4. service 파일 등록====
$ roscd ros_tutorials_service
$ mkdir srv
$ cd srv
$ gedit SrvTutorial.srv
int64 a
int64 b
---
int64 result
====3.5. service server 노드 작성====
$ add roscd ros_tutorials_service/src
$ gedit service_server.cpp
#include "ros/ros.h" // ROS Default Header File
#include "ros_tutorials_service/SrvTutorial.h" // SrvTutorial Message File Header. The header file is automatically created when building the package.
bool calculation(ros_tutorials_service::Srvtutorial::Request&req, ros_tutorials_service::SrvTutorial::Response&res)
res.result=req.a+req.b;
ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (iong 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, "topic_publisher"); // Initializes Node Name
ros::NodeHandle nh; // Node handle declaration for communication with ROS system
ros::ServiceServer ros_tutorials_service_server=nh.advertiseService("ros_tutorial_srv", calculation);
ROS_INFO("ready srv server!");
ros::spin();
return 0;
}
====3.6. service client 노드 작성====
$ add roscd ros_tutorials_service/src
$ gedit service_client.cpp
#include "ros/ros.h" // ROS Default Header File
#include "ros_tutorials_service/SrvTutorial.h" // MsgTutorial Message File Header. The header file is automatically created when building the package.
#include // Library for Using atroll Function
int main(int argc, char **argv) // Node Main Function
{
ros::init(argc, argv, "service_client"); // Initializes Node Name
if(argc!=3)
{ROS_INFO("cmd : rosrun ros_tutorial_service service_client arg0 argl");
ROS_INFO("arg0: double number, argl: double number");
return 1;
}
ros::NodeHandle nh; // Node handle declaration for communication with ROS system
// Declares service client. Create subscriber 'ros_tutorial_service' using the 'SrvTutorial'
// message file from the 'ros_tutorials_service_client' package. The topic name is
// 'ros_tutorial_srv'
ros::ServiceClient ros_tutorials_service_client=nh.serviceClient<"ros_tutorials_service::SrnTutorial>("ros_tutorial_srv");
ros_tutorials_service::SrvTutorial srv;
srv.request.a=atill(argv[1]);
srv.request.b=atill(argv[2]);
if(ros_tutorials_service_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_tutorial_srv");
return 1;
}
return 0;
}
====3.7. 실행 후 확인====
$ cd ~/catkin_ws && catkin_make
$ rosrun ros_tutorials_service service_server
[INFO][149572654.268629564]: ready srv server!
$ rosrun ros_tutorials_service service_client
[INFO][149572654.268629564]: send srv, srv.Request.a and b: 2, 3
[INFO][149572654.268629564]: receive.srv, srv.Response.result: 5
=====4. 액션(Action) 서버 <-> 클라이언트 노드=====
=====5. roslaunch 사용법=====
====5.1. 예시 1====
$ roscd ros tutorials_topic
$ mkdirlaunch
$ cd launch
$ gedit union.launch
====5.2. 예시 2====
$ roscd ros tutorials_topic/launch
$ gedit union.launch