server_goal_handle_destruction.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
36 
38 #include <actionlib/TestAction.h>
40 #include <ros/ros.h>
41 #include <gtest/gtest.h>
42 
43 namespace actionlib
44 {
45 
47 {
48 public:
50 
52 
55  GoalHandle * gh_;
56 
58  void goalCallback(GoalHandle gh);
59 };
60 
61 } // namespace actionlib
62 
63 using namespace actionlib;
64 
66 {
67  as_ = new ActionServer<TestAction>(nh_, "reference_action", false);
68  as_->start();
70  _1));
71  gh_ = new GoalHandle();
72 }
73 
75 {
76  delete as_;
77  gh_->setAccepted();
78  delete gh_;
79 }
80 
82 {
83  ROS_ERROR_NAMED("actionlib", "In callback");
84  // assign to our stored goal handle
85  *gh_ = gh;
86 
87  TestGoal goal = *gh.getGoal();
88 
89  switch (goal.goal) {
90  case 1:
91  gh.setAccepted();
92  gh.setSucceeded(TestResult(), "The ref server has succeeded");
93  break;
94  case 2:
95  gh.setAccepted();
96  gh.setAborted(TestResult(), "The ref server has aborted");
97  break;
98  case 3:
99  gh.setRejected(TestResult(), "The ref server has rejected");
100  break;
101  default:
102  break;
103  }
104 
105  ros::shutdown();
106 }
107 
108 void spinner()
109 {
110  ros::spin();
111 }
112 
113 TEST(ServerGoalHandleDestruction, destruction_test) {
114  boost::thread spin_thread(&spinner);
115 
117 
118  SimpleActionClient<TestAction> client("reference_action", true);
119 
120  ROS_ERROR_NAMED("actionlib", "Waiting for server");
121  client.waitForServer();
122  ROS_ERROR_NAMED("actionlib", "Done waiting for server");
123 
124  TestGoal goal;
125 
126  goal.goal = 1;
127  client.sendGoal(goal);
128  ROS_ERROR_NAMED("actionlib", "Sending goal");
129 
130  spin_thread.join();
131 }
132 
133 int main(int argc, char ** argv)
134 {
135  testing::InitGoogleTest(&argc, argv);
136 
137  ros::init(argc, argv, "ref_server");
138 
139  return RUN_ALL_TESTS();
140 }
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
Waits for the ActionServer to connect to this client.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void setRejected(const Result &result=Result(), const std::string &text=std::string(""))
Set the status of the goal associated with the ServerGoalHandle to rejected.
boost::shared_ptr< const Goal > getGoal() const
Accessor for the goal associated with the ServerGoalHandle.
void setAccepted(const std::string &text=std::string(""))
Accept the goal referenced by the goal handle. This will transition to the ACTIVE state or the PREEMP...
int main(int argc, char **argv)
void registerGoalCallback(boost::function< void(GoalHandle)> cb)
Register a callback to be invoked when a new goal is received, this will replace any previously regis...
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
Set the status of the goal associated with the ServerGoalHandle to succeeded.
ROSCPP_DECL void spin()
A Simple client implementation of the ActionInterface which supports only one goal at a time...
Encapsulates a state machine for a given goal that the user can trigger transitions on...
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
Set the status of the goal associated with the ServerGoalHandle to aborted.
void start()
Explicitly start the action server, used it auto_start is set to false.
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
Sends a goal to the ActionServer, and also registers callbacks.
#define ROS_ERROR_NAMED(name,...)
ROSCPP_DECL void shutdown()
TEST(ServerGoalHandleDestruction, destruction_test)


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Feb 18 2019 03:59:59