service_client_imp.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2009, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage, Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
37 #ifndef ACTIONLIB__CLIENT__SERVICE_CLIENT_IMP_H_
38 #define ACTIONLIB__CLIENT__SERVICE_CLIENT_IMP_H_
39 
40 #include <string>
41 
42 #include "ros/console.h"
43 
44 namespace actionlib
45 {
46 template<class ActionSpec>
48 {
49  ac_.reset(new SimpleActionClientT(n, name, true));
50 }
51 
52 template<class ActionSpec>
54 {
55  return ac_->waitForServer(timeout);
56 }
57 
58 template<class ActionSpec>
60 {
61  return ac_->isServerConnected();
62 }
63 
64 template<class ActionSpec>
65 bool ServiceClientImpT<ActionSpec>::call(const void * goal, std::string goal_md5sum,
66  void * result, std::string result_md5sum)
67 {
68  // ok... we need to static cast the goal message and result message
69  const Goal * goal_c = static_cast<const Goal *>(goal);
70  Result * result_c = static_cast<Result *>(result);
71 
72  // now we need to check that the md5sums are correct
73  namespace mt = ros::message_traits;
74 
75  if (strcmp(mt::md5sum(*goal_c),
76  goal_md5sum.c_str()) || strcmp(mt::md5sum(*result_c), result_md5sum.c_str()))
77  {
78  ROS_ERROR_NAMED("actionlib", "Incorrect md5Sums for goal and result types");
79  return false;
80  }
81 
82  if (!ac_->isServerConnected()) {
83  ROS_ERROR_NAMED("actionlib",
84  "Attempting to make a service call when the server isn't actually connected to the client.");
85  return false;
86  }
87 
88  ac_->sendGoalAndWait(*goal_c);
89  if (ac_->getState() == SimpleClientGoalState::SUCCEEDED) {
90  (*result_c) = *(ac_->getResult());
91  return true;
92  }
93 
94  return false;
95 }
96 
97 //****** ServiceClient *******************
98 template<class Goal, class Result>
99 bool ServiceClient::call(const Goal & goal, Result & result)
100 {
101  namespace mt = ros::message_traits;
102  return client_->call(&goal, mt::md5sum(goal), &result, mt::md5sum(result));
103 }
104 
106 {
107  return client_->waitForServer(timeout);
108 }
109 
111 {
112  return client_->isServerConnected();
113 }
114 
115 //****** actionlib::serviceClient *******************
116 template<class ActionSpec>
118 {
120  return ServiceClient(client_ptr);
121 }
122 
123 } // namespace actionlib
124 #endif // ACTIONLIB__CLIENT__SERVICE_CLIENT_IMP_H_
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0))
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
boost::shared_ptr< ServiceClientImp > client_
bool waitForServer(const ros::Duration &timeout)
bool call(const Goal &goal, Result &result)
A Simple client implementation of the ActionInterface which supports only one goal at a time...
#define ROS_ERROR_NAMED(name,...)
bool call(const void *goal, std::string goal_md5sum, void *result, std::string result_md5sum)
ServiceClientImpT(ros::NodeHandle n, std::string name)
ServiceClient(boost::shared_ptr< ServiceClientImp > client)


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Feb 28 2022 21:34:38