From 3322344f89479410d8a8092505bc512fac689db5 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Sergi=20Hern=C3=A0ndez=20Juan?= <shernand@iri.upc.edu>
Date: Wed, 6 Jul 2011 18:31:40 +0000
Subject: [PATCH] Modified the iri action server to use the isActive() function
 in the execute callback function.

---
 include/iri_action_server/iri_action_server.h | 13 +++++++------
 1 file changed, 7 insertions(+), 6 deletions(-)

diff --git a/include/iri_action_server/iri_action_server.h b/include/iri_action_server/iri_action_server.h
index ed1c0b9..50ceced 100755
--- a/include/iri_action_server/iri_action_server.h
+++ b/include/iri_action_server/iri_action_server.h
@@ -73,7 +73,7 @@ class IriActionServer
     typedef boost::shared_ptr<Feedback> FeedbackPtr;
     
   private:
-    
+  
    /**
     * \brief Start Callback object
     *
@@ -307,6 +307,7 @@ IriActionServer<ActionSpec>::IriActionServer(ros::NodeHandle & nh, const std::st
 template <class ActionSpec>
 IriActionServer<ActionSpec>::~IriActionServer(void)
 {
+
   ROS_DEBUG("IriActionServer::Destructor");
 }
 
@@ -359,10 +360,10 @@ void IriActionServer<ActionSpec>::executeCallback(const GoalConstPtr& goal)
     start_action_callback_(goal);
 
     // boolean to control action status
-    bool is_active = true;
+    //bool is_active = true;
 
     // while action is active
-    while( is_active )
+    while(this->as_.isActive() )
     {
       ROS_DEBUG("IriActionServer::executeCallback::Active!");
       
@@ -371,17 +372,17 @@ void IriActionServer<ActionSpec>::executeCallback(const GoalConstPtr& goal)
       if( as_.isPreemptRequested() || !ros::ok() )
       {
         ROS_DEBUG("IriActionServer::executeCallback::PREEMPTED!");
-        is_active = false;
+        //is_active = false;
 
         // stop action
         stop_action_callback_();
-        as_.setPreempted();
+        as_.setAborted();
       }
       // check if action has finished
       else if( is_finished_callback_() )
       {
         ROS_DEBUG("IriActionServer::executeCallback::FINISH!");
-        is_active = false;
+        //is_active = false;
 
         // get action result
         ResultPtr result(new Result);
-- 
GitLab