00001
00002 #ifndef ACTIONLIB_MSGS_MESSAGE_GOALSTATUSARRAY_H
00003 #define ACTIONLIB_MSGS_MESSAGE_GOALSTATUSARRAY_H
00004 #include <string>
00005 #include <vector>
00006 #include <map>
00007 #include <ostream>
00008 #include "ros/serialization.h"
00009 #include "ros/builtin_message_traits.h"
00010 #include "ros/message_operations.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/macros.h"
00014
00015 #include "ros/assert.h"
00016
00017 #include "std_msgs/Header.h"
00018 #include "actionlib_msgs/GoalStatus.h"
00019
00020 namespace actionlib_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct GoalStatusArray_ {
00024 typedef GoalStatusArray_<ContainerAllocator> Type;
00025
00026 GoalStatusArray_()
00027 : header()
00028 , status_list()
00029 {
00030 }
00031
00032 GoalStatusArray_(const ContainerAllocator& _alloc)
00033 : header(_alloc)
00034 , status_list(_alloc)
00035 {
00036 }
00037
00038 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00039 ::std_msgs::Header_<ContainerAllocator> header;
00040
00041 typedef std::vector< ::actionlib_msgs::GoalStatus_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::actionlib_msgs::GoalStatus_<ContainerAllocator> >::other > _status_list_type;
00042 std::vector< ::actionlib_msgs::GoalStatus_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::actionlib_msgs::GoalStatus_<ContainerAllocator> >::other > status_list;
00043
00044
00045 ROS_DEPRECATED uint32_t get_status_list_size() const { return (uint32_t)status_list.size(); }
00046 ROS_DEPRECATED void set_status_list_size(uint32_t size) { status_list.resize((size_t)size); }
00047 ROS_DEPRECATED void get_status_list_vec(std::vector< ::actionlib_msgs::GoalStatus_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::actionlib_msgs::GoalStatus_<ContainerAllocator> >::other > & vec) const { vec = this->status_list; }
00048 ROS_DEPRECATED void set_status_list_vec(const std::vector< ::actionlib_msgs::GoalStatus_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::actionlib_msgs::GoalStatus_<ContainerAllocator> >::other > & vec) { this->status_list = vec; }
00049 private:
00050 static const char* __s_getDataType_() { return "actionlib_msgs/GoalStatusArray"; }
00051 public:
00052 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00053
00054 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00055
00056 private:
00057 static const char* __s_getMD5Sum_() { return "8b2b82f13216d0a8ea88bd3af735e619"; }
00058 public:
00059 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00060
00061 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00062
00063 private:
00064 static const char* __s_getMessageDefinition_() { return "# Stores the statuses for goals that are currently being tracked\n\
00065 # by an action server\n\
00066 Header header\n\
00067 GoalStatus[] status_list\n\
00068 \n\
00069 \n\
00070 ================================================================================\n\
00071 MSG: std_msgs/Header\n\
00072 # Standard metadata for higher-level stamped data types.\n\
00073 # This is generally used to communicate timestamped data \n\
00074 # in a particular coordinate frame.\n\
00075 # \n\
00076 # sequence ID: consecutively increasing ID \n\
00077 uint32 seq\n\
00078 #Two-integer timestamp that is expressed as:\n\
00079 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00080 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00081 # time-handling sugar is provided by the client library\n\
00082 time stamp\n\
00083 #Frame this data is associated with\n\
00084 # 0: no frame\n\
00085 # 1: global frame\n\
00086 string frame_id\n\
00087 \n\
00088 ================================================================================\n\
00089 MSG: actionlib_msgs/GoalStatus\n\
00090 GoalID goal_id\n\
00091 uint8 status\n\
00092 uint8 PENDING = 0 # The goal has yet to be processed by the action server\n\
00093 uint8 ACTIVE = 1 # The goal is currently being processed by the action server\n\
00094 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing\n\
00095 # and has since completed its execution (Terminal State)\n\
00096 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)\n\
00097 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due\n\
00098 # to some failure (Terminal State)\n\
00099 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,\n\
00100 # because the goal was unattainable or invalid (Terminal State)\n\
00101 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing\n\
00102 # and has not yet completed execution\n\
00103 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,\n\
00104 # but the action server has not yet confirmed that the goal is canceled\n\
00105 uint8 RECALLED = 8 # The goal received a cancel request before it started executing\n\
00106 # and was successfully cancelled (Terminal State)\n\
00107 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be\n\
00108 # sent over the wire by an action server\n\
00109 \n\
00110 #Allow for the user to associate a string with GoalStatus for debugging\n\
00111 string text\n\
00112 \n\
00113 \n\
00114 ================================================================================\n\
00115 MSG: actionlib_msgs/GoalID\n\
00116 # The stamp should store the time at which this goal was requested.\n\
00117 # It is used by an action server when it tries to preempt all\n\
00118 # goals that were requested before a certain time\n\
00119 time stamp\n\
00120 \n\
00121 # The id provides a way to associate feedback and\n\
00122 # result message with specific goal requests. The id\n\
00123 # specified must be unique.\n\
00124 string id\n\
00125 \n\
00126 \n\
00127 "; }
00128 public:
00129 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00130
00131 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00132
00133 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00134 {
00135 ros::serialization::OStream stream(write_ptr, 1000000000);
00136 ros::serialization::serialize(stream, header);
00137 ros::serialization::serialize(stream, status_list);
00138 return stream.getData();
00139 }
00140
00141 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00142 {
00143 ros::serialization::IStream stream(read_ptr, 1000000000);
00144 ros::serialization::deserialize(stream, header);
00145 ros::serialization::deserialize(stream, status_list);
00146 return stream.getData();
00147 }
00148
00149 ROS_DEPRECATED virtual uint32_t serializationLength() const
00150 {
00151 uint32_t size = 0;
00152 size += ros::serialization::serializationLength(header);
00153 size += ros::serialization::serializationLength(status_list);
00154 return size;
00155 }
00156
00157 typedef boost::shared_ptr< ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> > Ptr;
00158 typedef boost::shared_ptr< ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> const> ConstPtr;
00159 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00160 };
00161 typedef ::actionlib_msgs::GoalStatusArray_<std::allocator<void> > GoalStatusArray;
00162
00163 typedef boost::shared_ptr< ::actionlib_msgs::GoalStatusArray> GoalStatusArrayPtr;
00164 typedef boost::shared_ptr< ::actionlib_msgs::GoalStatusArray const> GoalStatusArrayConstPtr;
00165
00166
00167 template<typename ContainerAllocator>
00168 std::ostream& operator<<(std::ostream& s, const ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> & v)
00169 {
00170 ros::message_operations::Printer< ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> >::stream(s, "", v);
00171 return s;}
00172
00173 }
00174
00175 namespace ros
00176 {
00177 namespace message_traits
00178 {
00179 template<class ContainerAllocator> struct IsMessage< ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> > : public TrueType {};
00180 template<class ContainerAllocator> struct IsMessage< ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> const> : public TrueType {};
00181 template<class ContainerAllocator>
00182 struct MD5Sum< ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> > {
00183 static const char* value()
00184 {
00185 return "8b2b82f13216d0a8ea88bd3af735e619";
00186 }
00187
00188 static const char* value(const ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> &) { return value(); }
00189 static const uint64_t static_value1 = 0x8b2b82f13216d0a8ULL;
00190 static const uint64_t static_value2 = 0xea88bd3af735e619ULL;
00191 };
00192
00193 template<class ContainerAllocator>
00194 struct DataType< ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> > {
00195 static const char* value()
00196 {
00197 return "actionlib_msgs/GoalStatusArray";
00198 }
00199
00200 static const char* value(const ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> &) { return value(); }
00201 };
00202
00203 template<class ContainerAllocator>
00204 struct Definition< ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> > {
00205 static const char* value()
00206 {
00207 return "# Stores the statuses for goals that are currently being tracked\n\
00208 # by an action server\n\
00209 Header header\n\
00210 GoalStatus[] status_list\n\
00211 \n\
00212 \n\
00213 ================================================================================\n\
00214 MSG: std_msgs/Header\n\
00215 # Standard metadata for higher-level stamped data types.\n\
00216 # This is generally used to communicate timestamped data \n\
00217 # in a particular coordinate frame.\n\
00218 # \n\
00219 # sequence ID: consecutively increasing ID \n\
00220 uint32 seq\n\
00221 #Two-integer timestamp that is expressed as:\n\
00222 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00223 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00224 # time-handling sugar is provided by the client library\n\
00225 time stamp\n\
00226 #Frame this data is associated with\n\
00227 # 0: no frame\n\
00228 # 1: global frame\n\
00229 string frame_id\n\
00230 \n\
00231 ================================================================================\n\
00232 MSG: actionlib_msgs/GoalStatus\n\
00233 GoalID goal_id\n\
00234 uint8 status\n\
00235 uint8 PENDING = 0 # The goal has yet to be processed by the action server\n\
00236 uint8 ACTIVE = 1 # The goal is currently being processed by the action server\n\
00237 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing\n\
00238 # and has since completed its execution (Terminal State)\n\
00239 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)\n\
00240 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due\n\
00241 # to some failure (Terminal State)\n\
00242 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,\n\
00243 # because the goal was unattainable or invalid (Terminal State)\n\
00244 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing\n\
00245 # and has not yet completed execution\n\
00246 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,\n\
00247 # but the action server has not yet confirmed that the goal is canceled\n\
00248 uint8 RECALLED = 8 # The goal received a cancel request before it started executing\n\
00249 # and was successfully cancelled (Terminal State)\n\
00250 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be\n\
00251 # sent over the wire by an action server\n\
00252 \n\
00253 #Allow for the user to associate a string with GoalStatus for debugging\n\
00254 string text\n\
00255 \n\
00256 \n\
00257 ================================================================================\n\
00258 MSG: actionlib_msgs/GoalID\n\
00259 # The stamp should store the time at which this goal was requested.\n\
00260 # It is used by an action server when it tries to preempt all\n\
00261 # goals that were requested before a certain time\n\
00262 time stamp\n\
00263 \n\
00264 # The id provides a way to associate feedback and\n\
00265 # result message with specific goal requests. The id\n\
00266 # specified must be unique.\n\
00267 string id\n\
00268 \n\
00269 \n\
00270 ";
00271 }
00272
00273 static const char* value(const ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> &) { return value(); }
00274 };
00275
00276 template<class ContainerAllocator> struct HasHeader< ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> > : public TrueType {};
00277 template<class ContainerAllocator> struct HasHeader< const ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> > : public TrueType {};
00278 }
00279 }
00280
00281 namespace ros
00282 {
00283 namespace serialization
00284 {
00285
00286 template<class ContainerAllocator> struct Serializer< ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> >
00287 {
00288 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00289 {
00290 stream.next(m.header);
00291 stream.next(m.status_list);
00292 }
00293
00294 ROS_DECLARE_ALLINONE_SERIALIZER;
00295 };
00296 }
00297 }
00298
00299 namespace ros
00300 {
00301 namespace message_operations
00302 {
00303
00304 template<class ContainerAllocator>
00305 struct Printer< ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> >
00306 {
00307 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::actionlib_msgs::GoalStatusArray_<ContainerAllocator> & v)
00308 {
00309 s << indent << "header: ";
00310 s << std::endl;
00311 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00312 s << indent << "status_list[]" << std::endl;
00313 for (size_t i = 0; i < v.status_list.size(); ++i)
00314 {
00315 s << indent << " status_list[" << i << "]: ";
00316 s << std::endl;
00317 s << indent;
00318 Printer< ::actionlib_msgs::GoalStatus_<ContainerAllocator> >::stream(s, indent + " ", v.status_list[i]);
00319 }
00320 }
00321 };
00322
00323
00324 }
00325 }
00326
00327 #endif // ACTIONLIB_MSGS_MESSAGE_GOALSTATUSARRAY_H
00328