client_goal_status.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #ifndef ACTIONLIB__CLIENT_GOAL_STATUS_H_
00036 #define ACTIONLIB__CLIENT_GOAL_STATUS_H_
00037 
00038 #include <string>
00039 
00040 #include "actionlib/GoalStatus.h"
00041 #include "ros/console.h"
00042 
00043 namespace actionlib
00044 {
00045 
00051 class ClientGoalStatus
00052 {
00053 public:
00055   enum StateEnum
00056   {
00057     PENDING,    
00058     ACTIVE,     
00059     PREEMPTED,  
00060     SUCCEEDED,  
00061     ABORTED,    
00062     REJECTED,   
00063     LOST        
00064   };
00065 
00066   ClientGoalStatus(StateEnum state)
00067   {
00068     state_ = state;
00069   }
00070 
00077   ClientGoalStatus(const GoalStatus & goal_status)
00078   {
00079     fromGoalStatus(goal_status);
00080   }
00081 
00086   inline bool isDone() const
00087   {
00088     if (state_ == PENDING || state_ == ACTIVE) {
00089       return false;
00090     }
00091     return true;
00092   }
00093 
00097   inline const StateEnum & operator=(const StateEnum & state)
00098   {
00099     state_ = state;
00100     return state;
00101   }
00102 
00106   inline bool operator==(const ClientGoalStatus & rhs) const
00107   {
00108     return state_ == rhs.state_;
00109   }
00110 
00114   inline bool operator!=(const ClientGoalStatus & rhs) const
00115   {
00116     return !(state_ == rhs.state_);
00117   }
00118 
00125   void fromGoalStatus(const GoalStatus & goal_status)
00126   {
00127     switch (goal_status.status) {
00128       case GoalStatus::PREEMPTED:
00129         state_ = ClientGoalStatus::PREEMPTED; break;
00130       case GoalStatus::SUCCEEDED:
00131         state_ = ClientGoalStatus::SUCCEEDED; break;
00132       case GoalStatus::ABORTED:
00133         state_ = ClientGoalStatus::ABORTED; break;
00134       case GoalStatus::REJECTED:
00135         state_ = ClientGoalStatus::REJECTED; break;
00136       default:
00137         state_ = ClientGoalStatus::LOST;
00138         ROS_ERROR_NAMED("actionlib", "Cannot convert GoalStatus %u to ClientGoalState",
00139           goal_status.status); break;
00140     }
00141   }
00142 
00147   std::string toString() const
00148   {
00149     switch (state_) {
00150       case PENDING:
00151         return "PENDING";
00152       case ACTIVE:
00153         return "ACTIVE";
00154       case PREEMPTED:
00155         return "PREEMPTED";
00156       case SUCCEEDED:
00157         return "SUCCEEDED";
00158       case ABORTED:
00159         return "ABORTED";
00160       case REJECTED:
00161         return "REJECTED";
00162       case LOST:
00163         return "LOST";
00164       default:
00165         ROS_ERROR_NAMED("actionlib", "BUG: Unhandled ClientGoalStatus");
00166         break;
00167     }
00168     return "BUG-UNKNOWN";
00169   }
00170 
00171 private:
00172   StateEnum state_;
00173   ClientGoalStatus();  
00174 };
00175 
00176 }  // namespace actionlib
00177 
00178 #endif  // ACTIONLIB__CLIENT_GOAL_STATUS_H_


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Sat Feb 16 2019 03:21:28