-
Notifications
You must be signed in to change notification settings - Fork 155
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
finish doneCb before waitForResult returns #156
Changes from all commits
e836981
0db4fe3
61d95ae
5b07440
5b6c38c
88d6c55
86ea5e4
75fec60
56d1afc
94367db
a48f586
cd2c25e
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -79,23 +79,17 @@ TEST(SimpleClient, easy_tests) { | |
} | ||
|
||
|
||
void easyDoneCallback(bool * called, const SimpleClientGoalState & state, | ||
void easyDoneCallback(bool * called, SimpleActionClient<TestAction> * 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(); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. i believe this should be done by waitForServer. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Yep, it should. But actually it isn't, see my comment above: #156 (comment) There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. i understand this is just a work-around to pass the test, but even with this duration SimpleClientFixture fails with server state is still ACTIVE (expected to be SUCCESS). so I expect this additional duration is not needed. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. It's the unrelated test file
|
||
|
||
TestGoal goal; | ||
bool finished; | ||
|
||
bool called = false; | ||
goal.goal = 1; | ||
SimpleActionClient<TestAction>::SimpleDoneCallback func = boost::bind(&easyDoneCallback, &called, _1, _2); | ||
SimpleActionClient<TestAction>::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; | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,9 @@ | ||
<launch> | ||
|
||
<node name="mock_simple_server" | ||
pkg="actionlib" type="mock_simple_server.py" output="screen" /> | ||
|
||
<test test-name="test_cpp_simple_client" time-limit="90" | ||
pkg="actionlib" type="actionlib-exercise_simple_client" /> | ||
|
||
</launch> |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
what is this duration for?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
It's a callback, that takes some time and gives execution back to the main thread in the mean time. Without the fix, this test case
easy_callback
fails.There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
See also reproduction step 2. in #155.