$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-applanix_driver/doc_stacks/2013-03-01_14-05-02.457261/applanix_driver/applanix_msgs/msg/AidingSensorParams.msg */ 00002 #ifndef APPLANIX_MSGS_MESSAGE_AIDINGSENSORPARAMS_H 00003 #define APPLANIX_MSGS_MESSAGE_AIDINGSENSORPARAMS_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/Point32.h" 00018 00019 namespace applanix_msgs 00020 { 00021 template <class ContainerAllocator> 00022 struct AidingSensorParams_ { 00023 typedef AidingSensorParams_<ContainerAllocator> Type; 00024 00025 AidingSensorParams_() 00026 : transaction(0) 00027 , dmi_scale_factor(0.0) 00028 , dmi_lever_arm() 00029 , reserved1(0.0) 00030 , reserved2(0.0) 00031 , reserved3(0.0) 00032 , reserved5(0.0) 00033 , reserved6(0.0) 00034 , reserved7(0.0) 00035 { 00036 } 00037 00038 AidingSensorParams_(const ContainerAllocator& _alloc) 00039 : transaction(0) 00040 , dmi_scale_factor(0.0) 00041 , dmi_lever_arm(_alloc) 00042 , reserved1(0.0) 00043 , reserved2(0.0) 00044 , reserved3(0.0) 00045 , reserved5(0.0) 00046 , reserved6(0.0) 00047 , reserved7(0.0) 00048 { 00049 } 00050 00051 typedef uint16_t _transaction_type; 00052 uint16_t transaction; 00053 00054 typedef float _dmi_scale_factor_type; 00055 float dmi_scale_factor; 00056 00057 typedef ::geometry_msgs::Point32_<ContainerAllocator> _dmi_lever_arm_type; 00058 ::geometry_msgs::Point32_<ContainerAllocator> dmi_lever_arm; 00059 00060 typedef float _reserved1_type; 00061 float reserved1; 00062 00063 typedef float _reserved2_type; 00064 float reserved2; 00065 00066 typedef float _reserved3_type; 00067 float reserved3; 00068 00069 typedef float _reserved5_type; 00070 float reserved5; 00071 00072 typedef float _reserved6_type; 00073 float reserved6; 00074 00075 typedef float _reserved7_type; 00076 float reserved7; 00077 00078 00079 private: 00080 static const char* __s_getDataType_() { return "applanix_msgs/AidingSensorParams"; } 00081 public: 00082 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00083 00084 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00085 00086 private: 00087 static const char* __s_getMD5Sum_() { return "c5f8cdbc1fbfdcb4567e70396891f001"; } 00088 public: 00089 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00090 00091 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00092 00093 private: 00094 static const char* __s_getMessageDefinition_() { return "# Msg 22\n\ 00095 uint16 transaction\n\ 00096 \n\ 00097 float32 dmi_scale_factor\n\ 00098 geometry_msgs/Point32 dmi_lever_arm\n\ 00099 \n\ 00100 float32 reserved1\n\ 00101 float32 reserved2\n\ 00102 float32 reserved3\n\ 00103 float32 reserved5\n\ 00104 float32 reserved6\n\ 00105 float32 reserved7\n\ 00106 \n\ 00107 ================================================================================\n\ 00108 MSG: geometry_msgs/Point32\n\ 00109 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00110 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00111 # \n\ 00112 # This recommendation is to promote interoperability. \n\ 00113 #\n\ 00114 # This message is designed to take up less space when sending\n\ 00115 # lots of points at once, as in the case of a PointCloud. \n\ 00116 \n\ 00117 float32 x\n\ 00118 float32 y\n\ 00119 float32 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, transaction); 00130 ros::serialization::serialize(stream, dmi_scale_factor); 00131 ros::serialization::serialize(stream, dmi_lever_arm); 00132 ros::serialization::serialize(stream, reserved1); 00133 ros::serialization::serialize(stream, reserved2); 00134 ros::serialization::serialize(stream, reserved3); 00135 ros::serialization::serialize(stream, reserved5); 00136 ros::serialization::serialize(stream, reserved6); 00137 ros::serialization::serialize(stream, reserved7); 00138 return stream.getData(); 00139 } 00140 00141 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00142 { 00143 ros::serialization::IStream stream(read_ptr, 1000000000); 00144 ros::serialization::deserialize(stream, transaction); 00145 ros::serialization::deserialize(stream, dmi_scale_factor); 00146 ros::serialization::deserialize(stream, dmi_lever_arm); 00147 ros::serialization::deserialize(stream, reserved1); 00148 ros::serialization::deserialize(stream, reserved2); 00149 ros::serialization::deserialize(stream, reserved3); 00150 ros::serialization::deserialize(stream, reserved5); 00151 ros::serialization::deserialize(stream, reserved6); 00152 ros::serialization::deserialize(stream, reserved7); 00153 return stream.getData(); 00154 } 00155 00156 ROS_DEPRECATED virtual uint32_t serializationLength() const 00157 { 00158 uint32_t size = 0; 00159 size += ros::serialization::serializationLength(transaction); 00160 size += ros::serialization::serializationLength(dmi_scale_factor); 00161 size += ros::serialization::serializationLength(dmi_lever_arm); 00162 size += ros::serialization::serializationLength(reserved1); 00163 size += ros::serialization::serializationLength(reserved2); 00164 size += ros::serialization::serializationLength(reserved3); 00165 size += ros::serialization::serializationLength(reserved5); 00166 size += ros::serialization::serializationLength(reserved6); 00167 size += ros::serialization::serializationLength(reserved7); 00168 return size; 00169 } 00170 00171 typedef boost::shared_ptr< ::applanix_msgs::AidingSensorParams_<ContainerAllocator> > Ptr; 00172 typedef boost::shared_ptr< ::applanix_msgs::AidingSensorParams_<ContainerAllocator> const> ConstPtr; 00173 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00174 }; // struct AidingSensorParams 00175 typedef ::applanix_msgs::AidingSensorParams_<std::allocator<void> > AidingSensorParams; 00176 00177 typedef boost::shared_ptr< ::applanix_msgs::AidingSensorParams> AidingSensorParamsPtr; 00178 typedef boost::shared_ptr< ::applanix_msgs::AidingSensorParams const> AidingSensorParamsConstPtr; 00179 00180 00181 template<typename ContainerAllocator> 00182 std::ostream& operator<<(std::ostream& s, const ::applanix_msgs::AidingSensorParams_<ContainerAllocator> & v) 00183 { 00184 ros::message_operations::Printer< ::applanix_msgs::AidingSensorParams_<ContainerAllocator> >::stream(s, "", v); 00185 return s;} 00186 00187 } // namespace applanix_msgs 00188 00189 namespace ros 00190 { 00191 namespace message_traits 00192 { 00193 template<class ContainerAllocator> struct IsMessage< ::applanix_msgs::AidingSensorParams_<ContainerAllocator> > : public TrueType {}; 00194 template<class ContainerAllocator> struct IsMessage< ::applanix_msgs::AidingSensorParams_<ContainerAllocator> const> : public TrueType {}; 00195 template<class ContainerAllocator> 00196 struct MD5Sum< ::applanix_msgs::AidingSensorParams_<ContainerAllocator> > { 00197 static const char* value() 00198 { 00199 return "c5f8cdbc1fbfdcb4567e70396891f001"; 00200 } 00201 00202 static const char* value(const ::applanix_msgs::AidingSensorParams_<ContainerAllocator> &) { return value(); } 00203 static const uint64_t static_value1 = 0xc5f8cdbc1fbfdcb4ULL; 00204 static const uint64_t static_value2 = 0x567e70396891f001ULL; 00205 }; 00206 00207 template<class ContainerAllocator> 00208 struct DataType< ::applanix_msgs::AidingSensorParams_<ContainerAllocator> > { 00209 static const char* value() 00210 { 00211 return "applanix_msgs/AidingSensorParams"; 00212 } 00213 00214 static const char* value(const ::applanix_msgs::AidingSensorParams_<ContainerAllocator> &) { return value(); } 00215 }; 00216 00217 template<class ContainerAllocator> 00218 struct Definition< ::applanix_msgs::AidingSensorParams_<ContainerAllocator> > { 00219 static const char* value() 00220 { 00221 return "# Msg 22\n\ 00222 uint16 transaction\n\ 00223 \n\ 00224 float32 dmi_scale_factor\n\ 00225 geometry_msgs/Point32 dmi_lever_arm\n\ 00226 \n\ 00227 float32 reserved1\n\ 00228 float32 reserved2\n\ 00229 float32 reserved3\n\ 00230 float32 reserved5\n\ 00231 float32 reserved6\n\ 00232 float32 reserved7\n\ 00233 \n\ 00234 ================================================================================\n\ 00235 MSG: geometry_msgs/Point32\n\ 00236 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00237 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00238 # \n\ 00239 # This recommendation is to promote interoperability. \n\ 00240 #\n\ 00241 # This message is designed to take up less space when sending\n\ 00242 # lots of points at once, as in the case of a PointCloud. \n\ 00243 \n\ 00244 float32 x\n\ 00245 float32 y\n\ 00246 float32 z\n\ 00247 "; 00248 } 00249 00250 static const char* value(const ::applanix_msgs::AidingSensorParams_<ContainerAllocator> &) { return value(); } 00251 }; 00252 00253 template<class ContainerAllocator> struct IsFixedSize< ::applanix_msgs::AidingSensorParams_<ContainerAllocator> > : public TrueType {}; 00254 } // namespace message_traits 00255 } // namespace ros 00256 00257 namespace ros 00258 { 00259 namespace serialization 00260 { 00261 00262 template<class ContainerAllocator> struct Serializer< ::applanix_msgs::AidingSensorParams_<ContainerAllocator> > 00263 { 00264 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00265 { 00266 stream.next(m.transaction); 00267 stream.next(m.dmi_scale_factor); 00268 stream.next(m.dmi_lever_arm); 00269 stream.next(m.reserved1); 00270 stream.next(m.reserved2); 00271 stream.next(m.reserved3); 00272 stream.next(m.reserved5); 00273 stream.next(m.reserved6); 00274 stream.next(m.reserved7); 00275 } 00276 00277 ROS_DECLARE_ALLINONE_SERIALIZER; 00278 }; // struct AidingSensorParams_ 00279 } // namespace serialization 00280 } // namespace ros 00281 00282 namespace ros 00283 { 00284 namespace message_operations 00285 { 00286 00287 template<class ContainerAllocator> 00288 struct Printer< ::applanix_msgs::AidingSensorParams_<ContainerAllocator> > 00289 { 00290 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::applanix_msgs::AidingSensorParams_<ContainerAllocator> & v) 00291 { 00292 s << indent << "transaction: "; 00293 Printer<uint16_t>::stream(s, indent + " ", v.transaction); 00294 s << indent << "dmi_scale_factor: "; 00295 Printer<float>::stream(s, indent + " ", v.dmi_scale_factor); 00296 s << indent << "dmi_lever_arm: "; 00297 s << std::endl; 00298 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.dmi_lever_arm); 00299 s << indent << "reserved1: "; 00300 Printer<float>::stream(s, indent + " ", v.reserved1); 00301 s << indent << "reserved2: "; 00302 Printer<float>::stream(s, indent + " ", v.reserved2); 00303 s << indent << "reserved3: "; 00304 Printer<float>::stream(s, indent + " ", v.reserved3); 00305 s << indent << "reserved5: "; 00306 Printer<float>::stream(s, indent + " ", v.reserved5); 00307 s << indent << "reserved6: "; 00308 Printer<float>::stream(s, indent + " ", v.reserved6); 00309 s << indent << "reserved7: "; 00310 Printer<float>::stream(s, indent + " ", v.reserved7); 00311 } 00312 }; 00313 00314 00315 } // namespace message_operations 00316 } // namespace ros 00317 00318 #endif // APPLANIX_MSGS_MESSAGE_AIDINGSENSORPARAMS_H 00319