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