FollowJointTrajectoryAction.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-fuerte-control/doc_stacks/2013-12-28_16-51-49.008021/control/control_msgs/msg/FollowJointTrajectoryAction.msg */
00002 #ifndef CONTROL_MSGS_MESSAGE_FOLLOWJOINTTRAJECTORYACTION_H
00003 #define CONTROL_MSGS_MESSAGE_FOLLOWJOINTTRAJECTORYACTION_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 "control_msgs/FollowJointTrajectoryActionGoal.h"
00018 #include "control_msgs/FollowJointTrajectoryActionResult.h"
00019 #include "control_msgs/FollowJointTrajectoryActionFeedback.h"
00020 
00021 namespace control_msgs
00022 {
00023 template <class ContainerAllocator>
00024 struct FollowJointTrajectoryAction_ {
00025   typedef FollowJointTrajectoryAction_<ContainerAllocator> Type;
00026 
00027   FollowJointTrajectoryAction_()
00028   : action_goal()
00029   , action_result()
00030   , action_feedback()
00031   {
00032   }
00033 
00034   FollowJointTrajectoryAction_(const ContainerAllocator& _alloc)
00035   : action_goal(_alloc)
00036   , action_result(_alloc)
00037   , action_feedback(_alloc)
00038   {
00039   }
00040 
00041   typedef  ::control_msgs::FollowJointTrajectoryActionGoal_<ContainerAllocator>  _action_goal_type;
00042    ::control_msgs::FollowJointTrajectoryActionGoal_<ContainerAllocator>  action_goal;
00043 
00044   typedef  ::control_msgs::FollowJointTrajectoryActionResult_<ContainerAllocator>  _action_result_type;
00045    ::control_msgs::FollowJointTrajectoryActionResult_<ContainerAllocator>  action_result;
00046 
00047   typedef  ::control_msgs::FollowJointTrajectoryActionFeedback_<ContainerAllocator>  _action_feedback_type;
00048    ::control_msgs::FollowJointTrajectoryActionFeedback_<ContainerAllocator>  action_feedback;
00049 
00050 
00051   typedef boost::shared_ptr< ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator> > Ptr;
00052   typedef boost::shared_ptr< ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator>  const> ConstPtr;
00053   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00054 }; // struct FollowJointTrajectoryAction
00055 typedef  ::control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > FollowJointTrajectoryAction;
00056 
00057 typedef boost::shared_ptr< ::control_msgs::FollowJointTrajectoryAction> FollowJointTrajectoryActionPtr;
00058 typedef boost::shared_ptr< ::control_msgs::FollowJointTrajectoryAction const> FollowJointTrajectoryActionConstPtr;
00059 
00060 
00061 template<typename ContainerAllocator>
00062 std::ostream& operator<<(std::ostream& s, const  ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator> & v)
00063 {
00064   ros::message_operations::Printer< ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator> >::stream(s, "", v);
00065   return s;}
00066 
00067 } // namespace control_msgs
00068 
00069 namespace ros
00070 {
00071 namespace message_traits
00072 {
00073 template<class ContainerAllocator> struct IsMessage< ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator> > : public TrueType {};
00074 template<class ContainerAllocator> struct IsMessage< ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator>  const> : public TrueType {};
00075 template<class ContainerAllocator>
00076 struct MD5Sum< ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator> > {
00077   static const char* value() 
00078   {
00079     return "a1222b69ec4dcd1675e990ca2f8fe9be";
00080   }
00081 
00082   static const char* value(const  ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator> &) { return value(); } 
00083   static const uint64_t static_value1 = 0xa1222b69ec4dcd16ULL;
00084   static const uint64_t static_value2 = 0x75e990ca2f8fe9beULL;
00085 };
00086 
00087 template<class ContainerAllocator>
00088 struct DataType< ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator> > {
00089   static const char* value() 
00090   {
00091     return "control_msgs/FollowJointTrajectoryAction";
00092   }
00093 
00094   static const char* value(const  ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator> &) { return value(); } 
00095 };
00096 
00097 template<class ContainerAllocator>
00098 struct Definition< ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator> > {
00099   static const char* value() 
00100   {
00101     return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00102 \n\
00103 FollowJointTrajectoryActionGoal action_goal\n\
00104 FollowJointTrajectoryActionResult action_result\n\
00105 FollowJointTrajectoryActionFeedback action_feedback\n\
00106 \n\
00107 ================================================================================\n\
00108 MSG: control_msgs/FollowJointTrajectoryActionGoal\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 FollowJointTrajectoryGoal 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: control_msgs/FollowJointTrajectoryGoal\n\
00148 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00149 # The joint trajectory to follow\n\
00150 trajectory_msgs/JointTrajectory trajectory\n\
00151 \n\
00152 # Tolerances for the trajectory.  If the measured joint values fall\n\
00153 # outside the tolerances the trajectory goal is aborted.  Any\n\
00154 # tolerances that are not specified (by being omitted or set to 0) are\n\
00155 # set to the defaults for the action server (often taken from the\n\
00156 # parameter server).\n\
00157 \n\
00158 # Tolerances applied to the joints as the trajectory is executed.  If\n\
00159 # violated, the goal aborts with error_code set to\n\
00160 # PATH_TOLERANCE_VIOLATED.\n\
00161 JointTolerance[] path_tolerance\n\
00162 \n\
00163 # To report success, the joints must be within goal_tolerance of the\n\
00164 # final trajectory value.  The goal must be achieved by time the\n\
00165 # trajectory ends plus goal_time_tolerance.  (goal_time_tolerance\n\
00166 # allows some leeway in time, so that the trajectory goal can still\n\
00167 # succeed even if the joints reach the goal some time after the\n\
00168 # precise end time of the trajectory).\n\
00169 #\n\
00170 # If the joints are not within goal_tolerance after \"trajectory finish\n\
00171 # time\" + goal_time_tolerance, the goal aborts with error_code set to\n\
00172 # GOAL_TOLERANCE_VIOLATED\n\
00173 JointTolerance[] goal_tolerance\n\
00174 duration goal_time_tolerance\n\
00175 \n\
00176 \n\
00177 ================================================================================\n\
00178 MSG: trajectory_msgs/JointTrajectory\n\
00179 Header header\n\
00180 string[] joint_names\n\
00181 JointTrajectoryPoint[] points\n\
00182 ================================================================================\n\
00183 MSG: trajectory_msgs/JointTrajectoryPoint\n\
00184 float64[] positions\n\
00185 float64[] velocities\n\
00186 float64[] accelerations\n\
00187 duration time_from_start\n\
00188 ================================================================================\n\
00189 MSG: control_msgs/JointTolerance\n\
00190 # The tolerances specify the amount the position, velocity, and\n\
00191 # accelerations can vary from the setpoints.  For example, in the case\n\
00192 # of trajectory control, when the actual position varies beyond\n\
00193 # (desired position + position tolerance), the trajectory goal may\n\
00194 # abort.\n\
00195 # \n\
00196 # There are two special values for tolerances:\n\
00197 #  * 0 - The tolerance is unspecified and will remain at whatever the default is\n\
00198 #  * -1 - The tolerance is \"erased\".  If there was a default, the joint will be\n\
00199 #         allowed to move without restriction.\n\
00200 \n\
00201 string name\n\
00202 float64 position  # in radians or meters (for a revolute or prismatic joint, respectively)\n\
00203 float64 velocity  # in rad/sec or m/sec\n\
00204 float64 acceleration  # in rad/sec^2 or m/sec^2\n\
00205 \n\
00206 ================================================================================\n\
00207 MSG: control_msgs/FollowJointTrajectoryActionResult\n\
00208 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00209 \n\
00210 Header header\n\
00211 actionlib_msgs/GoalStatus status\n\
00212 FollowJointTrajectoryResult result\n\
00213 \n\
00214 ================================================================================\n\
00215 MSG: actionlib_msgs/GoalStatus\n\
00216 GoalID goal_id\n\
00217 uint8 status\n\
00218 uint8 PENDING         = 0   # The goal has yet to be processed by the action server\n\
00219 uint8 ACTIVE          = 1   # The goal is currently being processed by the action server\n\
00220 uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing\n\
00221                             #   and has since completed its execution (Terminal State)\n\
00222 uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)\n\
00223 uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due\n\
00224                             #    to some failure (Terminal State)\n\
00225 uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,\n\
00226                             #    because the goal was unattainable or invalid (Terminal State)\n\
00227 uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing\n\
00228                             #    and has not yet completed execution\n\
00229 uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,\n\
00230                             #    but the action server has not yet confirmed that the goal is canceled\n\
00231 uint8 RECALLED        = 8   # The goal received a cancel request before it started executing\n\
00232                             #    and was successfully cancelled (Terminal State)\n\
00233 uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be\n\
00234                             #    sent over the wire by an action server\n\
00235 \n\
00236 #Allow for the user to associate a string with GoalStatus for debugging\n\
00237 string text\n\
00238 \n\
00239 \n\
00240 ================================================================================\n\
00241 MSG: control_msgs/FollowJointTrajectoryResult\n\
00242 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00243 int32 error_code\n\
00244 int32 SUCCESSFUL = 0\n\
00245 int32 INVALID_GOAL = -1\n\
00246 int32 INVALID_JOINTS = -2\n\
00247 int32 OLD_HEADER_TIMESTAMP = -3\n\
00248 int32 PATH_TOLERANCE_VIOLATED = -4\n\
00249 int32 GOAL_TOLERANCE_VIOLATED = -5\n\
00250 \n\
00251 \n\
00252 ================================================================================\n\
00253 MSG: control_msgs/FollowJointTrajectoryActionFeedback\n\
00254 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00255 \n\
00256 Header header\n\
00257 actionlib_msgs/GoalStatus status\n\
00258 FollowJointTrajectoryFeedback feedback\n\
00259 \n\
00260 ================================================================================\n\
00261 MSG: control_msgs/FollowJointTrajectoryFeedback\n\
00262 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00263 Header header\n\
00264 string[] joint_names\n\
00265 trajectory_msgs/JointTrajectoryPoint desired\n\
00266 trajectory_msgs/JointTrajectoryPoint actual\n\
00267 trajectory_msgs/JointTrajectoryPoint error\n\
00268 \n\
00269 \n\
00270 ";
00271   }
00272 
00273   static const char* value(const  ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator> &) { return value(); } 
00274 };
00275 
00276 } // namespace message_traits
00277 } // namespace ros
00278 
00279 namespace ros
00280 {
00281 namespace serialization
00282 {
00283 
00284 template<class ContainerAllocator> struct Serializer< ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator> >
00285 {
00286   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00287   {
00288     stream.next(m.action_goal);
00289     stream.next(m.action_result);
00290     stream.next(m.action_feedback);
00291   }
00292 
00293   ROS_DECLARE_ALLINONE_SERIALIZER;
00294 }; // struct FollowJointTrajectoryAction_
00295 } // namespace serialization
00296 } // namespace ros
00297 
00298 namespace ros
00299 {
00300 namespace message_operations
00301 {
00302 
00303 template<class ContainerAllocator>
00304 struct Printer< ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator> >
00305 {
00306   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::control_msgs::FollowJointTrajectoryAction_<ContainerAllocator> & v) 
00307   {
00308     s << indent << "action_goal: ";
00309 s << std::endl;
00310     Printer< ::control_msgs::FollowJointTrajectoryActionGoal_<ContainerAllocator> >::stream(s, indent + "  ", v.action_goal);
00311     s << indent << "action_result: ";
00312 s << std::endl;
00313     Printer< ::control_msgs::FollowJointTrajectoryActionResult_<ContainerAllocator> >::stream(s, indent + "  ", v.action_result);
00314     s << indent << "action_feedback: ";
00315 s << std::endl;
00316     Printer< ::control_msgs::FollowJointTrajectoryActionFeedback_<ContainerAllocator> >::stream(s, indent + "  ", v.action_feedback);
00317   }
00318 };
00319 
00320 
00321 } // namespace message_operations
00322 } // namespace ros
00323 
00324 #endif // CONTROL_MSGS_MESSAGE_FOLLOWJOINTTRAJECTORYACTION_H
00325 


control_msgs
Author(s): Stuart Glaser
autogenerated on Sat Dec 28 2013 16:52:54