Action Client Not Picking Up Messages from Action Server
Hi,
I'm not sure what I've missed here. Simply I have followed the action server/client tutorials and I've extended my own messages so that I can determine if the robot has or has not docked successfully.
I can see that the server is publishing the messages correctly however I must be missing something on the client side because despite setting up the callbacks when sendGoal is called and I can see that the callback is indeed called the message from the server isn't coming through.
Trying to show by example:
Server outputs:
[INFO] [1538084823.620614089]: DockDrive::processBumpChargeEvent
[INFO] [1538084823.620698260]: Docked DONE! [ INFO] [1538084823.620843878]:[/fibonacci]: Arrived on docking station successfully.
Running
rostopic echo /fibonacci/result shows:
status:
goal_id:
stamp:
secs: 1538084809
nsecs: 414171018
id: "/test_fibonacci-1-1538084809.414171018"
status: 3
text: ''
result:
text: "Arrived on docking station successfully."
state: "DONE"
Note Result message Text and State are set
On the Client side "Answer" is just a "?". It should read the text part of the result above i.e. "Arrived on docking station successfully."
[ INFO] [1538084809.141452693]: Waiting for action server to start.
[ INFO] [1538084809.414082459]: Action server started, sending goal.
[ INFO] [1538084809.415720796]: Goal just went active
[ INFO] [1538084823.621925341]: Finished in state [SUCCEEDED]
**[ INFO] [1538084823.622168467]: Answer: ?**
[ INFO] [1538084823.622424793]: Docked OK!
[ INFO] [1538084823.622538900]: Action finished: SUCCEEDED
The relevant parts of the Client side code:
Callback defined as:
void doneCb(const actionlib::SimpleClientGoalState& state,
const AutoDockingResultConstPtr& result)
{
ROS_INFO("Finished in state [%s]", state.toString().c_str());
ROS_INFO("Answer: %s", result->text);
}
And the main body of the code is:
void spinThread()
{
ros::spin();
}
int main (int argc, char **argv)
{
ros::init(argc, argv, "test_fibonacci");
// create the action client
// true causes the client to spin it's own thread
actionlib::SimpleActionClient<mxnet_actionlib::AutoDockingAction> ac("fibonacci", true);
boost::thread spin_thread(&spinThread);
ROS_INFO("Waiting for action server to start.");
// wait for the action server to start
ac.waitForServer(); //will wait for infinite time
ROS_INFO("Action server started, sending goal.");
// send a goal to the action
mxnet_actionlib::AutoDockingGoal goal;
// Need to register for feedback
ac.sendGoal(goal, &doneCb, &activeCb, &feedbackCb);
//wait for the action to return
bool finished_before_timeout = ac.waitForResult();
actionlib::SimpleClientGoalState state = ac.getState();
if (state == actionlib::SimpleClientGoalState::LOST)
{
ROS_INFO("Docking Lost - Attempting Redocking");
}
else if (state == actionlib::SimpleClientGoalState::SUCCEEDED)
{
ROS_INFO("Docked OK!");
}
else
{
ROS_INFO("Docking Failed!");
}
if (finished_before_timeout)
{
actionlib::SimpleClientGoalState state = ac.getState();
ROS_INFO("Action finished: %s",state.toString().c_str());
}
else
ROS_INFO("Action did not finish before the time out.");
return 0;
}
If someone can see what I've missed here I'd appreciate it.
Many Thanks
Mark