Go to the documentation of this file.00001
00002 #ifndef MOVE_BASE_MSGS_MESSAGE_MOVEBASEACTION_H
00003 #define MOVE_BASE_MSGS_MESSAGE_MOVEBASEACTION_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 "move_base_msgs/MoveBaseActionGoal.h"
00018 #include "move_base_msgs/MoveBaseActionResult.h"
00019 #include "move_base_msgs/MoveBaseActionFeedback.h"
00020
00021 namespace move_base_msgs
00022 {
00023 template <class ContainerAllocator>
00024 struct MoveBaseAction_ {
00025 typedef MoveBaseAction_<ContainerAllocator> Type;
00026
00027 MoveBaseAction_()
00028 : action_goal()
00029 , action_result()
00030 , action_feedback()
00031 {
00032 }
00033
00034 MoveBaseAction_(const ContainerAllocator& _alloc)
00035 : action_goal(_alloc)
00036 , action_result(_alloc)
00037 , action_feedback(_alloc)
00038 {
00039 }
00040
00041 typedef ::move_base_msgs::MoveBaseActionGoal_<ContainerAllocator> _action_goal_type;
00042 ::move_base_msgs::MoveBaseActionGoal_<ContainerAllocator> action_goal;
00043
00044 typedef ::move_base_msgs::MoveBaseActionResult_<ContainerAllocator> _action_result_type;
00045 ::move_base_msgs::MoveBaseActionResult_<ContainerAllocator> action_result;
00046
00047 typedef ::move_base_msgs::MoveBaseActionFeedback_<ContainerAllocator> _action_feedback_type;
00048 ::move_base_msgs::MoveBaseActionFeedback_<ContainerAllocator> action_feedback;
00049
00050
00051 typedef boost::shared_ptr< ::move_base_msgs::MoveBaseAction_<ContainerAllocator> > Ptr;
00052 typedef boost::shared_ptr< ::move_base_msgs::MoveBaseAction_<ContainerAllocator> const> ConstPtr;
00053 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00054 };
00055 typedef ::move_base_msgs::MoveBaseAction_<std::allocator<void> > MoveBaseAction;
00056
00057 typedef boost::shared_ptr< ::move_base_msgs::MoveBaseAction> MoveBaseActionPtr;
00058 typedef boost::shared_ptr< ::move_base_msgs::MoveBaseAction const> MoveBaseActionConstPtr;
00059
00060
00061 template<typename ContainerAllocator>
00062 std::ostream& operator<<(std::ostream& s, const ::move_base_msgs::MoveBaseAction_<ContainerAllocator> & v)
00063 {
00064 ros::message_operations::Printer< ::move_base_msgs::MoveBaseAction_<ContainerAllocator> >::stream(s, "", v);
00065 return s;}
00066
00067 }
00068
00069 namespace ros
00070 {
00071 namespace message_traits
00072 {
00073 template<class ContainerAllocator> struct IsMessage< ::move_base_msgs::MoveBaseAction_<ContainerAllocator> > : public TrueType {};
00074 template<class ContainerAllocator> struct IsMessage< ::move_base_msgs::MoveBaseAction_<ContainerAllocator> const> : public TrueType {};
00075 template<class ContainerAllocator>
00076 struct MD5Sum< ::move_base_msgs::MoveBaseAction_<ContainerAllocator> > {
00077 static const char* value()
00078 {
00079 return "70b6aca7c7f7746d8d1609ad94c80bb8";
00080 }
00081
00082 static const char* value(const ::move_base_msgs::MoveBaseAction_<ContainerAllocator> &) { return value(); }
00083 static const uint64_t static_value1 = 0x70b6aca7c7f7746dULL;
00084 static const uint64_t static_value2 = 0x8d1609ad94c80bb8ULL;
00085 };
00086
00087 template<class ContainerAllocator>
00088 struct DataType< ::move_base_msgs::MoveBaseAction_<ContainerAllocator> > {
00089 static const char* value()
00090 {
00091 return "move_base_msgs/MoveBaseAction";
00092 }
00093
00094 static const char* value(const ::move_base_msgs::MoveBaseAction_<ContainerAllocator> &) { return value(); }
00095 };
00096
00097 template<class ContainerAllocator>
00098 struct Definition< ::move_base_msgs::MoveBaseAction_<ContainerAllocator> > {
00099 static const char* value()
00100 {
00101 return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00102 \n\
00103 MoveBaseActionGoal action_goal\n\
00104 MoveBaseActionResult action_result\n\
00105 MoveBaseActionFeedback action_feedback\n\
00106 \n\
00107 ================================================================================\n\
00108 MSG: move_base_msgs/MoveBaseActionGoal\n\
00109 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00110 \n\
00111 Header header\n\
00112 actionlib_msgs/GoalID goal_id\n\
00113 MoveBaseGoal goal\n\
00114 \n\
00115 ================================================================================\n\
00116 MSG: std_msgs/Header\n\
00117 # Standard metadata for higher-level stamped data types.\n\
00118 # This is generally used to communicate timestamped data \n\
00119 # in a particular coordinate frame.\n\
00120 # \n\
00121 # sequence ID: consecutively increasing ID \n\
00122 uint32 seq\n\
00123 #Two-integer timestamp that is expressed as:\n\
00124 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00125 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00126 # time-handling sugar is provided by the client library\n\
00127 time stamp\n\
00128 #Frame this data is associated with\n\
00129 # 0: no frame\n\
00130 # 1: global frame\n\
00131 string frame_id\n\
00132 \n\
00133 ================================================================================\n\
00134 MSG: actionlib_msgs/GoalID\n\
00135 # The stamp should store the time at which this goal was requested.\n\
00136 # It is used by an action server when it tries to preempt all\n\
00137 # goals that were requested before a certain time\n\
00138 time stamp\n\
00139 \n\
00140 # The id provides a way to associate feedback and\n\
00141 # result message with specific goal requests. The id\n\
00142 # specified must be unique.\n\
00143 string id\n\
00144 \n\
00145 \n\
00146 ================================================================================\n\
00147 MSG: move_base_msgs/MoveBaseGoal\n\
00148 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00149 geometry_msgs/PoseStamped target_pose\n\
00150 \n\
00151 ================================================================================\n\
00152 MSG: geometry_msgs/PoseStamped\n\
00153 # A Pose with reference coordinate frame and timestamp\n\
00154 Header header\n\
00155 Pose pose\n\
00156 \n\
00157 ================================================================================\n\
00158 MSG: geometry_msgs/Pose\n\
00159 # A representation of pose in free space, composed of postion and orientation. \n\
00160 Point position\n\
00161 Quaternion orientation\n\
00162 \n\
00163 ================================================================================\n\
00164 MSG: geometry_msgs/Point\n\
00165 # This contains the position of a point in free space\n\
00166 float64 x\n\
00167 float64 y\n\
00168 float64 z\n\
00169 \n\
00170 ================================================================================\n\
00171 MSG: geometry_msgs/Quaternion\n\
00172 # This represents an orientation in free space in quaternion form.\n\
00173 \n\
00174 float64 x\n\
00175 float64 y\n\
00176 float64 z\n\
00177 float64 w\n\
00178 \n\
00179 ================================================================================\n\
00180 MSG: move_base_msgs/MoveBaseActionResult\n\
00181 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00182 \n\
00183 Header header\n\
00184 actionlib_msgs/GoalStatus status\n\
00185 MoveBaseResult result\n\
00186 \n\
00187 ================================================================================\n\
00188 MSG: actionlib_msgs/GoalStatus\n\
00189 GoalID goal_id\n\
00190 uint8 status\n\
00191 uint8 PENDING = 0 # The goal has yet to be processed by the action server\n\
00192 uint8 ACTIVE = 1 # The goal is currently being processed by the action server\n\
00193 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing\n\
00194 # and has since completed its execution (Terminal State)\n\
00195 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)\n\
00196 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due\n\
00197 # to some failure (Terminal State)\n\
00198 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,\n\
00199 # because the goal was unattainable or invalid (Terminal State)\n\
00200 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing\n\
00201 # and has not yet completed execution\n\
00202 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,\n\
00203 # but the action server has not yet confirmed that the goal is canceled\n\
00204 uint8 RECALLED = 8 # The goal received a cancel request before it started executing\n\
00205 # and was successfully cancelled (Terminal State)\n\
00206 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be\n\
00207 # sent over the wire by an action server\n\
00208 \n\
00209 #Allow for the user to associate a string with GoalStatus for debugging\n\
00210 string text\n\
00211 \n\
00212 \n\
00213 ================================================================================\n\
00214 MSG: move_base_msgs/MoveBaseResult\n\
00215 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00216 \n\
00217 ================================================================================\n\
00218 MSG: move_base_msgs/MoveBaseActionFeedback\n\
00219 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00220 \n\
00221 Header header\n\
00222 actionlib_msgs/GoalStatus status\n\
00223 MoveBaseFeedback feedback\n\
00224 \n\
00225 ================================================================================\n\
00226 MSG: move_base_msgs/MoveBaseFeedback\n\
00227 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00228 geometry_msgs/PoseStamped base_position\n\
00229 \n\
00230 \n\
00231 ";
00232 }
00233
00234 static const char* value(const ::move_base_msgs::MoveBaseAction_<ContainerAllocator> &) { return value(); }
00235 };
00236
00237 }
00238 }
00239
00240 namespace ros
00241 {
00242 namespace serialization
00243 {
00244
00245 template<class ContainerAllocator> struct Serializer< ::move_base_msgs::MoveBaseAction_<ContainerAllocator> >
00246 {
00247 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00248 {
00249 stream.next(m.action_goal);
00250 stream.next(m.action_result);
00251 stream.next(m.action_feedback);
00252 }
00253
00254 ROS_DECLARE_ALLINONE_SERIALIZER;
00255 };
00256 }
00257 }
00258
00259 namespace ros
00260 {
00261 namespace message_operations
00262 {
00263
00264 template<class ContainerAllocator>
00265 struct Printer< ::move_base_msgs::MoveBaseAction_<ContainerAllocator> >
00266 {
00267 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::move_base_msgs::MoveBaseAction_<ContainerAllocator> & v)
00268 {
00269 s << indent << "action_goal: ";
00270 s << std::endl;
00271 Printer< ::move_base_msgs::MoveBaseActionGoal_<ContainerAllocator> >::stream(s, indent + " ", v.action_goal);
00272 s << indent << "action_result: ";
00273 s << std::endl;
00274 Printer< ::move_base_msgs::MoveBaseActionResult_<ContainerAllocator> >::stream(s, indent + " ", v.action_result);
00275 s << indent << "action_feedback: ";
00276 s << std::endl;
00277 Printer< ::move_base_msgs::MoveBaseActionFeedback_<ContainerAllocator> >::stream(s, indent + " ", v.action_feedback);
00278 }
00279 };
00280
00281
00282 }
00283 }
00284
00285 #endif // MOVE_BASE_MSGS_MESSAGE_MOVEBASEACTION_H
00286