Skip to content

Commit

Permalink
Workaround actionlib race (#83)
Browse files Browse the repository at this point in the history
Looks like there is a race condition in actionlib when calling getState soon after sendGoal:
[ INFO] [1714746133.764753198]: MowingBehavior: (FIRST POINT)  Moving to path segment starting point
[ERROR] [1714746133.766643334]: getElem() should not see invalid handles

Try adding a sleep to workaround it.
  • Loading branch information
olliewalsh authored May 5, 2024
1 parent c232cd6 commit 378db90
Showing 1 changed file with 2 additions and 0 deletions.
2 changes: 2 additions & 0 deletions src/mower_logic/src/mower_logic/behaviors/MowingBehavior.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -328,6 +328,7 @@ bool MowingBehavior::execute_mowing_plan() {
moveBaseGoal.target_pose = path.path.poses[currentMowingPathIndex];
moveBaseGoal.controller = "FTCPlanner";
mbfClient->sendGoal(moveBaseGoal);
sleep(1);
actionlib::SimpleClientGoalState current_status(actionlib::SimpleClientGoalState::PENDING);
ros::Rate r(10);

Expand Down Expand Up @@ -438,6 +439,7 @@ bool MowingBehavior::execute_mowing_plan() {

ROS_INFO_STREAM("MowingBehavior: (MOW) First point reached - Executing mow path with " << path.path.poses.size() << " poses, from index " << exePathStartIndex);
mbfClientExePath->sendGoal(exePathGoal);
sleep(1);
actionlib::SimpleClientGoalState current_status(actionlib::SimpleClientGoalState::PENDING);
ros::Rate r(10);

Expand Down

0 comments on commit 378db90

Please sign in to comment.