32 #include <gtest/gtest.h> 34 #include <actionlib/TestRequestAction.h> 35 #include <actionlib/TestRequestGoal.h> 37 #include <actionlib_msgs/GoalStatus.h> 40 #define EXPECT_STATE(expected_state) EXPECT_TRUE( \ 41 ac_.getState() == SimpleClientGoalState::expected_state) \ 42 << "Expected [" << #expected_state << "], but goal state is [" << ac_.getState().toString() << \ 53 : ac_(
"test_request_action"), default_wait_(60.0) {}
68 goal.terminate_status = TestRequestGoal::TERMINATE_SUCCESS;
71 ac_.waitForResult(default_wait_);
73 EXPECT_EQ(42, ac_.getResult()->the_result);
78 goal.terminate_status = TestRequestGoal::TERMINATE_ABORTED;
81 ac_.waitForResult(default_wait_);
83 EXPECT_EQ(42, ac_.getResult()->the_result);
88 goal.terminate_status = TestRequestGoal::TERMINATE_SUCCESS;
94 for (
unsigned int i = 0; i < 100; i++) {
103 ac_.waitForResult(default_wait_);
105 EXPECT_EQ(42, ac_.getResult()->the_result);
109 TestRequestGoal goal;
110 goal.terminate_status = TestRequestGoal::TERMINATE_DROP;
111 goal.the_result = 42;
113 ac_.waitForResult(default_wait_);
115 EXPECT_EQ(0, ac_.getResult()->the_result);
119 TestRequestGoal goal;
120 goal.terminate_status = TestRequestGoal::TERMINATE_EXCEPTION;
121 goal.the_result = 42;
123 ac_.waitForResult(default_wait_);
125 EXPECT_EQ(0, ac_.getResult()->the_result);
129 TestRequestGoal goal;
130 goal.terminate_status = TestRequestGoal::TERMINATE_SUCCESS;
132 goal.ignore_cancel =
true;
133 goal.the_result = 42;
137 for (
unsigned int i = 0; i < 100; i++) {
146 ac_.waitForResult(default_wait_ + default_wait_);
148 EXPECT_EQ(42, ac_.getResult()->the_result);
152 TestRequestGoal goal;
153 goal.terminate_status = TestRequestGoal::TERMINATE_LOSE;
154 goal.the_result = 42;
156 ac_.waitForResult(default_wait_);
166 int main(
int argc,
char ** argv)
168 testing::InitGoogleTest(&argc, argv);
170 ros::init(argc, argv,
"simple_client_test");
174 int result = RUN_ALL_TESTS();
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define EXPECT_STATE(expected_state)
SimpleActionClient< TestRequestAction > ac_
#define ROS_DEBUG_NAMED(name,...)
TEST_F(SimpleClientFixture, just_succeed)
ros::Duration default_wait_
ROSCPP_DECL void shutdown()