GeneralParams.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-fuerte-applanix_driver/doc_stacks/2014-01-02_11-02-36.446834/applanix_driver/applanix_msgs/msg/GeneralParams.msg */
00002 #ifndef APPLANIX_MSGS_MESSAGE_GENERALPARAMS_H
00003 #define APPLANIX_MSGS_MESSAGE_GENERALPARAMS_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 #include "geometry_msgs/Point32.h"
00019 #include "geometry_msgs/Point32.h"
00020 #include "geometry_msgs/Point32.h"
00021 #include "geometry_msgs/Point32.h"
00022 #include "geometry_msgs/Point32.h"
00023 
00024 namespace applanix_msgs
00025 {
00026 template <class ContainerAllocator>
00027 struct GeneralParams_ {
00028   typedef GeneralParams_<ContainerAllocator> Type;
00029 
00030   GeneralParams_()
00031   : transaction(0)
00032   , time_types(0)
00033   , distance_type(0)
00034   , autostart(0)
00035   , imu_lever_arm()
00036   , primary_gnss_lever_arm()
00037   , aux_1_gnss_lever_arm()
00038   , aux_2_gnss_lever_arm()
00039   , imu_mounting_angle()
00040   , ref_mounting_angle()
00041   , multipath(0)
00042   {
00043   }
00044 
00045   GeneralParams_(const ContainerAllocator& _alloc)
00046   : transaction(0)
00047   , time_types(0)
00048   , distance_type(0)
00049   , autostart(0)
00050   , imu_lever_arm(_alloc)
00051   , primary_gnss_lever_arm(_alloc)
00052   , aux_1_gnss_lever_arm(_alloc)
00053   , aux_2_gnss_lever_arm(_alloc)
00054   , imu_mounting_angle(_alloc)
00055   , ref_mounting_angle(_alloc)
00056   , multipath(0)
00057   {
00058   }
00059 
00060   typedef uint16_t _transaction_type;
00061   uint16_t transaction;
00062 
00063   typedef uint8_t _time_types_type;
00064   uint8_t time_types;
00065 
00066   typedef uint8_t _distance_type_type;
00067   uint8_t distance_type;
00068 
00069   typedef uint8_t _autostart_type;
00070   uint8_t autostart;
00071 
00072   typedef  ::geometry_msgs::Point32_<ContainerAllocator>  _imu_lever_arm_type;
00073    ::geometry_msgs::Point32_<ContainerAllocator>  imu_lever_arm;
00074 
00075   typedef  ::geometry_msgs::Point32_<ContainerAllocator>  _primary_gnss_lever_arm_type;
00076    ::geometry_msgs::Point32_<ContainerAllocator>  primary_gnss_lever_arm;
00077 
00078   typedef  ::geometry_msgs::Point32_<ContainerAllocator>  _aux_1_gnss_lever_arm_type;
00079    ::geometry_msgs::Point32_<ContainerAllocator>  aux_1_gnss_lever_arm;
00080 
00081   typedef  ::geometry_msgs::Point32_<ContainerAllocator>  _aux_2_gnss_lever_arm_type;
00082    ::geometry_msgs::Point32_<ContainerAllocator>  aux_2_gnss_lever_arm;
00083 
00084   typedef  ::geometry_msgs::Point32_<ContainerAllocator>  _imu_mounting_angle_type;
00085    ::geometry_msgs::Point32_<ContainerAllocator>  imu_mounting_angle;
00086 
00087   typedef  ::geometry_msgs::Point32_<ContainerAllocator>  _ref_mounting_angle_type;
00088    ::geometry_msgs::Point32_<ContainerAllocator>  ref_mounting_angle;
00089 
00090   typedef uint8_t _multipath_type;
00091   uint8_t multipath;
00092 
00093   enum { MULTIPATH_LOW = 0 };
00094   enum { MULTIPATH_MEDIUM = 1 };
00095   enum { MULTIPATH_HIGH = 2 };
00096 
00097   typedef boost::shared_ptr< ::applanix_msgs::GeneralParams_<ContainerAllocator> > Ptr;
00098   typedef boost::shared_ptr< ::applanix_msgs::GeneralParams_<ContainerAllocator>  const> ConstPtr;
00099   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00100 }; // struct GeneralParams
00101 typedef  ::applanix_msgs::GeneralParams_<std::allocator<void> > GeneralParams;
00102 
00103 typedef boost::shared_ptr< ::applanix_msgs::GeneralParams> GeneralParamsPtr;
00104 typedef boost::shared_ptr< ::applanix_msgs::GeneralParams const> GeneralParamsConstPtr;
00105 
00106 
00107 template<typename ContainerAllocator>
00108 std::ostream& operator<<(std::ostream& s, const  ::applanix_msgs::GeneralParams_<ContainerAllocator> & v)
00109 {
00110   ros::message_operations::Printer< ::applanix_msgs::GeneralParams_<ContainerAllocator> >::stream(s, "", v);
00111   return s;}
00112 
00113 } // namespace applanix_msgs
00114 
00115 namespace ros
00116 {
00117 namespace message_traits
00118 {
00119 template<class ContainerAllocator> struct IsMessage< ::applanix_msgs::GeneralParams_<ContainerAllocator> > : public TrueType {};
00120 template<class ContainerAllocator> struct IsMessage< ::applanix_msgs::GeneralParams_<ContainerAllocator>  const> : public TrueType {};
00121 template<class ContainerAllocator>
00122 struct MD5Sum< ::applanix_msgs::GeneralParams_<ContainerAllocator> > {
00123   static const char* value() 
00124   {
00125     return "dd32351725c9c39d1131c0be17b24a7b";
00126   }
00127 
00128   static const char* value(const  ::applanix_msgs::GeneralParams_<ContainerAllocator> &) { return value(); } 
00129   static const uint64_t static_value1 = 0xdd32351725c9c39dULL;
00130   static const uint64_t static_value2 = 0x1131c0be17b24a7bULL;
00131 };
00132 
00133 template<class ContainerAllocator>
00134 struct DataType< ::applanix_msgs::GeneralParams_<ContainerAllocator> > {
00135   static const char* value() 
00136   {
00137     return "applanix_msgs/GeneralParams";
00138   }
00139 
00140   static const char* value(const  ::applanix_msgs::GeneralParams_<ContainerAllocator> &) { return value(); } 
00141 };
00142 
00143 template<class ContainerAllocator>
00144 struct Definition< ::applanix_msgs::GeneralParams_<ContainerAllocator> > {
00145   static const char* value() 
00146   {
00147     return "# Msg 20\n\
00148 uint16 transaction\n\
00149 \n\
00150 uint8 time_types\n\
00151 uint8 distance_type\n\
00152 uint8 autostart\n\
00153 \n\
00154 geometry_msgs/Point32 imu_lever_arm\n\
00155 geometry_msgs/Point32 primary_gnss_lever_arm\n\
00156 geometry_msgs/Point32 aux_1_gnss_lever_arm\n\
00157 geometry_msgs/Point32 aux_2_gnss_lever_arm\n\
00158 geometry_msgs/Point32 imu_mounting_angle\n\
00159 geometry_msgs/Point32 ref_mounting_angle\n\
00160 \n\
00161 uint8 MULTIPATH_LOW=0\n\
00162 uint8 MULTIPATH_MEDIUM=1\n\
00163 uint8 MULTIPATH_HIGH=2\n\
00164 uint8 multipath\n\
00165 \n\
00166 ================================================================================\n\
00167 MSG: geometry_msgs/Point32\n\
00168 # This contains the position of a point in free space(with 32 bits of precision).\n\
00169 # It is recommeded to use Point wherever possible instead of Point32.  \n\
00170 # \n\
00171 # This recommendation is to promote interoperability.  \n\
00172 #\n\
00173 # This message is designed to take up less space when sending\n\
00174 # lots of points at once, as in the case of a PointCloud.  \n\
00175 \n\
00176 float32 x\n\
00177 float32 y\n\
00178 float32 z\n\
00179 ";
00180   }
00181 
00182   static const char* value(const  ::applanix_msgs::GeneralParams_<ContainerAllocator> &) { return value(); } 
00183 };
00184 
00185 template<class ContainerAllocator> struct IsFixedSize< ::applanix_msgs::GeneralParams_<ContainerAllocator> > : public TrueType {};
00186 } // namespace message_traits
00187 } // namespace ros
00188 
00189 namespace ros
00190 {
00191 namespace serialization
00192 {
00193 
00194 template<class ContainerAllocator> struct Serializer< ::applanix_msgs::GeneralParams_<ContainerAllocator> >
00195 {
00196   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00197   {
00198     stream.next(m.transaction);
00199     stream.next(m.time_types);
00200     stream.next(m.distance_type);
00201     stream.next(m.autostart);
00202     stream.next(m.imu_lever_arm);
00203     stream.next(m.primary_gnss_lever_arm);
00204     stream.next(m.aux_1_gnss_lever_arm);
00205     stream.next(m.aux_2_gnss_lever_arm);
00206     stream.next(m.imu_mounting_angle);
00207     stream.next(m.ref_mounting_angle);
00208     stream.next(m.multipath);
00209   }
00210 
00211   ROS_DECLARE_ALLINONE_SERIALIZER;
00212 }; // struct GeneralParams_
00213 } // namespace serialization
00214 } // namespace ros
00215 
00216 namespace ros
00217 {
00218 namespace message_operations
00219 {
00220 
00221 template<class ContainerAllocator>
00222 struct Printer< ::applanix_msgs::GeneralParams_<ContainerAllocator> >
00223 {
00224   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::applanix_msgs::GeneralParams_<ContainerAllocator> & v) 
00225   {
00226     s << indent << "transaction: ";
00227     Printer<uint16_t>::stream(s, indent + "  ", v.transaction);
00228     s << indent << "time_types: ";
00229     Printer<uint8_t>::stream(s, indent + "  ", v.time_types);
00230     s << indent << "distance_type: ";
00231     Printer<uint8_t>::stream(s, indent + "  ", v.distance_type);
00232     s << indent << "autostart: ";
00233     Printer<uint8_t>::stream(s, indent + "  ", v.autostart);
00234     s << indent << "imu_lever_arm: ";
00235 s << std::endl;
00236     Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + "  ", v.imu_lever_arm);
00237     s << indent << "primary_gnss_lever_arm: ";
00238 s << std::endl;
00239     Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + "  ", v.primary_gnss_lever_arm);
00240     s << indent << "aux_1_gnss_lever_arm: ";
00241 s << std::endl;
00242     Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + "  ", v.aux_1_gnss_lever_arm);
00243     s << indent << "aux_2_gnss_lever_arm: ";
00244 s << std::endl;
00245     Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + "  ", v.aux_2_gnss_lever_arm);
00246     s << indent << "imu_mounting_angle: ";
00247 s << std::endl;
00248     Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + "  ", v.imu_mounting_angle);
00249     s << indent << "ref_mounting_angle: ";
00250 s << std::endl;
00251     Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + "  ", v.ref_mounting_angle);
00252     s << indent << "multipath: ";
00253     Printer<uint8_t>::stream(s, indent + "  ", v.multipath);
00254   }
00255 };
00256 
00257 
00258 } // namespace message_operations
00259 } // namespace ros
00260 
00261 #endif // APPLANIX_MSGS_MESSAGE_GENERALPARAMS_H
00262 


applanix_msgs
Author(s): Mike Purvis
autogenerated on Thu Jan 2 2014 11:04:51