Skip to content
Snippets Groups Projects
Commit ce5abacb authored by Sebastian Ebert's avatar Sebastian Ebert
Browse files

code for service tutorial

parent ea2d0181
Branches
No related tags found
No related merge requests found
......@@ -26,3 +26,11 @@ add_dependencies(talker tutorial_ros_pub_sub_generate_messages_cpp)
add_executable(listener src/listener.cpp)
target_link_libraries(listener ${catkin_LIBRARIES})
add_dependencies(listener tutorial_ros_pub_sub_generate_messages_cpp)
add_executable(add_two_ints_server src/add_two_ints_server.cpp)
target_link_libraries(add_two_ints_server ${catkin_LIBRARIES})
add_dependencies(add_two_ints_server tutorial_ros_pub_sub_generate_gencpp)
add_executable(add_two_ints_client src/add_two_ints_client.cpp)
target_link_libraries(add_two_ints_client ${catkin_LIBRARIES})
add_dependencies(add_two_ints_client tutorial_ros_pub_sub_generate_gencpp)
#include "ros/ros.h"
#include "tutorial_ros_pub_sub/AddTwoInts.h"
#include <cstdlib>
int main(int argc, char **argv)
{
ros::init(argc, argv, "add_two_ints_client");
if (argc != 3)
{
ROS_INFO("usage: add_two_ints_client X Y");
return 1;
}
ros::NodeHandle n;
ros::ServiceClient client = n.serviceClient<tutorial_ros_pub_sub::AddTwoInts>("add_two_ints");
tutorial_ros_pub_sub::AddTwoInts srv;
srv.request.a = atoll(argv[1]);
srv.request.b = atoll(argv[2]);
if (client.call(srv))
{
ROS_INFO("Sum: %ld", (long int)srv.response.sum);
}
else
{
ROS_ERROR("Failed to call service add_two_ints");
return 1;
}
return 0;
}
#include "ros/ros.h"
#include "tutorial_ros_pub_sub/AddTwoInts.h"
bool add(tutorial_ros_pub_sub::AddTwoInts::Request &req,
tutorial_ros_pub_sub::AddTwoInts::Response &res)
{
res.sum = req.a + req.b;
ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b);
ROS_INFO("sending back response: [%ld]", (long int)res.sum);
return true;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "add_two_ints_server");
ros::NodeHandle n;
ros::ServiceServer service = n.advertiseService("add_two_ints", add);
ROS_INFO("Ready to add two ints.");
ros::spin();
return 0;
}
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment