00001
00002 #ifndef ASCTEC_MSGS_MESSAGE_IMUCALCDATA_H
00003 #define ASCTEC_MSGS_MESSAGE_IMUCALCDATA_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "std_msgs/Header.h"
00014
00015 namespace asctec_msgs
00016 {
00017 template <class ContainerAllocator>
00018 struct IMUCalcData_ : public ros::Message
00019 {
00020 typedef IMUCalcData_<ContainerAllocator> Type;
00021
00022 IMUCalcData_()
00023 : header()
00024 , angle_nick(0)
00025 , angle_roll(0)
00026 , angle_yaw(0)
00027 , angvel_nick(0)
00028 , angvel_roll(0)
00029 , angvel_yaw(0)
00030 , acc_x_calib(0)
00031 , acc_y_calib(0)
00032 , acc_z_calib(0)
00033 , acc_x(0)
00034 , acc_y(0)
00035 , acc_z(0)
00036 , acc_angle_nick(0)
00037 , acc_angle_roll(0)
00038 , acc_absolute_value(0)
00039 , Hx(0)
00040 , Hy(0)
00041 , Hz(0)
00042 , mag_heading(0)
00043 , speed_x(0)
00044 , speed_y(0)
00045 , speed_z(0)
00046 , height(0)
00047 , dheight(0)
00048 , dheight_reference(0)
00049 , height_reference(0)
00050 {
00051 }
00052
00053 IMUCalcData_(const ContainerAllocator& _alloc)
00054 : header(_alloc)
00055 , angle_nick(0)
00056 , angle_roll(0)
00057 , angle_yaw(0)
00058 , angvel_nick(0)
00059 , angvel_roll(0)
00060 , angvel_yaw(0)
00061 , acc_x_calib(0)
00062 , acc_y_calib(0)
00063 , acc_z_calib(0)
00064 , acc_x(0)
00065 , acc_y(0)
00066 , acc_z(0)
00067 , acc_angle_nick(0)
00068 , acc_angle_roll(0)
00069 , acc_absolute_value(0)
00070 , Hx(0)
00071 , Hy(0)
00072 , Hz(0)
00073 , mag_heading(0)
00074 , speed_x(0)
00075 , speed_y(0)
00076 , speed_z(0)
00077 , height(0)
00078 , dheight(0)
00079 , dheight_reference(0)
00080 , height_reference(0)
00081 {
00082 }
00083
00084 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00085 ::std_msgs::Header_<ContainerAllocator> header;
00086
00087 typedef int32_t _angle_nick_type;
00088 int32_t angle_nick;
00089
00090 typedef int32_t _angle_roll_type;
00091 int32_t angle_roll;
00092
00093 typedef int32_t _angle_yaw_type;
00094 int32_t angle_yaw;
00095
00096 typedef int32_t _angvel_nick_type;
00097 int32_t angvel_nick;
00098
00099 typedef int32_t _angvel_roll_type;
00100 int32_t angvel_roll;
00101
00102 typedef int32_t _angvel_yaw_type;
00103 int32_t angvel_yaw;
00104
00105 typedef int16_t _acc_x_calib_type;
00106 int16_t acc_x_calib;
00107
00108 typedef int16_t _acc_y_calib_type;
00109 int16_t acc_y_calib;
00110
00111 typedef int16_t _acc_z_calib_type;
00112 int16_t acc_z_calib;
00113
00114 typedef int16_t _acc_x_type;
00115 int16_t acc_x;
00116
00117 typedef int16_t _acc_y_type;
00118 int16_t acc_y;
00119
00120 typedef int16_t _acc_z_type;
00121 int16_t acc_z;
00122
00123 typedef int32_t _acc_angle_nick_type;
00124 int32_t acc_angle_nick;
00125
00126 typedef int32_t _acc_angle_roll_type;
00127 int32_t acc_angle_roll;
00128
00129 typedef int32_t _acc_absolute_value_type;
00130 int32_t acc_absolute_value;
00131
00132 typedef int32_t _Hx_type;
00133 int32_t Hx;
00134
00135 typedef int32_t _Hy_type;
00136 int32_t Hy;
00137
00138 typedef int32_t _Hz_type;
00139 int32_t Hz;
00140
00141 typedef int32_t _mag_heading_type;
00142 int32_t mag_heading;
00143
00144 typedef int32_t _speed_x_type;
00145 int32_t speed_x;
00146
00147 typedef int32_t _speed_y_type;
00148 int32_t speed_y;
00149
00150 typedef int32_t _speed_z_type;
00151 int32_t speed_z;
00152
00153 typedef int32_t _height_type;
00154 int32_t height;
00155
00156 typedef int32_t _dheight_type;
00157 int32_t dheight;
00158
00159 typedef int32_t _dheight_reference_type;
00160 int32_t dheight_reference;
00161
00162 typedef int32_t _height_reference_type;
00163 int32_t height_reference;
00164
00165
00166 private:
00167 static const char* __s_getDataType_() { return "asctec_msgs/IMUCalcData"; }
00168 public:
00169 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00170
00171 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00172
00173 private:
00174 static const char* __s_getMD5Sum_() { return "69fa9ec7b73af705eabe7dcbfd39ac85"; }
00175 public:
00176 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00177
00178 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00179
00180 private:
00181 static const char* __s_getMessageDefinition_() { return "# Software License Agreement (BSD License)\n\
00182 #\n\
00183 # Copyright (c) 2010\n\
00184 # William Morris <morris@ee.ccny.cuny.edu>\n\
00185 # Ivan Dryanovski <ivan.dryanovski@gmail.com>\n\
00186 # All rights reserved.\n\
00187 #\n\
00188 # Redistribution and use in source and binary forms, with or without\n\
00189 # modification, are permitted provided that the following conditions\n\
00190 # are met:\n\
00191 #\n\
00192 # * Redistributions of source code must retain the above copyright\n\
00193 # notice, this list of conditions and the following disclaimer.\n\
00194 # * Redistributions in binary form must reproduce the above\n\
00195 # copyright notice, this list of conditions and the following\n\
00196 # disclaimer in the documentation and/or other materials provided\n\
00197 # with the distribution.\n\
00198 # * Neither the name of CCNY Robotics Lab nor the names of its\n\
00199 # contributors may be used to endorse or promote products derived\n\
00200 # from this software without specific prior written permission.\n\
00201 #\n\
00202 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n\
00203 # \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n\
00204 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n\
00205 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n\
00206 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n\
00207 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n\
00208 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n\
00209 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n\
00210 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n\
00211 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n\
00212 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n\
00213 # POSSIBILITY OF SUCH DAMAGE.\n\
00214 \n\
00215 Header header\n\
00216 # angles derived by integration of gyro_outputs, drift compensated by data fusion;\n\
00217 #-90000..+90000 pitch(nick) and roll, 0..360000 yaw; 1000 = 1 degree\n\
00218 \n\
00219 int32 angle_nick\n\
00220 int32 angle_roll\n\
00221 int32 angle_yaw\n\
00222 \n\
00223 # angular velocities, raw values [16 bit], bias free, in 0.0154 degree/s (=> 64.8 = 1 degree/s)\n\
00224 \n\
00225 int32 angvel_nick\n\
00226 int32 angvel_roll\n\
00227 int32 angvel_yaw\n\
00228 \n\
00229 # acc-sensor outputs, calibrated: -10000..+10000 = -1g..+1g\n\
00230 \n\
00231 int16 acc_x_calib\n\
00232 int16 acc_y_calib\n\
00233 int16 acc_z_calib\n\
00234 \n\
00235 # horizontal / vertical accelerations: -10000..+10000 = -1g..+1g\n\
00236 \n\
00237 int16 acc_x\n\
00238 int16 acc_y\n\
00239 int16 acc_z\n\
00240 \n\
00241 # reference angles derived by accelerations only: -90000..+90000; 1000 = 1 degree\n\
00242 \n\
00243 int32 acc_angle_nick\n\
00244 int32 acc_angle_roll\n\
00245 \n\
00246 # total acceleration measured (10000 = 1g)\n\
00247 \n\
00248 int32 acc_absolute_value\n\
00249 \n\
00250 # magnetic field sensors output, offset free and scaled; units not determined, \n\
00251 # as only the direction of the field vector is taken into account\n\
00252 \n\
00253 int32 Hx\n\
00254 int32 Hy\n\
00255 int32 Hz\n\
00256 \n\
00257 # compass reading: angle reference for angle_yaw: 0..360000; 1000 = 1 degree\n\
00258 \n\
00259 int32 mag_heading\n\
00260 \n\
00261 # pseudo speed measurements: integrated accelerations, pulled towards zero; units unknown;\n\
00262 # used for short-term position stabilization\n\
00263 \n\
00264 int32 speed_x\n\
00265 int32 speed_y\n\
00266 int32 speed_z\n\
00267 \n\
00268 # height in mm (after data fusion)\n\
00269 \n\
00270 int32 height\n\
00271 \n\
00272 # diff. height in mm/s (after data fusion)\n\
00273 \n\
00274 int32 dheight\n\
00275 \n\
00276 # diff. height measured by the pressure sensor [mm/s]\n\
00277 \n\
00278 int32 dheight_reference\n\
00279 \n\
00280 # height measured by the pressure sensor [mm]\n\
00281 \n\
00282 int32 height_reference\n\
00283 \n\
00284 \n\
00285 ================================================================================\n\
00286 MSG: std_msgs/Header\n\
00287 # Standard metadata for higher-level stamped data types.\n\
00288 # This is generally used to communicate timestamped data \n\
00289 # in a particular coordinate frame.\n\
00290 # \n\
00291 # sequence ID: consecutively increasing ID \n\
00292 uint32 seq\n\
00293 #Two-integer timestamp that is expressed as:\n\
00294 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00295 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00296 # time-handling sugar is provided by the client library\n\
00297 time stamp\n\
00298 #Frame this data is associated with\n\
00299 # 0: no frame\n\
00300 # 1: global frame\n\
00301 string frame_id\n\
00302 \n\
00303 "; }
00304 public:
00305 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00306
00307 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00308
00309 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00310 {
00311 ros::serialization::OStream stream(write_ptr, 1000000000);
00312 ros::serialization::serialize(stream, header);
00313 ros::serialization::serialize(stream, angle_nick);
00314 ros::serialization::serialize(stream, angle_roll);
00315 ros::serialization::serialize(stream, angle_yaw);
00316 ros::serialization::serialize(stream, angvel_nick);
00317 ros::serialization::serialize(stream, angvel_roll);
00318 ros::serialization::serialize(stream, angvel_yaw);
00319 ros::serialization::serialize(stream, acc_x_calib);
00320 ros::serialization::serialize(stream, acc_y_calib);
00321 ros::serialization::serialize(stream, acc_z_calib);
00322 ros::serialization::serialize(stream, acc_x);
00323 ros::serialization::serialize(stream, acc_y);
00324 ros::serialization::serialize(stream, acc_z);
00325 ros::serialization::serialize(stream, acc_angle_nick);
00326 ros::serialization::serialize(stream, acc_angle_roll);
00327 ros::serialization::serialize(stream, acc_absolute_value);
00328 ros::serialization::serialize(stream, Hx);
00329 ros::serialization::serialize(stream, Hy);
00330 ros::serialization::serialize(stream, Hz);
00331 ros::serialization::serialize(stream, mag_heading);
00332 ros::serialization::serialize(stream, speed_x);
00333 ros::serialization::serialize(stream, speed_y);
00334 ros::serialization::serialize(stream, speed_z);
00335 ros::serialization::serialize(stream, height);
00336 ros::serialization::serialize(stream, dheight);
00337 ros::serialization::serialize(stream, dheight_reference);
00338 ros::serialization::serialize(stream, height_reference);
00339 return stream.getData();
00340 }
00341
00342 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00343 {
00344 ros::serialization::IStream stream(read_ptr, 1000000000);
00345 ros::serialization::deserialize(stream, header);
00346 ros::serialization::deserialize(stream, angle_nick);
00347 ros::serialization::deserialize(stream, angle_roll);
00348 ros::serialization::deserialize(stream, angle_yaw);
00349 ros::serialization::deserialize(stream, angvel_nick);
00350 ros::serialization::deserialize(stream, angvel_roll);
00351 ros::serialization::deserialize(stream, angvel_yaw);
00352 ros::serialization::deserialize(stream, acc_x_calib);
00353 ros::serialization::deserialize(stream, acc_y_calib);
00354 ros::serialization::deserialize(stream, acc_z_calib);
00355 ros::serialization::deserialize(stream, acc_x);
00356 ros::serialization::deserialize(stream, acc_y);
00357 ros::serialization::deserialize(stream, acc_z);
00358 ros::serialization::deserialize(stream, acc_angle_nick);
00359 ros::serialization::deserialize(stream, acc_angle_roll);
00360 ros::serialization::deserialize(stream, acc_absolute_value);
00361 ros::serialization::deserialize(stream, Hx);
00362 ros::serialization::deserialize(stream, Hy);
00363 ros::serialization::deserialize(stream, Hz);
00364 ros::serialization::deserialize(stream, mag_heading);
00365 ros::serialization::deserialize(stream, speed_x);
00366 ros::serialization::deserialize(stream, speed_y);
00367 ros::serialization::deserialize(stream, speed_z);
00368 ros::serialization::deserialize(stream, height);
00369 ros::serialization::deserialize(stream, dheight);
00370 ros::serialization::deserialize(stream, dheight_reference);
00371 ros::serialization::deserialize(stream, height_reference);
00372 return stream.getData();
00373 }
00374
00375 ROS_DEPRECATED virtual uint32_t serializationLength() const
00376 {
00377 uint32_t size = 0;
00378 size += ros::serialization::serializationLength(header);
00379 size += ros::serialization::serializationLength(angle_nick);
00380 size += ros::serialization::serializationLength(angle_roll);
00381 size += ros::serialization::serializationLength(angle_yaw);
00382 size += ros::serialization::serializationLength(angvel_nick);
00383 size += ros::serialization::serializationLength(angvel_roll);
00384 size += ros::serialization::serializationLength(angvel_yaw);
00385 size += ros::serialization::serializationLength(acc_x_calib);
00386 size += ros::serialization::serializationLength(acc_y_calib);
00387 size += ros::serialization::serializationLength(acc_z_calib);
00388 size += ros::serialization::serializationLength(acc_x);
00389 size += ros::serialization::serializationLength(acc_y);
00390 size += ros::serialization::serializationLength(acc_z);
00391 size += ros::serialization::serializationLength(acc_angle_nick);
00392 size += ros::serialization::serializationLength(acc_angle_roll);
00393 size += ros::serialization::serializationLength(acc_absolute_value);
00394 size += ros::serialization::serializationLength(Hx);
00395 size += ros::serialization::serializationLength(Hy);
00396 size += ros::serialization::serializationLength(Hz);
00397 size += ros::serialization::serializationLength(mag_heading);
00398 size += ros::serialization::serializationLength(speed_x);
00399 size += ros::serialization::serializationLength(speed_y);
00400 size += ros::serialization::serializationLength(speed_z);
00401 size += ros::serialization::serializationLength(height);
00402 size += ros::serialization::serializationLength(dheight);
00403 size += ros::serialization::serializationLength(dheight_reference);
00404 size += ros::serialization::serializationLength(height_reference);
00405 return size;
00406 }
00407
00408 typedef boost::shared_ptr< ::asctec_msgs::IMUCalcData_<ContainerAllocator> > Ptr;
00409 typedef boost::shared_ptr< ::asctec_msgs::IMUCalcData_<ContainerAllocator> const> ConstPtr;
00410 };
00411 typedef ::asctec_msgs::IMUCalcData_<std::allocator<void> > IMUCalcData;
00412
00413 typedef boost::shared_ptr< ::asctec_msgs::IMUCalcData> IMUCalcDataPtr;
00414 typedef boost::shared_ptr< ::asctec_msgs::IMUCalcData const> IMUCalcDataConstPtr;
00415
00416
00417 template<typename ContainerAllocator>
00418 std::ostream& operator<<(std::ostream& s, const ::asctec_msgs::IMUCalcData_<ContainerAllocator> & v)
00419 {
00420 ros::message_operations::Printer< ::asctec_msgs::IMUCalcData_<ContainerAllocator> >::stream(s, "", v);
00421 return s;}
00422
00423 }
00424
00425 namespace ros
00426 {
00427 namespace message_traits
00428 {
00429 template<class ContainerAllocator>
00430 struct MD5Sum< ::asctec_msgs::IMUCalcData_<ContainerAllocator> > {
00431 static const char* value()
00432 {
00433 return "69fa9ec7b73af705eabe7dcbfd39ac85";
00434 }
00435
00436 static const char* value(const ::asctec_msgs::IMUCalcData_<ContainerAllocator> &) { return value(); }
00437 static const uint64_t static_value1 = 0x69fa9ec7b73af705ULL;
00438 static const uint64_t static_value2 = 0xeabe7dcbfd39ac85ULL;
00439 };
00440
00441 template<class ContainerAllocator>
00442 struct DataType< ::asctec_msgs::IMUCalcData_<ContainerAllocator> > {
00443 static const char* value()
00444 {
00445 return "asctec_msgs/IMUCalcData";
00446 }
00447
00448 static const char* value(const ::asctec_msgs::IMUCalcData_<ContainerAllocator> &) { return value(); }
00449 };
00450
00451 template<class ContainerAllocator>
00452 struct Definition< ::asctec_msgs::IMUCalcData_<ContainerAllocator> > {
00453 static const char* value()
00454 {
00455 return "# Software License Agreement (BSD License)\n\
00456 #\n\
00457 # Copyright (c) 2010\n\
00458 # William Morris <morris@ee.ccny.cuny.edu>\n\
00459 # Ivan Dryanovski <ivan.dryanovski@gmail.com>\n\
00460 # All rights reserved.\n\
00461 #\n\
00462 # Redistribution and use in source and binary forms, with or without\n\
00463 # modification, are permitted provided that the following conditions\n\
00464 # are met:\n\
00465 #\n\
00466 # * Redistributions of source code must retain the above copyright\n\
00467 # notice, this list of conditions and the following disclaimer.\n\
00468 # * Redistributions in binary form must reproduce the above\n\
00469 # copyright notice, this list of conditions and the following\n\
00470 # disclaimer in the documentation and/or other materials provided\n\
00471 # with the distribution.\n\
00472 # * Neither the name of CCNY Robotics Lab nor the names of its\n\
00473 # contributors may be used to endorse or promote products derived\n\
00474 # from this software without specific prior written permission.\n\
00475 #\n\
00476 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n\
00477 # \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n\
00478 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n\
00479 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n\
00480 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n\
00481 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n\
00482 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n\
00483 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n\
00484 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n\
00485 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n\
00486 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n\
00487 # POSSIBILITY OF SUCH DAMAGE.\n\
00488 \n\
00489 Header header\n\
00490 # angles derived by integration of gyro_outputs, drift compensated by data fusion;\n\
00491 #-90000..+90000 pitch(nick) and roll, 0..360000 yaw; 1000 = 1 degree\n\
00492 \n\
00493 int32 angle_nick\n\
00494 int32 angle_roll\n\
00495 int32 angle_yaw\n\
00496 \n\
00497 # angular velocities, raw values [16 bit], bias free, in 0.0154 degree/s (=> 64.8 = 1 degree/s)\n\
00498 \n\
00499 int32 angvel_nick\n\
00500 int32 angvel_roll\n\
00501 int32 angvel_yaw\n\
00502 \n\
00503 # acc-sensor outputs, calibrated: -10000..+10000 = -1g..+1g\n\
00504 \n\
00505 int16 acc_x_calib\n\
00506 int16 acc_y_calib\n\
00507 int16 acc_z_calib\n\
00508 \n\
00509 # horizontal / vertical accelerations: -10000..+10000 = -1g..+1g\n\
00510 \n\
00511 int16 acc_x\n\
00512 int16 acc_y\n\
00513 int16 acc_z\n\
00514 \n\
00515 # reference angles derived by accelerations only: -90000..+90000; 1000 = 1 degree\n\
00516 \n\
00517 int32 acc_angle_nick\n\
00518 int32 acc_angle_roll\n\
00519 \n\
00520 # total acceleration measured (10000 = 1g)\n\
00521 \n\
00522 int32 acc_absolute_value\n\
00523 \n\
00524 # magnetic field sensors output, offset free and scaled; units not determined, \n\
00525 # as only the direction of the field vector is taken into account\n\
00526 \n\
00527 int32 Hx\n\
00528 int32 Hy\n\
00529 int32 Hz\n\
00530 \n\
00531 # compass reading: angle reference for angle_yaw: 0..360000; 1000 = 1 degree\n\
00532 \n\
00533 int32 mag_heading\n\
00534 \n\
00535 # pseudo speed measurements: integrated accelerations, pulled towards zero; units unknown;\n\
00536 # used for short-term position stabilization\n\
00537 \n\
00538 int32 speed_x\n\
00539 int32 speed_y\n\
00540 int32 speed_z\n\
00541 \n\
00542 # height in mm (after data fusion)\n\
00543 \n\
00544 int32 height\n\
00545 \n\
00546 # diff. height in mm/s (after data fusion)\n\
00547 \n\
00548 int32 dheight\n\
00549 \n\
00550 # diff. height measured by the pressure sensor [mm/s]\n\
00551 \n\
00552 int32 dheight_reference\n\
00553 \n\
00554 # height measured by the pressure sensor [mm]\n\
00555 \n\
00556 int32 height_reference\n\
00557 \n\
00558 \n\
00559 ================================================================================\n\
00560 MSG: std_msgs/Header\n\
00561 # Standard metadata for higher-level stamped data types.\n\
00562 # This is generally used to communicate timestamped data \n\
00563 # in a particular coordinate frame.\n\
00564 # \n\
00565 # sequence ID: consecutively increasing ID \n\
00566 uint32 seq\n\
00567 #Two-integer timestamp that is expressed as:\n\
00568 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00569 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00570 # time-handling sugar is provided by the client library\n\
00571 time stamp\n\
00572 #Frame this data is associated with\n\
00573 # 0: no frame\n\
00574 # 1: global frame\n\
00575 string frame_id\n\
00576 \n\
00577 ";
00578 }
00579
00580 static const char* value(const ::asctec_msgs::IMUCalcData_<ContainerAllocator> &) { return value(); }
00581 };
00582
00583 template<class ContainerAllocator> struct HasHeader< ::asctec_msgs::IMUCalcData_<ContainerAllocator> > : public TrueType {};
00584 template<class ContainerAllocator> struct HasHeader< const ::asctec_msgs::IMUCalcData_<ContainerAllocator> > : public TrueType {};
00585 }
00586 }
00587
00588 namespace ros
00589 {
00590 namespace serialization
00591 {
00592
00593 template<class ContainerAllocator> struct Serializer< ::asctec_msgs::IMUCalcData_<ContainerAllocator> >
00594 {
00595 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00596 {
00597 stream.next(m.header);
00598 stream.next(m.angle_nick);
00599 stream.next(m.angle_roll);
00600 stream.next(m.angle_yaw);
00601 stream.next(m.angvel_nick);
00602 stream.next(m.angvel_roll);
00603 stream.next(m.angvel_yaw);
00604 stream.next(m.acc_x_calib);
00605 stream.next(m.acc_y_calib);
00606 stream.next(m.acc_z_calib);
00607 stream.next(m.acc_x);
00608 stream.next(m.acc_y);
00609 stream.next(m.acc_z);
00610 stream.next(m.acc_angle_nick);
00611 stream.next(m.acc_angle_roll);
00612 stream.next(m.acc_absolute_value);
00613 stream.next(m.Hx);
00614 stream.next(m.Hy);
00615 stream.next(m.Hz);
00616 stream.next(m.mag_heading);
00617 stream.next(m.speed_x);
00618 stream.next(m.speed_y);
00619 stream.next(m.speed_z);
00620 stream.next(m.height);
00621 stream.next(m.dheight);
00622 stream.next(m.dheight_reference);
00623 stream.next(m.height_reference);
00624 }
00625
00626 ROS_DECLARE_ALLINONE_SERIALIZER;
00627 };
00628 }
00629 }
00630
00631 namespace ros
00632 {
00633 namespace message_operations
00634 {
00635
00636 template<class ContainerAllocator>
00637 struct Printer< ::asctec_msgs::IMUCalcData_<ContainerAllocator> >
00638 {
00639 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::asctec_msgs::IMUCalcData_<ContainerAllocator> & v)
00640 {
00641 s << indent << "header: ";
00642 s << std::endl;
00643 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00644 s << indent << "angle_nick: ";
00645 Printer<int32_t>::stream(s, indent + " ", v.angle_nick);
00646 s << indent << "angle_roll: ";
00647 Printer<int32_t>::stream(s, indent + " ", v.angle_roll);
00648 s << indent << "angle_yaw: ";
00649 Printer<int32_t>::stream(s, indent + " ", v.angle_yaw);
00650 s << indent << "angvel_nick: ";
00651 Printer<int32_t>::stream(s, indent + " ", v.angvel_nick);
00652 s << indent << "angvel_roll: ";
00653 Printer<int32_t>::stream(s, indent + " ", v.angvel_roll);
00654 s << indent << "angvel_yaw: ";
00655 Printer<int32_t>::stream(s, indent + " ", v.angvel_yaw);
00656 s << indent << "acc_x_calib: ";
00657 Printer<int16_t>::stream(s, indent + " ", v.acc_x_calib);
00658 s << indent << "acc_y_calib: ";
00659 Printer<int16_t>::stream(s, indent + " ", v.acc_y_calib);
00660 s << indent << "acc_z_calib: ";
00661 Printer<int16_t>::stream(s, indent + " ", v.acc_z_calib);
00662 s << indent << "acc_x: ";
00663 Printer<int16_t>::stream(s, indent + " ", v.acc_x);
00664 s << indent << "acc_y: ";
00665 Printer<int16_t>::stream(s, indent + " ", v.acc_y);
00666 s << indent << "acc_z: ";
00667 Printer<int16_t>::stream(s, indent + " ", v.acc_z);
00668 s << indent << "acc_angle_nick: ";
00669 Printer<int32_t>::stream(s, indent + " ", v.acc_angle_nick);
00670 s << indent << "acc_angle_roll: ";
00671 Printer<int32_t>::stream(s, indent + " ", v.acc_angle_roll);
00672 s << indent << "acc_absolute_value: ";
00673 Printer<int32_t>::stream(s, indent + " ", v.acc_absolute_value);
00674 s << indent << "Hx: ";
00675 Printer<int32_t>::stream(s, indent + " ", v.Hx);
00676 s << indent << "Hy: ";
00677 Printer<int32_t>::stream(s, indent + " ", v.Hy);
00678 s << indent << "Hz: ";
00679 Printer<int32_t>::stream(s, indent + " ", v.Hz);
00680 s << indent << "mag_heading: ";
00681 Printer<int32_t>::stream(s, indent + " ", v.mag_heading);
00682 s << indent << "speed_x: ";
00683 Printer<int32_t>::stream(s, indent + " ", v.speed_x);
00684 s << indent << "speed_y: ";
00685 Printer<int32_t>::stream(s, indent + " ", v.speed_y);
00686 s << indent << "speed_z: ";
00687 Printer<int32_t>::stream(s, indent + " ", v.speed_z);
00688 s << indent << "height: ";
00689 Printer<int32_t>::stream(s, indent + " ", v.height);
00690 s << indent << "dheight: ";
00691 Printer<int32_t>::stream(s, indent + " ", v.dheight);
00692 s << indent << "dheight_reference: ";
00693 Printer<int32_t>::stream(s, indent + " ", v.dheight_reference);
00694 s << indent << "height_reference: ";
00695 Printer<int32_t>::stream(s, indent + " ", v.height_reference);
00696 }
00697 };
00698
00699
00700 }
00701 }
00702
00703 #endif // ASCTEC_MSGS_MESSAGE_IMUCALCDATA_H
00704