00001
00002 #ifndef CONTROL_MSGS_MESSAGE_FOLLOWJOINTTRAJECTORYGOAL_H
00003 #define CONTROL_MSGS_MESSAGE_FOLLOWJOINTTRAJECTORYGOAL_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "trajectory_msgs/JointTrajectory.h"
00014 #include "control_msgs/JointTolerance.h"
00015 #include "control_msgs/JointTolerance.h"
00016
00017 namespace control_msgs
00018 {
00019 template <class ContainerAllocator>
00020 struct FollowJointTrajectoryGoal_ : public ros::Message
00021 {
00022 typedef FollowJointTrajectoryGoal_<ContainerAllocator> Type;
00023
00024 FollowJointTrajectoryGoal_()
00025 : trajectory()
00026 , path_tolerance()
00027 , goal_tolerance()
00028 , goal_time_tolerance()
00029 {
00030 }
00031
00032 FollowJointTrajectoryGoal_(const ContainerAllocator& _alloc)
00033 : trajectory(_alloc)
00034 , path_tolerance(_alloc)
00035 , goal_tolerance(_alloc)
00036 , goal_time_tolerance()
00037 {
00038 }
00039
00040 typedef ::trajectory_msgs::JointTrajectory_<ContainerAllocator> _trajectory_type;
00041 ::trajectory_msgs::JointTrajectory_<ContainerAllocator> trajectory;
00042
00043 typedef std::vector< ::control_msgs::JointTolerance_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::control_msgs::JointTolerance_<ContainerAllocator> >::other > _path_tolerance_type;
00044 std::vector< ::control_msgs::JointTolerance_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::control_msgs::JointTolerance_<ContainerAllocator> >::other > path_tolerance;
00045
00046 typedef std::vector< ::control_msgs::JointTolerance_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::control_msgs::JointTolerance_<ContainerAllocator> >::other > _goal_tolerance_type;
00047 std::vector< ::control_msgs::JointTolerance_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::control_msgs::JointTolerance_<ContainerAllocator> >::other > goal_tolerance;
00048
00049 typedef ros::Duration _goal_time_tolerance_type;
00050 ros::Duration goal_time_tolerance;
00051
00052
00053 ROS_DEPRECATED uint32_t get_path_tolerance_size() const { return (uint32_t)path_tolerance.size(); }
00054 ROS_DEPRECATED void set_path_tolerance_size(uint32_t size) { path_tolerance.resize((size_t)size); }
00055 ROS_DEPRECATED void get_path_tolerance_vec(std::vector< ::control_msgs::JointTolerance_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::control_msgs::JointTolerance_<ContainerAllocator> >::other > & vec) const { vec = this->path_tolerance; }
00056 ROS_DEPRECATED void set_path_tolerance_vec(const std::vector< ::control_msgs::JointTolerance_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::control_msgs::JointTolerance_<ContainerAllocator> >::other > & vec) { this->path_tolerance = vec; }
00057 ROS_DEPRECATED uint32_t get_goal_tolerance_size() const { return (uint32_t)goal_tolerance.size(); }
00058 ROS_DEPRECATED void set_goal_tolerance_size(uint32_t size) { goal_tolerance.resize((size_t)size); }
00059 ROS_DEPRECATED void get_goal_tolerance_vec(std::vector< ::control_msgs::JointTolerance_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::control_msgs::JointTolerance_<ContainerAllocator> >::other > & vec) const { vec = this->goal_tolerance; }
00060 ROS_DEPRECATED void set_goal_tolerance_vec(const std::vector< ::control_msgs::JointTolerance_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::control_msgs::JointTolerance_<ContainerAllocator> >::other > & vec) { this->goal_tolerance = vec; }
00061 private:
00062 static const char* __s_getDataType_() { return "control_msgs/FollowJointTrajectoryGoal"; }
00063 public:
00064 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00065
00066 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00067
00068 private:
00069 static const char* __s_getMD5Sum_() { return "01f6d702507b59bae3fc1e7149e6210c"; }
00070 public:
00071 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00072
00073 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00074
00075 private:
00076 static const char* __s_getMessageDefinition_() { return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00077 # The joint trajectory to follow\n\
00078 trajectory_msgs/JointTrajectory trajectory\n\
00079 \n\
00080 # Tolerances for the trajectory. If the measured joint values fall\n\
00081 # outside the tolerances the trajectory goal is aborted. Any\n\
00082 # tolerances that are not specified (by being omitted or set to 0) are\n\
00083 # set to the defaults for the action server (often taken from the\n\
00084 # parameter server).\n\
00085 \n\
00086 # Tolerances applied to the joints as the trajectory is executed. If\n\
00087 # violated, the goal aborts with error_code set to\n\
00088 # PATH_TOLERANCE_VIOLATED.\n\
00089 JointTolerance[] path_tolerance\n\
00090 \n\
00091 # To report success, the joints must be within goal_tolerance of the\n\
00092 # final trajectory value. The goal must be achieved by time the\n\
00093 # trajectory ends plus goal_time_tolerance. (goal_time_tolerance\n\
00094 # allows some leeway in time, so that the trajectory goal can still\n\
00095 # succeed even if the joints reach the goal some time after the\n\
00096 # precise end time of the trajectory).\n\
00097 #\n\
00098 # If the joints are not within goal_tolerance after \"trajectory finish\n\
00099 # time\" + goal_time_tolerance, the goal aborts with error_code set to\n\
00100 # GOAL_TOLERANCE_VIOLATED\n\
00101 JointTolerance[] goal_tolerance\n\
00102 duration goal_time_tolerance\n\
00103 \n\
00104 \n\
00105 ================================================================================\n\
00106 MSG: trajectory_msgs/JointTrajectory\n\
00107 Header header\n\
00108 string[] joint_names\n\
00109 JointTrajectoryPoint[] points\n\
00110 ================================================================================\n\
00111 MSG: std_msgs/Header\n\
00112 # Standard metadata for higher-level stamped data types.\n\
00113 # This is generally used to communicate timestamped data \n\
00114 # in a particular coordinate frame.\n\
00115 # \n\
00116 # sequence ID: consecutively increasing ID \n\
00117 uint32 seq\n\
00118 #Two-integer timestamp that is expressed as:\n\
00119 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00120 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00121 # time-handling sugar is provided by the client library\n\
00122 time stamp\n\
00123 #Frame this data is associated with\n\
00124 # 0: no frame\n\
00125 # 1: global frame\n\
00126 string frame_id\n\
00127 \n\
00128 ================================================================================\n\
00129 MSG: trajectory_msgs/JointTrajectoryPoint\n\
00130 float64[] positions\n\
00131 float64[] velocities\n\
00132 float64[] accelerations\n\
00133 duration time_from_start\n\
00134 ================================================================================\n\
00135 MSG: control_msgs/JointTolerance\n\
00136 # The tolerances specify the amount the position, velocity, and\n\
00137 # accelerations can vary from the setpoints. For example, in the case\n\
00138 # of trajectory control, when the actual position varies beyond\n\
00139 # (desired position + position tolerance), the trajectory goal may\n\
00140 # abort.\n\
00141 # \n\
00142 # There are two special values for tolerances:\n\
00143 # * 0 - The tolerance is unspecified and will remain at whatever the default is\n\
00144 # * -1 - The tolerance is \"erased\". If there was a default, the joint will be\n\
00145 # allowed to move without restriction.\n\
00146 \n\
00147 string name\n\
00148 float64 position # in radians or meters (for a revolute or prismatic joint, respectively)\n\
00149 float64 velocity # in rad/sec or m/sec\n\
00150 float64 acceleration # in rad/sec^2 or m/sec^2\n\
00151 \n\
00152 "; }
00153 public:
00154 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00155
00156 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00157
00158 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00159 {
00160 ros::serialization::OStream stream(write_ptr, 1000000000);
00161 ros::serialization::serialize(stream, trajectory);
00162 ros::serialization::serialize(stream, path_tolerance);
00163 ros::serialization::serialize(stream, goal_tolerance);
00164 ros::serialization::serialize(stream, goal_time_tolerance);
00165 return stream.getData();
00166 }
00167
00168 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00169 {
00170 ros::serialization::IStream stream(read_ptr, 1000000000);
00171 ros::serialization::deserialize(stream, trajectory);
00172 ros::serialization::deserialize(stream, path_tolerance);
00173 ros::serialization::deserialize(stream, goal_tolerance);
00174 ros::serialization::deserialize(stream, goal_time_tolerance);
00175 return stream.getData();
00176 }
00177
00178 ROS_DEPRECATED virtual uint32_t serializationLength() const
00179 {
00180 uint32_t size = 0;
00181 size += ros::serialization::serializationLength(trajectory);
00182 size += ros::serialization::serializationLength(path_tolerance);
00183 size += ros::serialization::serializationLength(goal_tolerance);
00184 size += ros::serialization::serializationLength(goal_time_tolerance);
00185 return size;
00186 }
00187
00188 typedef boost::shared_ptr< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> > Ptr;
00189 typedef boost::shared_ptr< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> const> ConstPtr;
00190 };
00191 typedef ::control_msgs::FollowJointTrajectoryGoal_<std::allocator<void> > FollowJointTrajectoryGoal;
00192
00193 typedef boost::shared_ptr< ::control_msgs::FollowJointTrajectoryGoal> FollowJointTrajectoryGoalPtr;
00194 typedef boost::shared_ptr< ::control_msgs::FollowJointTrajectoryGoal const> FollowJointTrajectoryGoalConstPtr;
00195
00196
00197 template<typename ContainerAllocator>
00198 std::ostream& operator<<(std::ostream& s, const ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> & v)
00199 {
00200 ros::message_operations::Printer< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> >::stream(s, "", v);
00201 return s;}
00202
00203 }
00204
00205 namespace ros
00206 {
00207 namespace message_traits
00208 {
00209 template<class ContainerAllocator>
00210 struct MD5Sum< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> > {
00211 static const char* value()
00212 {
00213 return "01f6d702507b59bae3fc1e7149e6210c";
00214 }
00215
00216 static const char* value(const ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> &) { return value(); }
00217 static const uint64_t static_value1 = 0x01f6d702507b59baULL;
00218 static const uint64_t static_value2 = 0xe3fc1e7149e6210cULL;
00219 };
00220
00221 template<class ContainerAllocator>
00222 struct DataType< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> > {
00223 static const char* value()
00224 {
00225 return "control_msgs/FollowJointTrajectoryGoal";
00226 }
00227
00228 static const char* value(const ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> &) { return value(); }
00229 };
00230
00231 template<class ContainerAllocator>
00232 struct Definition< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> > {
00233 static const char* value()
00234 {
00235 return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00236 # The joint trajectory to follow\n\
00237 trajectory_msgs/JointTrajectory trajectory\n\
00238 \n\
00239 # Tolerances for the trajectory. If the measured joint values fall\n\
00240 # outside the tolerances the trajectory goal is aborted. Any\n\
00241 # tolerances that are not specified (by being omitted or set to 0) are\n\
00242 # set to the defaults for the action server (often taken from the\n\
00243 # parameter server).\n\
00244 \n\
00245 # Tolerances applied to the joints as the trajectory is executed. If\n\
00246 # violated, the goal aborts with error_code set to\n\
00247 # PATH_TOLERANCE_VIOLATED.\n\
00248 JointTolerance[] path_tolerance\n\
00249 \n\
00250 # To report success, the joints must be within goal_tolerance of the\n\
00251 # final trajectory value. The goal must be achieved by time the\n\
00252 # trajectory ends plus goal_time_tolerance. (goal_time_tolerance\n\
00253 # allows some leeway in time, so that the trajectory goal can still\n\
00254 # succeed even if the joints reach the goal some time after the\n\
00255 # precise end time of the trajectory).\n\
00256 #\n\
00257 # If the joints are not within goal_tolerance after \"trajectory finish\n\
00258 # time\" + goal_time_tolerance, the goal aborts with error_code set to\n\
00259 # GOAL_TOLERANCE_VIOLATED\n\
00260 JointTolerance[] goal_tolerance\n\
00261 duration goal_time_tolerance\n\
00262 \n\
00263 \n\
00264 ================================================================================\n\
00265 MSG: trajectory_msgs/JointTrajectory\n\
00266 Header header\n\
00267 string[] joint_names\n\
00268 JointTrajectoryPoint[] points\n\
00269 ================================================================================\n\
00270 MSG: std_msgs/Header\n\
00271 # Standard metadata for higher-level stamped data types.\n\
00272 # This is generally used to communicate timestamped data \n\
00273 # in a particular coordinate frame.\n\
00274 # \n\
00275 # sequence ID: consecutively increasing ID \n\
00276 uint32 seq\n\
00277 #Two-integer timestamp that is expressed as:\n\
00278 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00279 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00280 # time-handling sugar is provided by the client library\n\
00281 time stamp\n\
00282 #Frame this data is associated with\n\
00283 # 0: no frame\n\
00284 # 1: global frame\n\
00285 string frame_id\n\
00286 \n\
00287 ================================================================================\n\
00288 MSG: trajectory_msgs/JointTrajectoryPoint\n\
00289 float64[] positions\n\
00290 float64[] velocities\n\
00291 float64[] accelerations\n\
00292 duration time_from_start\n\
00293 ================================================================================\n\
00294 MSG: control_msgs/JointTolerance\n\
00295 # The tolerances specify the amount the position, velocity, and\n\
00296 # accelerations can vary from the setpoints. For example, in the case\n\
00297 # of trajectory control, when the actual position varies beyond\n\
00298 # (desired position + position tolerance), the trajectory goal may\n\
00299 # abort.\n\
00300 # \n\
00301 # There are two special values for tolerances:\n\
00302 # * 0 - The tolerance is unspecified and will remain at whatever the default is\n\
00303 # * -1 - The tolerance is \"erased\". If there was a default, the joint will be\n\
00304 # allowed to move without restriction.\n\
00305 \n\
00306 string name\n\
00307 float64 position # in radians or meters (for a revolute or prismatic joint, respectively)\n\
00308 float64 velocity # in rad/sec or m/sec\n\
00309 float64 acceleration # in rad/sec^2 or m/sec^2\n\
00310 \n\
00311 ";
00312 }
00313
00314 static const char* value(const ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> &) { return value(); }
00315 };
00316
00317 }
00318 }
00319
00320 namespace ros
00321 {
00322 namespace serialization
00323 {
00324
00325 template<class ContainerAllocator> struct Serializer< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> >
00326 {
00327 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00328 {
00329 stream.next(m.trajectory);
00330 stream.next(m.path_tolerance);
00331 stream.next(m.goal_tolerance);
00332 stream.next(m.goal_time_tolerance);
00333 }
00334
00335 ROS_DECLARE_ALLINONE_SERIALIZER;
00336 };
00337 }
00338 }
00339
00340 namespace ros
00341 {
00342 namespace message_operations
00343 {
00344
00345 template<class ContainerAllocator>
00346 struct Printer< ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> >
00347 {
00348 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::control_msgs::FollowJointTrajectoryGoal_<ContainerAllocator> & v)
00349 {
00350 s << indent << "trajectory: ";
00351 s << std::endl;
00352 Printer< ::trajectory_msgs::JointTrajectory_<ContainerAllocator> >::stream(s, indent + " ", v.trajectory);
00353 s << indent << "path_tolerance[]" << std::endl;
00354 for (size_t i = 0; i < v.path_tolerance.size(); ++i)
00355 {
00356 s << indent << " path_tolerance[" << i << "]: ";
00357 s << std::endl;
00358 s << indent;
00359 Printer< ::control_msgs::JointTolerance_<ContainerAllocator> >::stream(s, indent + " ", v.path_tolerance[i]);
00360 }
00361 s << indent << "goal_tolerance[]" << std::endl;
00362 for (size_t i = 0; i < v.goal_tolerance.size(); ++i)
00363 {
00364 s << indent << " goal_tolerance[" << i << "]: ";
00365 s << std::endl;
00366 s << indent;
00367 Printer< ::control_msgs::JointTolerance_<ContainerAllocator> >::stream(s, indent + " ", v.goal_tolerance[i]);
00368 }
00369 s << indent << "goal_time_tolerance: ";
00370 Printer<ros::Duration>::stream(s, indent + " ", v.goal_time_tolerance);
00371 }
00372 };
00373
00374
00375 }
00376 }
00377
00378 #endif // CONTROL_MSGS_MESSAGE_FOLLOWJOINTTRAJECTORYGOAL_H
00379