diff --git a/actionlib/CMakeLists.txt b/actionlib/CMakeLists.txt index 327beffd..ce583b80 100644 --- a/actionlib/CMakeLists.txt +++ b/actionlib/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.0.2) project(actionlib) find_package(catkin REQUIRED COMPONENTS actionlib_msgs message_generation roscpp std_msgs) diff --git a/actionlib/include/actionlib/client/simple_action_client.h b/actionlib/include/actionlib/client/simple_action_client.h index cb85154f..52637edb 100644 --- a/actionlib/include/actionlib/client/simple_action_client.h +++ b/actionlib/include/actionlib/client/simple_action_client.h @@ -535,15 +535,15 @@ void SimpleActionClient::handleTransition(GoalHandleT gh) switch (cur_simple_state_.state_) { case SimpleGoalState::PENDING: case SimpleGoalState::ACTIVE: + if (done_cb_) { + done_cb_(getState(), gh.getResult()); + } + { boost::mutex::scoped_lock lock(done_mutex_); setSimpleState(SimpleGoalState::DONE); } - if (done_cb_) { - done_cb_(getState(), gh.getResult()); - } - done_condition_.notify_all(); break; case SimpleGoalState::DONE: diff --git a/actionlib/test/CMakeLists.txt b/actionlib/test/CMakeLists.txt index 4add4fdb..395eb5bf 100644 --- a/actionlib/test/CMakeLists.txt +++ b/actionlib/test/CMakeLists.txt @@ -61,7 +61,8 @@ add_rostest(test_python_server.launch) add_rostest(test_python_server2.launch) add_rostest(test_python_server3.launch) add_rostest(test_python_simple_server.launch) -add_rostest(test_exercise_simple_clients.launch) +add_rostest(test_cpp_exercise_simple_client.launch) +add_rostest(test_python_exercise_simple_client.launch) add_rostest(test_simple_action_server_deadlock_python.launch) catkin_add_gtest(actionlib-destruction_guard_test destruction_guard_test.cpp) diff --git a/actionlib/test/simple_client_test.cpp b/actionlib/test/simple_client_test.cpp index ca6c144c..341bbc9f 100644 --- a/actionlib/test/simple_client_test.cpp +++ b/actionlib/test/simple_client_test.cpp @@ -79,23 +79,17 @@ TEST(SimpleClient, easy_tests) { } -void easyDoneCallback(bool * called, const SimpleClientGoalState & state, +void easyDoneCallback(bool * called, SimpleActionClient * ac, const SimpleClientGoalState & state, const TestResultConstPtr &) { - *called = true; + EXPECT_TRUE(ac->getState() == SimpleClientGoalState::SUCCEEDED) + << "Expected [SUCCEEDED], but getState() returned [" << ac->getState().toString() << "]"; EXPECT_TRUE(state == SimpleClientGoalState::SUCCEEDED) << "Expected [SUCCEEDED], but goal state is [" << state.toString() << "]"; -} - -void easyOldDoneCallback(bool * called, const TerminalState & terminal_state, - const TestResultConstPtr &) -{ + ros::Duration(0.1).sleep(); *called = true; - EXPECT_TRUE(terminal_state == TerminalState::SUCCEEDED) - << "Expected [SUCCEEDED], but terminal state is [" << terminal_state.toString() << "]"; } -/* Intermittent failures #5087 TEST(SimpleClient, easy_callback) { ros::NodeHandle n; @@ -104,18 +98,21 @@ TEST(SimpleClient, easy_callback) bool started = client.waitForServer(ros::Duration(10.0)); ASSERT_TRUE(started); + // sleep a bit to make sure that all topics are properly connected to the server. + ros::Duration(0.01).sleep(); + TestGoal goal; bool finished; bool called = false; goal.goal = 1; - SimpleActionClient::SimpleDoneCallback func = boost::bind(&easyDoneCallback, &called, _1, _2); + SimpleActionClient::SimpleDoneCallback func = boost::bind(&easyDoneCallback, &called, &client, _1, _2); client.sendGoal(goal, func); finished = client.waitForResult(ros::Duration(10.0)); ASSERT_TRUE(finished); EXPECT_TRUE(called) << "easyDoneCallback() was never called" ; } -*/ + void spinThread() { ros::NodeHandle nh; diff --git a/actionlib/test/test_cpp_exercise_simple_client.launch b/actionlib/test/test_cpp_exercise_simple_client.launch new file mode 100644 index 00000000..c7804f41 --- /dev/null +++ b/actionlib/test/test_cpp_exercise_simple_client.launch @@ -0,0 +1,9 @@ + + + + + + + diff --git a/actionlib/test/test_exercise_simple_clients.launch b/actionlib/test/test_python_exercise_simple_client.launch similarity index 67% rename from actionlib/test/test_exercise_simple_clients.launch rename to actionlib/test/test_python_exercise_simple_client.launch index c54905df..e541913d 100644 --- a/actionlib/test/test_exercise_simple_clients.launch +++ b/actionlib/test/test_python_exercise_simple_client.launch @@ -6,7 +6,4 @@ - - diff --git a/actionlib_tools/CMakeLists.txt b/actionlib_tools/CMakeLists.txt index e4dbdc62..0f76fa4f 100644 --- a/actionlib_tools/CMakeLists.txt +++ b/actionlib_tools/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.0.2) project(actionlib_tools) find_package(catkin REQUIRED)