Skip to content

Commit

Permalink
adding stuff for the service client tutorial
Browse files Browse the repository at this point in the history
  • Loading branch information
wjwwood committed Nov 21, 2012
1 parent 0202ed2 commit 270389a
Show file tree
Hide file tree
Showing 14 changed files with 482 additions and 0 deletions.
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1 +1,3 @@
build
devel
install
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
int64 num
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
#include "ros/ros.h"
#include "std_msgs/String.h"

/**
* This tutorial demonstrates simple receipt of messages over the ROS system.
*/
void chatterCallback(const std_msgs::String::ConstPtr& msg)
{
ROS_INFO("I heard: [%s]", msg->data.c_str());
}

int main(int argc, char **argv)
{
/**
* The ros::init() function needs to see argc and argv so that it can
* perform any ROS arguments and name remapping that were provided
* at the command line. For programmatic remappings you can use a
* different version of init() which takes remappings directly, but
* for most command-line programs, passing argc and argv is the easiest
* way to do it. The third argument to init() is the name of the node.
*
* You must call one of the versions of ros::init() before using any other
* part of the ROS system.
*/
ros::init(argc, argv, "listener");

/**
* NodeHandle is the main access point to communications with the
* ROS system. The first NodeHandle constructed will fully initialize
* this node, and the last NodeHandle destructed will close down the node.
*/
ros::NodeHandle n;

/**
* The subscribe() call is how you tell ROS that you want to receive
* messages on a given topic. This invokes a call to the ROS master
* node, which keeps a registry of who is publishing and who is subscribing.
* Messages are passed to a callback function, here called chatterCallback.
* subscribe() returns a Subscriber object that you must hold on to
* until you want to unsubscribe. When all copies of the Subscriber
* object go out of scope, this callback will automatically be
* unsubscribed from this topic.
*
* The second parameter to the subscribe() function is the size of
* the message queue. If messages are arriving faster than they are
* being processed, this is the number of messages that will be
* buffered up before beginning to throw away the oldest ones.
*/
ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);

/**
* ros::spin() will enter a loop, pumping callbacks. With this
* version, all callbacks will be called from within this thread
* (the main one). ros::spin() will exit when Ctrl-C is pressed,
* or the node is shutdown by the master.
*/
ros::spin();

return 0;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
#include "ros/ros.h"
#include "std_msgs/String.h"

#include <sstream>

/**
* This tutorial demonstrates simple sending of messages over the ROS system.
*/
int main(int argc, char **argv)
{
/**
* The ros::init() function needs to see argc and argv so that it can
* perform any ROS arguments and name remapping that were provided at
* the command line. For programmatic remappings you can use a
* different version of init() which takes remappings directly, but
* for most command-line programs, passing argc and argv is the easiest
* way to do it. The third argument to init() is the name of the node.
*
* You must call one of the versions of ros::init() before using any
* other part of the ROS system.
*/
ros::init(argc, argv, "talker");

/**
* NodeHandle is the main access point to communications with the
* ROS system. The first NodeHandle constructed will fully initialize
* this node, and the last NodeHandle destructed will close down
* the node.
*/
ros::NodeHandle n;

/**
* The advertise() function is how you tell ROS that you want to
* publish on a given topic name. This invokes a call to the ROS
* master node, which keeps a registry of who is publishing and who
* is subscribing. After this advertise() call is made, the master
* node will notify anyone who is trying to subscribe to this topic name,
* and they will in turn negotiate a peer-to-peer connection with this
* node. advertise() returns a Publisher object which allows you to
* publish messages on that topic through a call to publish(). Once
* all copies of the returned Publisher object are destroyed, the topic
* will be automatically unadvertised.
*
* The second parameter to advertise() is the size of the message queue
* used for publishing messages. If messages are published more quickly
* than we can send them, the number here specifies how many messages to
* buffer up before throwing some away.
*/
ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);

ros::Rate loop_rate(10);

/**
* A count of how many messages we have sent. This is used to create
* a unique string for each message.
*/
int count = 0;
while (ros::ok())
{
/**
* This is a message object. You stuff it with data, and then publish it.
*/
std_msgs::String msg;

std::stringstream ss;
ss << "hello world " << count;
msg.data = ss.str();

ROS_INFO("%s", msg.data.c_str());

/**
* The publish() function is how you send messages. The parameter
* is the message object. The type of this object must agree with the type
* given as a template parameter to the advertise<>() call, as was done
* in the constructor above.
*/
chatter_pub.publish(msg);

ros::spinOnce();

loop_rate.sleep();
++count;
}


return 0;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
int64 a
int64 b
---
int64 sum
47 changes: 47 additions & 0 deletions create_package_srvclient/catkin_ws/src/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
# toplevel CMakeLists.txt for a catkin workspace
# catkin/cmake/toplevel.cmake

cmake_minimum_required(VERSION 2.8.3)

# optionally provide a cmake file in the workspace to override arbitrary stuff
include(workspace.cmake OPTIONAL)

set(CATKIN_TOPLEVEL TRUE)

# include catkin directly or via find_package()
if(EXISTS "${CMAKE_SOURCE_DIR}/catkin/cmake/all.cmake" AND EXISTS "${CMAKE_SOURCE_DIR}/catkin/CMakeLists.txt")
set(catkin_EXTRAS_DIR "${CMAKE_SOURCE_DIR}/catkin/cmake")
# include all.cmake without add_subdirectory to let it operate in same scope
include(catkin/cmake/all.cmake NO_POLICY_SCOPE)
add_subdirectory(catkin)

else()
# use either CMAKE_PREFIX_PATH explicitly passed to CMake as a command line argument
# or CMAKE_PREFIX_PATH from the environment
if(NOT DEFINED CMAKE_PREFIX_PATH)
if(NOT "$ENV{CMAKE_PREFIX_PATH}" STREQUAL "")
string(REPLACE ":" ";" CMAKE_PREFIX_PATH $ENV{CMAKE_PREFIX_PATH})
endif()
endif()

# list of catkin workspaces
set(catkin_search_path "")
foreach(path ${CMAKE_PREFIX_PATH})
if(EXISTS "${path}/.CATKIN_WORKSPACE")
list(FIND catkin_search_path ${path} _index)
if(_index EQUAL -1)
list(APPEND catkin_search_path ${path})
endif()
endif()
endforeach()

# search for catkin in all workspaces
set(CATKIN_TOPLEVEL_FIND_PACKAGE TRUE)
find_package(catkin REQUIRED
NO_POLICY_SCOPE
PATHS ${catkin_search_path}
NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH)
unset(CATKIN_TOPLEVEL_FIND_PACKAGE)
endif()

catkin_workspace()
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
# %Tag(FULLTEXT)%
cmake_minimum_required(VERSION 2.8.3)
project(beginner_tutorials)

## Find catkin and any catkin packages
find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs genmsg)

## Declare ROS messages and services
add_message_files(DIRECTORY msg FILES Num.msg)
add_service_files(DIRECTORY srv FILES AddTwoInts.srv)

## Generate added messages and services
generate_messages(DEPENDENCIES std_msgs)

## Declare a catkin package
catkin_package()

## Build talker and listener
include_directories(include ${catkin_INCLUDE_DIRS})

add_executable(talker src/talker.cpp)
target_link_libraries(talker ${catkin_LIBRARIES})

add_executable(listener src/listener.cpp)
target_link_libraries(listener ${catkin_LIBRARIES})

## Build service client and server
add_executable(add_two_ints_server src/add_two_ints_server.cpp)
target_link_libraries(add_two_ints_server ${catkin_LIBRARIES})

add_executable(add_two_ints_client src/add_two_ints_client.cpp)
target_link_libraries(add_two_ints_client ${catkin_LIBRARIES})

# %EndTag(FULLTEXT)%
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
int64 num
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
<?xml version="1.0"?>
<!-- %Tag(FULLTEXT,-1)% -->
<package>
<!-- %Tag(NAME)% -->
<name>beginner_tutorials</name>
<!-- %EndTag(NAME)% -->
<!-- %Tag(VERSION)% -->
<version>0.1.0</version>
<!-- %EndTag(VERSION)% -->
<!-- %Tag(DESC)% -->
<description>The beginner_tutorials package</description>
<!-- %EndTag(DESC)% -->

<!-- %Tag(MAINTAINER)% -->
<maintainer email="you@yourdomain.tld">Your Name</maintainer>
<!-- %EndTag(MAINTAINER)% -->
<!-- %Tag(LICENSE)% -->
<license>BSD</license>
<!-- %EndTag(LICENSE)% -->
<!-- %Tag(URLS)% -->
<url type="website">http://wiki.ros.org/beginner_tutorials</url>
<!-- %EndTag(URLS)% -->
<!-- %Tag(AUTHORS)% -->
<author email="you@yourdomain.tld">Jane Doe</author>
<!-- %EndTag(AUTHORS)% -->

<!-- %Tag(DEPS)% -->
<buildtool_depend>catkin</buildtool_depend>

<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>

<run_depend>roscpp</run_depend>
<run_depend>rospy</run_depend>
<run_depend>std_msgs</run_depend>
<!-- %EndTag(DEPS)% -->

<!-- %Tag(EXPORT)% -->
<!-- %EndTag(EXPORT)% -->
</package>
<!-- %EndTag(FULLTEXT)% -->
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#include "ros/ros.h"
#include "beginner_tutorials/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<beginner_tutorials::AddTwoInts>("add_two_ints");
beginner_tutorials::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;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
#include "ros/ros.h"
#include "beginner_tutorials/AddTwoInts.h"

bool add(beginner_tutorials::AddTwoInts::Request &req,
beginner_tutorials::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;
}
Loading

0 comments on commit 270389a

Please sign in to comment.