$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-pr2_controllers/doc_stacks/2013-03-01_16-45-23.561928/pr2_controllers/pr2_controllers_msgs/msg/PointHeadGoal.msg */ 00002 #ifndef PR2_CONTROLLERS_MSGS_MESSAGE_POINTHEADGOAL_H 00003 #define PR2_CONTROLLERS_MSGS_MESSAGE_POINTHEADGOAL_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 "geometry_msgs/PointStamped.h" 00018 #include "geometry_msgs/Vector3.h" 00019 00020 namespace pr2_controllers_msgs 00021 { 00022 template <class ContainerAllocator> 00023 struct PointHeadGoal_ { 00024 typedef PointHeadGoal_<ContainerAllocator> Type; 00025 00026 PointHeadGoal_() 00027 : target() 00028 , pointing_axis() 00029 , pointing_frame() 00030 , min_duration() 00031 , max_velocity(0.0) 00032 { 00033 } 00034 00035 PointHeadGoal_(const ContainerAllocator& _alloc) 00036 : target(_alloc) 00037 , pointing_axis(_alloc) 00038 , pointing_frame(_alloc) 00039 , min_duration() 00040 , max_velocity(0.0) 00041 { 00042 } 00043 00044 typedef ::geometry_msgs::PointStamped_<ContainerAllocator> _target_type; 00045 ::geometry_msgs::PointStamped_<ContainerAllocator> target; 00046 00047 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _pointing_axis_type; 00048 ::geometry_msgs::Vector3_<ContainerAllocator> pointing_axis; 00049 00050 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _pointing_frame_type; 00051 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > pointing_frame; 00052 00053 typedef ros::Duration _min_duration_type; 00054 ros::Duration min_duration; 00055 00056 typedef double _max_velocity_type; 00057 double max_velocity; 00058 00059 00060 private: 00061 static const char* __s_getDataType_() { return "pr2_controllers_msgs/PointHeadGoal"; } 00062 public: 00063 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00064 00065 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00066 00067 private: 00068 static const char* __s_getMD5Sum_() { return "8b92b1cd5e06c8a94c917dc3209a4c1d"; } 00069 public: 00070 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00071 00072 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00073 00074 private: 00075 static const char* __s_getMessageDefinition_() { return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\ 00076 geometry_msgs/PointStamped target\n\ 00077 geometry_msgs/Vector3 pointing_axis\n\ 00078 string pointing_frame\n\ 00079 duration min_duration\n\ 00080 float64 max_velocity\n\ 00081 \n\ 00082 ================================================================================\n\ 00083 MSG: geometry_msgs/PointStamped\n\ 00084 # This represents a Point with reference coordinate frame and timestamp\n\ 00085 Header header\n\ 00086 Point point\n\ 00087 \n\ 00088 ================================================================================\n\ 00089 MSG: std_msgs/Header\n\ 00090 # Standard metadata for higher-level stamped data types.\n\ 00091 # This is generally used to communicate timestamped data \n\ 00092 # in a particular coordinate frame.\n\ 00093 # \n\ 00094 # sequence ID: consecutively increasing ID \n\ 00095 uint32 seq\n\ 00096 #Two-integer timestamp that is expressed as:\n\ 00097 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00098 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00099 # time-handling sugar is provided by the client library\n\ 00100 time stamp\n\ 00101 #Frame this data is associated with\n\ 00102 # 0: no frame\n\ 00103 # 1: global frame\n\ 00104 string frame_id\n\ 00105 \n\ 00106 ================================================================================\n\ 00107 MSG: geometry_msgs/Point\n\ 00108 # This contains the position of a point in free space\n\ 00109 float64 x\n\ 00110 float64 y\n\ 00111 float64 z\n\ 00112 \n\ 00113 ================================================================================\n\ 00114 MSG: geometry_msgs/Vector3\n\ 00115 # This represents a vector in free space. \n\ 00116 \n\ 00117 float64 x\n\ 00118 float64 y\n\ 00119 float64 z\n\ 00120 "; } 00121 public: 00122 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00123 00124 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00125 00126 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00127 { 00128 ros::serialization::OStream stream(write_ptr, 1000000000); 00129 ros::serialization::serialize(stream, target); 00130 ros::serialization::serialize(stream, pointing_axis); 00131 ros::serialization::serialize(stream, pointing_frame); 00132 ros::serialization::serialize(stream, min_duration); 00133 ros::serialization::serialize(stream, max_velocity); 00134 return stream.getData(); 00135 } 00136 00137 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00138 { 00139 ros::serialization::IStream stream(read_ptr, 1000000000); 00140 ros::serialization::deserialize(stream, target); 00141 ros::serialization::deserialize(stream, pointing_axis); 00142 ros::serialization::deserialize(stream, pointing_frame); 00143 ros::serialization::deserialize(stream, min_duration); 00144 ros::serialization::deserialize(stream, max_velocity); 00145 return stream.getData(); 00146 } 00147 00148 ROS_DEPRECATED virtual uint32_t serializationLength() const 00149 { 00150 uint32_t size = 0; 00151 size += ros::serialization::serializationLength(target); 00152 size += ros::serialization::serializationLength(pointing_axis); 00153 size += ros::serialization::serializationLength(pointing_frame); 00154 size += ros::serialization::serializationLength(min_duration); 00155 size += ros::serialization::serializationLength(max_velocity); 00156 return size; 00157 } 00158 00159 typedef boost::shared_ptr< ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> > Ptr; 00160 typedef boost::shared_ptr< ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> const> ConstPtr; 00161 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00162 }; // struct PointHeadGoal 00163 typedef ::pr2_controllers_msgs::PointHeadGoal_<std::allocator<void> > PointHeadGoal; 00164 00165 typedef boost::shared_ptr< ::pr2_controllers_msgs::PointHeadGoal> PointHeadGoalPtr; 00166 typedef boost::shared_ptr< ::pr2_controllers_msgs::PointHeadGoal const> PointHeadGoalConstPtr; 00167 00168 00169 template<typename ContainerAllocator> 00170 std::ostream& operator<<(std::ostream& s, const ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> & v) 00171 { 00172 ros::message_operations::Printer< ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> >::stream(s, "", v); 00173 return s;} 00174 00175 } // namespace pr2_controllers_msgs 00176 00177 namespace ros 00178 { 00179 namespace message_traits 00180 { 00181 template<class ContainerAllocator> struct IsMessage< ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> > : public TrueType {}; 00182 template<class ContainerAllocator> struct IsMessage< ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> const> : public TrueType {}; 00183 template<class ContainerAllocator> 00184 struct MD5Sum< ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> > { 00185 static const char* value() 00186 { 00187 return "8b92b1cd5e06c8a94c917dc3209a4c1d"; 00188 } 00189 00190 static const char* value(const ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> &) { return value(); } 00191 static const uint64_t static_value1 = 0x8b92b1cd5e06c8a9ULL; 00192 static const uint64_t static_value2 = 0x4c917dc3209a4c1dULL; 00193 }; 00194 00195 template<class ContainerAllocator> 00196 struct DataType< ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> > { 00197 static const char* value() 00198 { 00199 return "pr2_controllers_msgs/PointHeadGoal"; 00200 } 00201 00202 static const char* value(const ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> &) { return value(); } 00203 }; 00204 00205 template<class ContainerAllocator> 00206 struct Definition< ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> > { 00207 static const char* value() 00208 { 00209 return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\ 00210 geometry_msgs/PointStamped target\n\ 00211 geometry_msgs/Vector3 pointing_axis\n\ 00212 string pointing_frame\n\ 00213 duration min_duration\n\ 00214 float64 max_velocity\n\ 00215 \n\ 00216 ================================================================================\n\ 00217 MSG: geometry_msgs/PointStamped\n\ 00218 # This represents a Point with reference coordinate frame and timestamp\n\ 00219 Header header\n\ 00220 Point point\n\ 00221 \n\ 00222 ================================================================================\n\ 00223 MSG: std_msgs/Header\n\ 00224 # Standard metadata for higher-level stamped data types.\n\ 00225 # This is generally used to communicate timestamped data \n\ 00226 # in a particular coordinate frame.\n\ 00227 # \n\ 00228 # sequence ID: consecutively increasing ID \n\ 00229 uint32 seq\n\ 00230 #Two-integer timestamp that is expressed as:\n\ 00231 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00232 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00233 # time-handling sugar is provided by the client library\n\ 00234 time stamp\n\ 00235 #Frame this data is associated with\n\ 00236 # 0: no frame\n\ 00237 # 1: global frame\n\ 00238 string frame_id\n\ 00239 \n\ 00240 ================================================================================\n\ 00241 MSG: geometry_msgs/Point\n\ 00242 # This contains the position of a point in free space\n\ 00243 float64 x\n\ 00244 float64 y\n\ 00245 float64 z\n\ 00246 \n\ 00247 ================================================================================\n\ 00248 MSG: geometry_msgs/Vector3\n\ 00249 # This represents a vector in free space. \n\ 00250 \n\ 00251 float64 x\n\ 00252 float64 y\n\ 00253 float64 z\n\ 00254 "; 00255 } 00256 00257 static const char* value(const ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> &) { return value(); } 00258 }; 00259 00260 } // namespace message_traits 00261 } // namespace ros 00262 00263 namespace ros 00264 { 00265 namespace serialization 00266 { 00267 00268 template<class ContainerAllocator> struct Serializer< ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> > 00269 { 00270 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00271 { 00272 stream.next(m.target); 00273 stream.next(m.pointing_axis); 00274 stream.next(m.pointing_frame); 00275 stream.next(m.min_duration); 00276 stream.next(m.max_velocity); 00277 } 00278 00279 ROS_DECLARE_ALLINONE_SERIALIZER; 00280 }; // struct PointHeadGoal_ 00281 } // namespace serialization 00282 } // namespace ros 00283 00284 namespace ros 00285 { 00286 namespace message_operations 00287 { 00288 00289 template<class ContainerAllocator> 00290 struct Printer< ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> > 00291 { 00292 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_controllers_msgs::PointHeadGoal_<ContainerAllocator> & v) 00293 { 00294 s << indent << "target: "; 00295 s << std::endl; 00296 Printer< ::geometry_msgs::PointStamped_<ContainerAllocator> >::stream(s, indent + " ", v.target); 00297 s << indent << "pointing_axis: "; 00298 s << std::endl; 00299 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.pointing_axis); 00300 s << indent << "pointing_frame: "; 00301 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.pointing_frame); 00302 s << indent << "min_duration: "; 00303 Printer<ros::Duration>::stream(s, indent + " ", v.min_duration); 00304 s << indent << "max_velocity: "; 00305 Printer<double>::stream(s, indent + " ", v.max_velocity); 00306 } 00307 }; 00308 00309 00310 } // namespace message_operations 00311 } // namespace ros 00312 00313 #endif // PR2_CONTROLLERS_MSGS_MESSAGE_POINTHEADGOAL_H 00314