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