FollowJointTrajectoryGoal.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/FollowJointTrajectoryGoal.msg */
00002 #ifndef CONTROL_MSGS_MESSAGE_FOLLOWJOINTTRAJECTORYGOAL_H
00003 #define CONTROL_MSGS_MESSAGE_FOLLOWJOINTTRAJECTORYGOAL_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 "trajectory_msgs/JointTrajectory.h"
00018 #include "control_msgs/JointTolerance.h"
00019 #include "control_msgs/JointTolerance.h"
00020 
00021 namespace control_msgs
00022 {
00023 template <class ContainerAllocator>
00024 struct FollowJointTrajectoryGoal_ {
00025   typedef FollowJointTrajectoryGoal_<ContainerAllocator> Type;
00026 
00027   FollowJointTrajectoryGoal_()
00028   : trajectory()
00029   , path_tolerance()
00030   , goal_tolerance()
00031   , goal_time_tolerance()
00032   {
00033   }
00034 
00035   FollowJointTrajectoryGoal_(const ContainerAllocator& _alloc)
00036   : trajectory(_alloc)
00037   , path_tolerance(_alloc)
00038   , goal_tolerance(_alloc)
00039   , goal_time_tolerance()
00040   {
00041   }
00042 
00043   typedef  ::trajectory_msgs::JointTrajectory_<ContainerAllocator>  _trajectory_type;
00044    ::trajectory_msgs::JointTrajectory_<ContainerAllocator>  trajectory;
00045 
00046   typedef std::vector< ::control_msgs::JointTolerance_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::control_msgs::JointTolerance_<ContainerAllocator> >::other >  _path_tolerance_type;
00047   std::vector< ::control_msgs::JointTolerance_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::control_msgs::JointTolerance_<ContainerAllocator> >::other >  path_tolerance;
00048 
00049   typedef std::vector< ::control_msgs::JointTolerance_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::control_msgs::JointTolerance_<ContainerAllocator> >::other >  _goal_tolerance_type;
00050   std::vector< ::control_msgs::JointTolerance_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::control_msgs::JointTolerance_<ContainerAllocator> >::other >  goal_tolerance;
00051 
00052   typedef ros::Duration _goal_time_tolerance_type;
00053   ros::Duration goal_time_tolerance;
00054 
00055 
00056   typedef boost::shared_ptr< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> > Ptr;
00057   typedef boost::shared_ptr< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator>  const> ConstPtr;
00058   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00059 }; // struct FollowJointTrajectoryGoal
00060 typedef  ::control_msgs::FollowJointTrajectoryGoal_<std::allocator<void> > FollowJointTrajectoryGoal;
00061 
00062 typedef boost::shared_ptr< ::control_msgs::FollowJointTrajectoryGoal> FollowJointTrajectoryGoalPtr;
00063 typedef boost::shared_ptr< ::control_msgs::FollowJointTrajectoryGoal const> FollowJointTrajectoryGoalConstPtr;
00064 
00065 
00066 template<typename ContainerAllocator>
00067 std::ostream& operator<<(std::ostream& s, const  ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> & v)
00068 {
00069   ros::message_operations::Printer< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> >::stream(s, "", v);
00070   return s;}
00071 
00072 } // namespace control_msgs
00073 
00074 namespace ros
00075 {
00076 namespace message_traits
00077 {
00078 template<class ContainerAllocator> struct IsMessage< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> > : public TrueType {};
00079 template<class ContainerAllocator> struct IsMessage< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator>  const> : public TrueType {};
00080 template<class ContainerAllocator>
00081 struct MD5Sum< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> > {
00082   static const char* value() 
00083   {
00084     return "01f6d702507b59bae3fc1e7149e6210c";
00085   }
00086 
00087   static const char* value(const  ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> &) { return value(); } 
00088   static const uint64_t static_value1 = 0x01f6d702507b59baULL;
00089   static const uint64_t static_value2 = 0xe3fc1e7149e6210cULL;
00090 };
00091 
00092 template<class ContainerAllocator>
00093 struct DataType< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> > {
00094   static const char* value() 
00095   {
00096     return "control_msgs/FollowJointTrajectoryGoal";
00097   }
00098 
00099   static const char* value(const  ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> &) { return value(); } 
00100 };
00101 
00102 template<class ContainerAllocator>
00103 struct Definition< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> > {
00104   static const char* value() 
00105   {
00106     return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00107 # The joint trajectory to follow\n\
00108 trajectory_msgs/JointTrajectory trajectory\n\
00109 \n\
00110 # Tolerances for the trajectory.  If the measured joint values fall\n\
00111 # outside the tolerances the trajectory goal is aborted.  Any\n\
00112 # tolerances that are not specified (by being omitted or set to 0) are\n\
00113 # set to the defaults for the action server (often taken from the\n\
00114 # parameter server).\n\
00115 \n\
00116 # Tolerances applied to the joints as the trajectory is executed.  If\n\
00117 # violated, the goal aborts with error_code set to\n\
00118 # PATH_TOLERANCE_VIOLATED.\n\
00119 JointTolerance[] path_tolerance\n\
00120 \n\
00121 # To report success, the joints must be within goal_tolerance of the\n\
00122 # final trajectory value.  The goal must be achieved by time the\n\
00123 # trajectory ends plus goal_time_tolerance.  (goal_time_tolerance\n\
00124 # allows some leeway in time, so that the trajectory goal can still\n\
00125 # succeed even if the joints reach the goal some time after the\n\
00126 # precise end time of the trajectory).\n\
00127 #\n\
00128 # If the joints are not within goal_tolerance after \"trajectory finish\n\
00129 # time\" + goal_time_tolerance, the goal aborts with error_code set to\n\
00130 # GOAL_TOLERANCE_VIOLATED\n\
00131 JointTolerance[] goal_tolerance\n\
00132 duration goal_time_tolerance\n\
00133 \n\
00134 \n\
00135 ================================================================================\n\
00136 MSG: trajectory_msgs/JointTrajectory\n\
00137 Header header\n\
00138 string[] joint_names\n\
00139 JointTrajectoryPoint[] points\n\
00140 ================================================================================\n\
00141 MSG: std_msgs/Header\n\
00142 # Standard metadata for higher-level stamped data types.\n\
00143 # This is generally used to communicate timestamped data \n\
00144 # in a particular coordinate frame.\n\
00145 # \n\
00146 # sequence ID: consecutively increasing ID \n\
00147 uint32 seq\n\
00148 #Two-integer timestamp that is expressed as:\n\
00149 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00150 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00151 # time-handling sugar is provided by the client library\n\
00152 time stamp\n\
00153 #Frame this data is associated with\n\
00154 # 0: no frame\n\
00155 # 1: global frame\n\
00156 string frame_id\n\
00157 \n\
00158 ================================================================================\n\
00159 MSG: trajectory_msgs/JointTrajectoryPoint\n\
00160 float64[] positions\n\
00161 float64[] velocities\n\
00162 float64[] accelerations\n\
00163 duration time_from_start\n\
00164 ================================================================================\n\
00165 MSG: control_msgs/JointTolerance\n\
00166 # The tolerances specify the amount the position, velocity, and\n\
00167 # accelerations can vary from the setpoints.  For example, in the case\n\
00168 # of trajectory control, when the actual position varies beyond\n\
00169 # (desired position + position tolerance), the trajectory goal may\n\
00170 # abort.\n\
00171 # \n\
00172 # There are two special values for tolerances:\n\
00173 #  * 0 - The tolerance is unspecified and will remain at whatever the default is\n\
00174 #  * -1 - The tolerance is \"erased\".  If there was a default, the joint will be\n\
00175 #         allowed to move without restriction.\n\
00176 \n\
00177 string name\n\
00178 float64 position  # in radians or meters (for a revolute or prismatic joint, respectively)\n\
00179 float64 velocity  # in rad/sec or m/sec\n\
00180 float64 acceleration  # in rad/sec^2 or m/sec^2\n\
00181 \n\
00182 ";
00183   }
00184 
00185   static const char* value(const  ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> &) { return value(); } 
00186 };
00187 
00188 } // namespace message_traits
00189 } // namespace ros
00190 
00191 namespace ros
00192 {
00193 namespace serialization
00194 {
00195 
00196 template<class ContainerAllocator> struct Serializer< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> >
00197 {
00198   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00199   {
00200     stream.next(m.trajectory);
00201     stream.next(m.path_tolerance);
00202     stream.next(m.goal_tolerance);
00203     stream.next(m.goal_time_tolerance);
00204   }
00205 
00206   ROS_DECLARE_ALLINONE_SERIALIZER;
00207 }; // struct FollowJointTrajectoryGoal_
00208 } // namespace serialization
00209 } // namespace ros
00210 
00211 namespace ros
00212 {
00213 namespace message_operations
00214 {
00215 
00216 template<class ContainerAllocator>
00217 struct Printer< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> >
00218 {
00219   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> & v) 
00220   {
00221     s << indent << "trajectory: ";
00222 s << std::endl;
00223     Printer< ::trajectory_msgs::JointTrajectory_<ContainerAllocator> >::stream(s, indent + "  ", v.trajectory);
00224     s << indent << "path_tolerance[]" << std::endl;
00225     for (size_t i = 0; i < v.path_tolerance.size(); ++i)
00226     {
00227       s << indent << "  path_tolerance[" << i << "]: ";
00228       s << std::endl;
00229       s << indent;
00230       Printer< ::control_msgs::JointTolerance_<ContainerAllocator> >::stream(s, indent + "    ", v.path_tolerance[i]);
00231     }
00232     s << indent << "goal_tolerance[]" << std::endl;
00233     for (size_t i = 0; i < v.goal_tolerance.size(); ++i)
00234     {
00235       s << indent << "  goal_tolerance[" << i << "]: ";
00236       s << std::endl;
00237       s << indent;
00238       Printer< ::control_msgs::JointTolerance_<ContainerAllocator> >::stream(s, indent + "    ", v.goal_tolerance[i]);
00239     }
00240     s << indent << "goal_time_tolerance: ";
00241     Printer<ros::Duration>::stream(s, indent + "  ", v.goal_time_tolerance);
00242   }
00243 };
00244 
00245 
00246 } // namespace message_operations
00247 } // namespace ros
00248 
00249 #endif // CONTROL_MSGS_MESSAGE_FOLLOWJOINTTRAJECTORYGOAL_H
00250 


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