Broken sending goals from doneCb in noetic
After https://github.com/ros/actionlib/issues/155 one of our use cases is broken.
If you are using a SimpleActionClient, and on your done_cb send another goal, it is possible that a status message or result message from the previous goal is interpreted for the current goal.
This code sample fails on 1.13.2 but works fine on 1.12.1:
#include <actionlib_tutorials/FibonacciAction.h>
#include <actionlib/client/simple_action_client.h>
#include <actionlib/server/simple_action_server.h>
#include <ros/ros.h>
class FibonacciAction
{
protected:
ros::NodeHandle nh_;
actionlib::SimpleActionServer<actionlib_tutorials::FibonacciAction>
as_; // NodeHandle instance must be created before this line. Otherwise strange error occurs.
std::string action_name_;
public:
FibonacciAction(std::string name)
: as_(nh_, name, boost::bind(&FibonacciAction::executeCB, this, _1), false)
, action_name_(name)
{
as_.start();
}
void executeCB(const actionlib_tutorials::FibonacciGoalConstPtr &goal)
{
as_.setSucceeded();
}
};
std::unique_ptr<actionlib::SimpleActionClient<actionlib_tutorials::FibonacciAction>> client;
void done_cb(const actionlib::SimpleClientGoalState &state,
const actionlib_tutorials::FibonacciResultConstPtr &result)
{
ROS_INFO_STREAM("Goal done ");
actionlib_tutorials::FibonacciGoal goal;
goal.order = 1;
client->sendGoal(goal, &done_cb);
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "test_fibonacci");
ros::AsyncSpinner spinner(1);
spinner.start();
FibonacciAction server("fibonacci");
client.reset(new actionlib::SimpleActionClient<actionlib_tutorials::FibonacciAction>(
"fibonacci", true));
ROS_INFO("Waiting for action server to start.");
// wait for the action server to start
client->waitForServer(); // will wait for infinite time
ROS_INFO("Action server started, sending goal.");
// send a goal to the action
actionlib_tutorials::FibonacciGoal goal;
client->sendGoal(goal, &done_cb);
while (ros::ok())
{
ros::Duration(.1).sleep();
}
// exit
return 0;
}
After #155 it gets stuck with:
[ INFO] [1631185426.628695785]: Waiting for action server to start. [ INFO] [1631185426.822095819]: Action server started, sending goal. [ INFO] [1631185426.822328039]: Goal done [ERROR] [1631185426.822456738]: BUG: Got a transition to CommState [ACTIVE] when in SimpleGoalState [DONE] [ERROR] [1631185426.822487358]: BUG: Got a second transition to DONE:
After #155 one of our use cases is broken.
If you are using a SimpleActionClient, and on your
done_cbsend another goal, it is possible that a status message or result message from the previous goal is interpreted for the current goal.This code sample fails on 1.13.2 but works fine on 1.12.1:
#include <actionlib_tutorials/FibonacciAction.h> #include <actionlib/client/simple_action_client.h> #include <actionlib/server/simple_action_server.h> #include <ros/ros.h> class FibonacciAction { protected: ros::NodeHandle nh_; actionlib::SimpleActionServer<actionlib_tutorials::FibonacciAction> as_; // NodeHandle instance must be created before this line. Otherwise strange error occurs. std::string action_name_; public: FibonacciAction(std::string name) : as_(nh_, name, boost::bind(&FibonacciAction::executeCB, this, _1), false) , action_name_(name) { as_.start(); } void executeCB(const actionlib_tutorials::FibonacciGoalConstPtr &goal) { as_.setSucceeded(); } }; std::unique_ptr<actionlib::SimpleActionClient<actionlib_tutorials::FibonacciAction>> client; void done_cb(const actionlib::SimpleClientGoalState &state, const actionlib_tutorials::FibonacciResultConstPtr &result) { ROS_INFO_STREAM("Goal done "); actionlib_tutorials::FibonacciGoal goal; goal.order = 1; client->sendGoal(goal, &done_cb); } int main(int argc, char **argv) { ros::init(argc, argv, "test_fibonacci"); ros::AsyncSpinner spinner(1); spinner.start(); FibonacciAction server("fibonacci"); client.reset(new actionlib::SimpleActionClient<actionlib_tutorials::FibonacciAction>( "fibonacci", true)); ROS_INFO("Waiting for action server to start."); // wait for the action server to start client->waitForServer(); // will wait for infinite time ROS_INFO("Action server started, sending goal."); // send a goal to the action actionlib_tutorials::FibonacciGoal goal; client->sendGoal(goal, &done_cb); while (ros::ok()) { ros::Duration(.1).sleep(); } // exit return 0; }After #155 it gets stuck with:
[ INFO] [1631185426.628695785]: Waiting for action server to start. [ INFO] [1631185426.822095819]: Action server started, sending goal. [ INFO] [1631185426.822328039]: Goal done [ERROR] [1631185426.822456738]: BUG: Got a transition to CommState [ACTIVE] when in SimpleGoalState [DONE] [ERROR] [1631185426.822487358]: BUG: Got a second transition to DONE:
I have the same problem,do you have a solution?

We had to implement a hacky workaround. I believe we use a single shot timer to send the new goal later, instead of right at the doneCb.
We had to implement a hacky workaround. I believe we use a single shot timer to send the new goal later, instead of right at the doneCb.
I think this is not the optimal solution, I hope it can be solved completely