$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-arm_navigation/doc_stacks/2013-03-01_14-05-03.553953/arm_navigation/arm_navigation_msgs/msg/OrientationConstraint.msg */ 00002 #ifndef ARM_NAVIGATION_MSGS_MESSAGE_ORIENTATIONCONSTRAINT_H 00003 #define ARM_NAVIGATION_MSGS_MESSAGE_ORIENTATIONCONSTRAINT_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 "geometry_msgs/Quaternion.h" 00019 00020 namespace arm_navigation_msgs 00021 { 00022 template <class ContainerAllocator> 00023 struct OrientationConstraint_ { 00024 typedef OrientationConstraint_<ContainerAllocator> Type; 00025 00026 OrientationConstraint_() 00027 : header() 00028 , link_name() 00029 , type(0) 00030 , orientation() 00031 , absolute_roll_tolerance(0.0) 00032 , absolute_pitch_tolerance(0.0) 00033 , absolute_yaw_tolerance(0.0) 00034 , weight(0.0) 00035 { 00036 } 00037 00038 OrientationConstraint_(const ContainerAllocator& _alloc) 00039 : header(_alloc) 00040 , link_name(_alloc) 00041 , type(0) 00042 , orientation(_alloc) 00043 , absolute_roll_tolerance(0.0) 00044 , absolute_pitch_tolerance(0.0) 00045 , absolute_yaw_tolerance(0.0) 00046 , weight(0.0) 00047 { 00048 } 00049 00050 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00051 ::std_msgs::Header_<ContainerAllocator> header; 00052 00053 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _link_name_type; 00054 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > link_name; 00055 00056 typedef int32_t _type_type; 00057 int32_t type; 00058 00059 typedef ::geometry_msgs::Quaternion_<ContainerAllocator> _orientation_type; 00060 ::geometry_msgs::Quaternion_<ContainerAllocator> orientation; 00061 00062 typedef double _absolute_roll_tolerance_type; 00063 double absolute_roll_tolerance; 00064 00065 typedef double _absolute_pitch_tolerance_type; 00066 double absolute_pitch_tolerance; 00067 00068 typedef double _absolute_yaw_tolerance_type; 00069 double absolute_yaw_tolerance; 00070 00071 typedef double _weight_type; 00072 double weight; 00073 00074 enum { LINK_FRAME = 0 }; 00075 enum { HEADER_FRAME = 1 }; 00076 00077 private: 00078 static const char* __s_getDataType_() { return "arm_navigation_msgs/OrientationConstraint"; } 00079 public: 00080 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00081 00082 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00083 00084 private: 00085 static const char* __s_getMD5Sum_() { return "27d99749ba49d4a822298bbd1e0988ba"; } 00086 public: 00087 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00088 00089 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00090 00091 private: 00092 static const char* __s_getMessageDefinition_() { return "# This message contains the definition of an orientation constraint.\n\ 00093 Header header\n\ 00094 \n\ 00095 # The robot link this constraint refers to\n\ 00096 string link_name\n\ 00097 \n\ 00098 # The type of the constraint\n\ 00099 int32 type\n\ 00100 int32 LINK_FRAME=0\n\ 00101 int32 HEADER_FRAME=1\n\ 00102 \n\ 00103 # The desired orientation of the robot link specified as a quaternion\n\ 00104 geometry_msgs/Quaternion orientation\n\ 00105 \n\ 00106 # optional RPY error tolerances specified if \n\ 00107 float64 absolute_roll_tolerance\n\ 00108 float64 absolute_pitch_tolerance\n\ 00109 float64 absolute_yaw_tolerance\n\ 00110 \n\ 00111 # Constraint weighting factor - a weight for this constraint\n\ 00112 float64 weight\n\ 00113 \n\ 00114 ================================================================================\n\ 00115 MSG: std_msgs/Header\n\ 00116 # Standard metadata for higher-level stamped data types.\n\ 00117 # This is generally used to communicate timestamped data \n\ 00118 # in a particular coordinate frame.\n\ 00119 # \n\ 00120 # sequence ID: consecutively increasing ID \n\ 00121 uint32 seq\n\ 00122 #Two-integer timestamp that is expressed as:\n\ 00123 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00124 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00125 # time-handling sugar is provided by the client library\n\ 00126 time stamp\n\ 00127 #Frame this data is associated with\n\ 00128 # 0: no frame\n\ 00129 # 1: global frame\n\ 00130 string frame_id\n\ 00131 \n\ 00132 ================================================================================\n\ 00133 MSG: geometry_msgs/Quaternion\n\ 00134 # This represents an orientation in free space in quaternion form.\n\ 00135 \n\ 00136 float64 x\n\ 00137 float64 y\n\ 00138 float64 z\n\ 00139 float64 w\n\ 00140 \n\ 00141 "; } 00142 public: 00143 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00144 00145 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00146 00147 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00148 { 00149 ros::serialization::OStream stream(write_ptr, 1000000000); 00150 ros::serialization::serialize(stream, header); 00151 ros::serialization::serialize(stream, link_name); 00152 ros::serialization::serialize(stream, type); 00153 ros::serialization::serialize(stream, orientation); 00154 ros::serialization::serialize(stream, absolute_roll_tolerance); 00155 ros::serialization::serialize(stream, absolute_pitch_tolerance); 00156 ros::serialization::serialize(stream, absolute_yaw_tolerance); 00157 ros::serialization::serialize(stream, weight); 00158 return stream.getData(); 00159 } 00160 00161 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00162 { 00163 ros::serialization::IStream stream(read_ptr, 1000000000); 00164 ros::serialization::deserialize(stream, header); 00165 ros::serialization::deserialize(stream, link_name); 00166 ros::serialization::deserialize(stream, type); 00167 ros::serialization::deserialize(stream, orientation); 00168 ros::serialization::deserialize(stream, absolute_roll_tolerance); 00169 ros::serialization::deserialize(stream, absolute_pitch_tolerance); 00170 ros::serialization::deserialize(stream, absolute_yaw_tolerance); 00171 ros::serialization::deserialize(stream, weight); 00172 return stream.getData(); 00173 } 00174 00175 ROS_DEPRECATED virtual uint32_t serializationLength() const 00176 { 00177 uint32_t size = 0; 00178 size += ros::serialization::serializationLength(header); 00179 size += ros::serialization::serializationLength(link_name); 00180 size += ros::serialization::serializationLength(type); 00181 size += ros::serialization::serializationLength(orientation); 00182 size += ros::serialization::serializationLength(absolute_roll_tolerance); 00183 size += ros::serialization::serializationLength(absolute_pitch_tolerance); 00184 size += ros::serialization::serializationLength(absolute_yaw_tolerance); 00185 size += ros::serialization::serializationLength(weight); 00186 return size; 00187 } 00188 00189 typedef boost::shared_ptr< ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> > Ptr; 00190 typedef boost::shared_ptr< ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> const> ConstPtr; 00191 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00192 }; // struct OrientationConstraint 00193 typedef ::arm_navigation_msgs::OrientationConstraint_<std::allocator<void> > OrientationConstraint; 00194 00195 typedef boost::shared_ptr< ::arm_navigation_msgs::OrientationConstraint> OrientationConstraintPtr; 00196 typedef boost::shared_ptr< ::arm_navigation_msgs::OrientationConstraint const> OrientationConstraintConstPtr; 00197 00198 00199 template<typename ContainerAllocator> 00200 std::ostream& operator<<(std::ostream& s, const ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> & v) 00201 { 00202 ros::message_operations::Printer< ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> >::stream(s, "", v); 00203 return s;} 00204 00205 } // namespace arm_navigation_msgs 00206 00207 namespace ros 00208 { 00209 namespace message_traits 00210 { 00211 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> > : public TrueType {}; 00212 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> const> : public TrueType {}; 00213 template<class ContainerAllocator> 00214 struct MD5Sum< ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> > { 00215 static const char* value() 00216 { 00217 return "27d99749ba49d4a822298bbd1e0988ba"; 00218 } 00219 00220 static const char* value(const ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> &) { return value(); } 00221 static const uint64_t static_value1 = 0x27d99749ba49d4a8ULL; 00222 static const uint64_t static_value2 = 0x22298bbd1e0988baULL; 00223 }; 00224 00225 template<class ContainerAllocator> 00226 struct DataType< ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> > { 00227 static const char* value() 00228 { 00229 return "arm_navigation_msgs/OrientationConstraint"; 00230 } 00231 00232 static const char* value(const ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> &) { return value(); } 00233 }; 00234 00235 template<class ContainerAllocator> 00236 struct Definition< ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> > { 00237 static const char* value() 00238 { 00239 return "# This message contains the definition of an orientation constraint.\n\ 00240 Header header\n\ 00241 \n\ 00242 # The robot link this constraint refers to\n\ 00243 string link_name\n\ 00244 \n\ 00245 # The type of the constraint\n\ 00246 int32 type\n\ 00247 int32 LINK_FRAME=0\n\ 00248 int32 HEADER_FRAME=1\n\ 00249 \n\ 00250 # The desired orientation of the robot link specified as a quaternion\n\ 00251 geometry_msgs/Quaternion orientation\n\ 00252 \n\ 00253 # optional RPY error tolerances specified if \n\ 00254 float64 absolute_roll_tolerance\n\ 00255 float64 absolute_pitch_tolerance\n\ 00256 float64 absolute_yaw_tolerance\n\ 00257 \n\ 00258 # Constraint weighting factor - a weight for this constraint\n\ 00259 float64 weight\n\ 00260 \n\ 00261 ================================================================================\n\ 00262 MSG: std_msgs/Header\n\ 00263 # Standard metadata for higher-level stamped data types.\n\ 00264 # This is generally used to communicate timestamped data \n\ 00265 # in a particular coordinate frame.\n\ 00266 # \n\ 00267 # sequence ID: consecutively increasing ID \n\ 00268 uint32 seq\n\ 00269 #Two-integer timestamp that is expressed as:\n\ 00270 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00271 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00272 # time-handling sugar is provided by the client library\n\ 00273 time stamp\n\ 00274 #Frame this data is associated with\n\ 00275 # 0: no frame\n\ 00276 # 1: global frame\n\ 00277 string frame_id\n\ 00278 \n\ 00279 ================================================================================\n\ 00280 MSG: geometry_msgs/Quaternion\n\ 00281 # This represents an orientation in free space in quaternion form.\n\ 00282 \n\ 00283 float64 x\n\ 00284 float64 y\n\ 00285 float64 z\n\ 00286 float64 w\n\ 00287 \n\ 00288 "; 00289 } 00290 00291 static const char* value(const ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> &) { return value(); } 00292 }; 00293 00294 template<class ContainerAllocator> struct HasHeader< ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> > : public TrueType {}; 00295 template<class ContainerAllocator> struct HasHeader< const ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> > : public TrueType {}; 00296 } // namespace message_traits 00297 } // namespace ros 00298 00299 namespace ros 00300 { 00301 namespace serialization 00302 { 00303 00304 template<class ContainerAllocator> struct Serializer< ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> > 00305 { 00306 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00307 { 00308 stream.next(m.header); 00309 stream.next(m.link_name); 00310 stream.next(m.type); 00311 stream.next(m.orientation); 00312 stream.next(m.absolute_roll_tolerance); 00313 stream.next(m.absolute_pitch_tolerance); 00314 stream.next(m.absolute_yaw_tolerance); 00315 stream.next(m.weight); 00316 } 00317 00318 ROS_DECLARE_ALLINONE_SERIALIZER; 00319 }; // struct OrientationConstraint_ 00320 } // namespace serialization 00321 } // namespace ros 00322 00323 namespace ros 00324 { 00325 namespace message_operations 00326 { 00327 00328 template<class ContainerAllocator> 00329 struct Printer< ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> > 00330 { 00331 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::arm_navigation_msgs::OrientationConstraint_<ContainerAllocator> & v) 00332 { 00333 s << indent << "header: "; 00334 s << std::endl; 00335 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00336 s << indent << "link_name: "; 00337 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.link_name); 00338 s << indent << "type: "; 00339 Printer<int32_t>::stream(s, indent + " ", v.type); 00340 s << indent << "orientation: "; 00341 s << std::endl; 00342 Printer< ::geometry_msgs::Quaternion_<ContainerAllocator> >::stream(s, indent + " ", v.orientation); 00343 s << indent << "absolute_roll_tolerance: "; 00344 Printer<double>::stream(s, indent + " ", v.absolute_roll_tolerance); 00345 s << indent << "absolute_pitch_tolerance: "; 00346 Printer<double>::stream(s, indent + " ", v.absolute_pitch_tolerance); 00347 s << indent << "absolute_yaw_tolerance: "; 00348 Printer<double>::stream(s, indent + " ", v.absolute_yaw_tolerance); 00349 s << indent << "weight: "; 00350 Printer<double>::stream(s, indent + " ", v.weight); 00351 } 00352 }; 00353 00354 00355 } // namespace message_operations 00356 } // namespace ros 00357 00358 #endif // ARM_NAVIGATION_MSGS_MESSAGE_ORIENTATIONCONSTRAINT_H 00359