From d74ee960d9e1339d7c4eb12db039b113c82a2400 Mon Sep 17 00:00:00 2001
From: Sergi Hernandez Juan <shernand@iri.upc.edu>
Date: Tue, 16 May 2023 11:14:16 +0200
Subject: [PATCH] In the action_done callback, the action status is only
 updated if the tiemout and watchdog have not been activated.

---
 include/iri_ros_tools/module_action.h | 39 ++++++++++++++-------------
 1 file changed, 21 insertions(+), 18 deletions(-)

diff --git a/include/iri_ros_tools/module_action.h b/include/iri_ros_tools/module_action.h
index c960934..8932320 100644
--- a/include/iri_ros_tools/module_action.h
+++ b/include/iri_ros_tools/module_action.h
@@ -217,26 +217,29 @@ class CModuleAction
     void action_done(const actionlib::SimpleClientGoalState& state,const ResultConstPtr& result)
     {
       this->action_access.enter();
-      if(state==actionlib::SimpleClientGoalState::ABORTED)
+      if(this->status==ACTION_RUNNING)
       {
-        ROS_ERROR_STREAM("CModuleAction::action_done: goal on server " << this->name << " aborted");
-        this->status=ACTION_ABORTED;
-      }
-      if(state==actionlib::SimpleClientGoalState::REJECTED)
-      {
-        ROS_ERROR_STREAM("CModuleAction::action_done: goal on server " << this->name << " rejected");
-        this->status=ACTION_REJECTED;
-      }
-      else if(state==actionlib::SimpleClientGoalState::PREEMPTED)
-      {
-        ROS_WARN_STREAM("CModuleAction::action_done: goal on server " << this->name << " preempted");
-        this->status=ACTION_PREEMPTED;
+        if(state==actionlib::SimpleClientGoalState::ABORTED)
+        {
+          ROS_ERROR_STREAM("CModuleAction::action_done: goal on server " << this->name << " aborted");
+          this->status=ACTION_ABORTED;
+        }
+        if(state==actionlib::SimpleClientGoalState::REJECTED)
+        {
+          ROS_ERROR_STREAM("CModuleAction::action_done: goal on server " << this->name << " rejected");
+          this->status=ACTION_REJECTED;
+        }
+        else if(state==actionlib::SimpleClientGoalState::PREEMPTED)
+        {
+          ROS_WARN_STREAM("CModuleAction::action_done: goal on server " << this->name << " preempted");
+          this->status=ACTION_PREEMPTED;
+        }
+        else if(state==actionlib::SimpleClientGoalState::SUCCEEDED)
+        {
+          ROS_INFO_STREAM("CModuleAction::action_done: goal on server " << this->name << " successfull");
+          this->status=ACTION_SUCCESS;
+        } 
       }
-      else if(state==actionlib::SimpleClientGoalState::SUCCEEDED)
-      {
-        ROS_INFO_STREAM("CModuleAction::action_done: goal on server " << this->name << " successfull");
-        this->status=ACTION_SUCCESS;
-      } 
       this->action_result_msg=*result;
       this->action_feedback_msg=Feedback();
       this->action_access.exit();
-- 
GitLab