00001
00002 #ifndef COLLVOID_MSGS_MESSAGE_COLLVOID_DEBUG_H
00003 #define COLLVOID_MSGS_MESSAGE_COLLVOID_DEBUG_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/Twist.h"
00019 #include "geometry_msgs/Vector3Stamped.h"
00020 #include "nav_msgs/Odometry.h"
00021 #include "nav_msgs/Odometry.h"
00022 #include "geometry_msgs/PoseStamped.h"
00023
00024 namespace collvoid_msgs
00025 {
00026 template <class ContainerAllocator>
00027 struct collvoid_debug_ {
00028 typedef collvoid_debug_<ContainerAllocator> Type;
00029
00030 collvoid_debug_()
00031 : header()
00032 , run(0)
00033 , cmd_vel()
00034 , holo_vel()
00035 , odom()
00036 , ground_truth()
00037 , located_pose()
00038 , loc_error(0.0)
00039 , radius_uncertainty(0.0)
00040 {
00041 }
00042
00043 collvoid_debug_(const ContainerAllocator& _alloc)
00044 : header(_alloc)
00045 , run(0)
00046 , cmd_vel(_alloc)
00047 , holo_vel(_alloc)
00048 , odom(_alloc)
00049 , ground_truth(_alloc)
00050 , located_pose(_alloc)
00051 , loc_error(0.0)
00052 , radius_uncertainty(0.0)
00053 {
00054 }
00055
00056 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00057 ::std_msgs::Header_<ContainerAllocator> header;
00058
00059 typedef int32_t _run_type;
00060 int32_t run;
00061
00062 typedef ::geometry_msgs::Twist_<ContainerAllocator> _cmd_vel_type;
00063 ::geometry_msgs::Twist_<ContainerAllocator> cmd_vel;
00064
00065 typedef ::geometry_msgs::Vector3Stamped_<ContainerAllocator> _holo_vel_type;
00066 ::geometry_msgs::Vector3Stamped_<ContainerAllocator> holo_vel;
00067
00068 typedef ::nav_msgs::Odometry_<ContainerAllocator> _odom_type;
00069 ::nav_msgs::Odometry_<ContainerAllocator> odom;
00070
00071 typedef ::nav_msgs::Odometry_<ContainerAllocator> _ground_truth_type;
00072 ::nav_msgs::Odometry_<ContainerAllocator> ground_truth;
00073
00074 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _located_pose_type;
00075 ::geometry_msgs::PoseStamped_<ContainerAllocator> located_pose;
00076
00077 typedef float _loc_error_type;
00078 float loc_error;
00079
00080 typedef float _radius_uncertainty_type;
00081 float radius_uncertainty;
00082
00083
00084 typedef boost::shared_ptr< ::collvoid_msgs::collvoid_debug_<ContainerAllocator> > Ptr;
00085 typedef boost::shared_ptr< ::collvoid_msgs::collvoid_debug_<ContainerAllocator> const> ConstPtr;
00086 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00087 };
00088 typedef ::collvoid_msgs::collvoid_debug_<std::allocator<void> > collvoid_debug;
00089
00090 typedef boost::shared_ptr< ::collvoid_msgs::collvoid_debug> collvoid_debugPtr;
00091 typedef boost::shared_ptr< ::collvoid_msgs::collvoid_debug const> collvoid_debugConstPtr;
00092
00093
00094 template<typename ContainerAllocator>
00095 std::ostream& operator<<(std::ostream& s, const ::collvoid_msgs::collvoid_debug_<ContainerAllocator> & v)
00096 {
00097 ros::message_operations::Printer< ::collvoid_msgs::collvoid_debug_<ContainerAllocator> >::stream(s, "", v);
00098 return s;}
00099
00100 }
00101
00102 namespace ros
00103 {
00104 namespace message_traits
00105 {
00106 template<class ContainerAllocator> struct IsMessage< ::collvoid_msgs::collvoid_debug_<ContainerAllocator> > : public TrueType {};
00107 template<class ContainerAllocator> struct IsMessage< ::collvoid_msgs::collvoid_debug_<ContainerAllocator> const> : public TrueType {};
00108 template<class ContainerAllocator>
00109 struct MD5Sum< ::collvoid_msgs::collvoid_debug_<ContainerAllocator> > {
00110 static const char* value()
00111 {
00112 return "a304cee99f1657d40961f7cc6bca76f7";
00113 }
00114
00115 static const char* value(const ::collvoid_msgs::collvoid_debug_<ContainerAllocator> &) { return value(); }
00116 static const uint64_t static_value1 = 0xa304cee99f1657d4ULL;
00117 static const uint64_t static_value2 = 0x0961f7cc6bca76f7ULL;
00118 };
00119
00120 template<class ContainerAllocator>
00121 struct DataType< ::collvoid_msgs::collvoid_debug_<ContainerAllocator> > {
00122 static const char* value()
00123 {
00124 return "collvoid_msgs/collvoid_debug";
00125 }
00126
00127 static const char* value(const ::collvoid_msgs::collvoid_debug_<ContainerAllocator> &) { return value(); }
00128 };
00129
00130 template<class ContainerAllocator>
00131 struct Definition< ::collvoid_msgs::collvoid_debug_<ContainerAllocator> > {
00132 static const char* value()
00133 {
00134 return "Header header\n\
00135 int32 run\n\
00136 geometry_msgs/Twist cmd_vel\n\
00137 geometry_msgs/Vector3Stamped holo_vel\n\
00138 nav_msgs/Odometry odom\n\
00139 nav_msgs/Odometry ground_truth\n\
00140 geometry_msgs/PoseStamped located_pose\n\
00141 float32 loc_error\n\
00142 float32 radius_uncertainty\n\
00143 ================================================================================\n\
00144 MSG: std_msgs/Header\n\
00145 # Standard metadata for higher-level stamped data types.\n\
00146 # This is generally used to communicate timestamped data \n\
00147 # in a particular coordinate frame.\n\
00148 # \n\
00149 # sequence ID: consecutively increasing ID \n\
00150 uint32 seq\n\
00151 #Two-integer timestamp that is expressed as:\n\
00152 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00153 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00154 # time-handling sugar is provided by the client library\n\
00155 time stamp\n\
00156 #Frame this data is associated with\n\
00157 # 0: no frame\n\
00158 # 1: global frame\n\
00159 string frame_id\n\
00160 \n\
00161 ================================================================================\n\
00162 MSG: geometry_msgs/Twist\n\
00163 # This expresses velocity in free space broken into it's linear and angular parts. \n\
00164 Vector3 linear\n\
00165 Vector3 angular\n\
00166 \n\
00167 ================================================================================\n\
00168 MSG: geometry_msgs/Vector3\n\
00169 # This represents a vector in free space. \n\
00170 \n\
00171 float64 x\n\
00172 float64 y\n\
00173 float64 z\n\
00174 ================================================================================\n\
00175 MSG: geometry_msgs/Vector3Stamped\n\
00176 # This represents a Vector3 with reference coordinate frame and timestamp\n\
00177 Header header\n\
00178 Vector3 vector\n\
00179 \n\
00180 ================================================================================\n\
00181 MSG: nav_msgs/Odometry\n\
00182 # This represents an estimate of a position and velocity in free space. \n\
00183 # The pose in this message should be specified in the coordinate frame given by header.frame_id.\n\
00184 # The twist in this message should be specified in the coordinate frame given by the child_frame_id\n\
00185 Header header\n\
00186 string child_frame_id\n\
00187 geometry_msgs/PoseWithCovariance pose\n\
00188 geometry_msgs/TwistWithCovariance twist\n\
00189 \n\
00190 ================================================================================\n\
00191 MSG: geometry_msgs/PoseWithCovariance\n\
00192 # This represents a pose in free space with uncertainty.\n\
00193 \n\
00194 Pose pose\n\
00195 \n\
00196 # Row-major representation of the 6x6 covariance matrix\n\
00197 # The orientation parameters use a fixed-axis representation.\n\
00198 # In order, the parameters are:\n\
00199 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\
00200 float64[36] covariance\n\
00201 \n\
00202 ================================================================================\n\
00203 MSG: geometry_msgs/Pose\n\
00204 # A representation of pose in free space, composed of postion and orientation. \n\
00205 Point position\n\
00206 Quaternion orientation\n\
00207 \n\
00208 ================================================================================\n\
00209 MSG: geometry_msgs/Point\n\
00210 # This contains the position of a point in free space\n\
00211 float64 x\n\
00212 float64 y\n\
00213 float64 z\n\
00214 \n\
00215 ================================================================================\n\
00216 MSG: geometry_msgs/Quaternion\n\
00217 # This represents an orientation in free space in quaternion form.\n\
00218 \n\
00219 float64 x\n\
00220 float64 y\n\
00221 float64 z\n\
00222 float64 w\n\
00223 \n\
00224 ================================================================================\n\
00225 MSG: geometry_msgs/TwistWithCovariance\n\
00226 # This expresses velocity in free space with uncertianty.\n\
00227 \n\
00228 Twist twist\n\
00229 \n\
00230 # Row-major representation of the 6x6 covariance matrix\n\
00231 # The orientation parameters use a fixed-axis representation.\n\
00232 # In order, the parameters are:\n\
00233 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\
00234 float64[36] covariance\n\
00235 \n\
00236 ================================================================================\n\
00237 MSG: geometry_msgs/PoseStamped\n\
00238 # A Pose with reference coordinate frame and timestamp\n\
00239 Header header\n\
00240 Pose pose\n\
00241 \n\
00242 ";
00243 }
00244
00245 static const char* value(const ::collvoid_msgs::collvoid_debug_<ContainerAllocator> &) { return value(); }
00246 };
00247
00248 template<class ContainerAllocator> struct HasHeader< ::collvoid_msgs::collvoid_debug_<ContainerAllocator> > : public TrueType {};
00249 template<class ContainerAllocator> struct HasHeader< const ::collvoid_msgs::collvoid_debug_<ContainerAllocator> > : public TrueType {};
00250 }
00251 }
00252
00253 namespace ros
00254 {
00255 namespace serialization
00256 {
00257
00258 template<class ContainerAllocator> struct Serializer< ::collvoid_msgs::collvoid_debug_<ContainerAllocator> >
00259 {
00260 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00261 {
00262 stream.next(m.header);
00263 stream.next(m.run);
00264 stream.next(m.cmd_vel);
00265 stream.next(m.holo_vel);
00266 stream.next(m.odom);
00267 stream.next(m.ground_truth);
00268 stream.next(m.located_pose);
00269 stream.next(m.loc_error);
00270 stream.next(m.radius_uncertainty);
00271 }
00272
00273 ROS_DECLARE_ALLINONE_SERIALIZER;
00274 };
00275 }
00276 }
00277
00278 namespace ros
00279 {
00280 namespace message_operations
00281 {
00282
00283 template<class ContainerAllocator>
00284 struct Printer< ::collvoid_msgs::collvoid_debug_<ContainerAllocator> >
00285 {
00286 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::collvoid_msgs::collvoid_debug_<ContainerAllocator> & v)
00287 {
00288 s << indent << "header: ";
00289 s << std::endl;
00290 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00291 s << indent << "run: ";
00292 Printer<int32_t>::stream(s, indent + " ", v.run);
00293 s << indent << "cmd_vel: ";
00294 s << std::endl;
00295 Printer< ::geometry_msgs::Twist_<ContainerAllocator> >::stream(s, indent + " ", v.cmd_vel);
00296 s << indent << "holo_vel: ";
00297 s << std::endl;
00298 Printer< ::geometry_msgs::Vector3Stamped_<ContainerAllocator> >::stream(s, indent + " ", v.holo_vel);
00299 s << indent << "odom: ";
00300 s << std::endl;
00301 Printer< ::nav_msgs::Odometry_<ContainerAllocator> >::stream(s, indent + " ", v.odom);
00302 s << indent << "ground_truth: ";
00303 s << std::endl;
00304 Printer< ::nav_msgs::Odometry_<ContainerAllocator> >::stream(s, indent + " ", v.ground_truth);
00305 s << indent << "located_pose: ";
00306 s << std::endl;
00307 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.located_pose);
00308 s << indent << "loc_error: ";
00309 Printer<float>::stream(s, indent + " ", v.loc_error);
00310 s << indent << "radius_uncertainty: ";
00311 Printer<float>::stream(s, indent + " ", v.radius_uncertainty);
00312 }
00313 };
00314
00315
00316 }
00317 }
00318
00319 #endif // COLLVOID_MSGS_MESSAGE_COLLVOID_DEBUG_H
00320