00001
00002 #ifndef IRI_SEGWAY_RMP_MSGS_MESSAGE_SEGWAYRMP200STATUS_H
00003 #define IRI_SEGWAY_RMP_MSGS_MESSAGE_SEGWAYRMP200STATUS_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
00019 namespace iri_segway_rmp_msgs
00020 {
00021 template <class ContainerAllocator>
00022 struct SegwayRMP200Status_ {
00023 typedef SegwayRMP200Status_<ContainerAllocator> Type;
00024
00025 SegwayRMP200Status_()
00026 : header()
00027 , pitch_angle(0.0)
00028 , pitch_rate(0.0)
00029 , roll_angle(0.0)
00030 , roll_rate(0.0)
00031 , left_wheel_velocity(0.0)
00032 , right_wheel_velocity(0.0)
00033 , yaw_rate(0.0)
00034 , uptime(0.0)
00035 , left_wheel_displacement(0.0)
00036 , right_wheel_displacement(0.0)
00037 , forward_displacement(0.0)
00038 , yaw_displacement(0.0)
00039 , left_motor_torque(0.0)
00040 , right_motor_torque(0.0)
00041 , operation_mode(0)
00042 , gain_schedule(0)
00043 , ui_battery(0.0)
00044 , powerbase_battery(0.0)
00045 {
00046 }
00047
00048 SegwayRMP200Status_(const ContainerAllocator& _alloc)
00049 : header(_alloc)
00050 , pitch_angle(0.0)
00051 , pitch_rate(0.0)
00052 , roll_angle(0.0)
00053 , roll_rate(0.0)
00054 , left_wheel_velocity(0.0)
00055 , right_wheel_velocity(0.0)
00056 , yaw_rate(0.0)
00057 , uptime(0.0)
00058 , left_wheel_displacement(0.0)
00059 , right_wheel_displacement(0.0)
00060 , forward_displacement(0.0)
00061 , yaw_displacement(0.0)
00062 , left_motor_torque(0.0)
00063 , right_motor_torque(0.0)
00064 , operation_mode(0)
00065 , gain_schedule(0)
00066 , ui_battery(0.0)
00067 , powerbase_battery(0.0)
00068 {
00069 }
00070
00071 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00072 ::std_msgs::Header_<ContainerAllocator> header;
00073
00074 typedef float _pitch_angle_type;
00075 float pitch_angle;
00076
00077 typedef float _pitch_rate_type;
00078 float pitch_rate;
00079
00080 typedef float _roll_angle_type;
00081 float roll_angle;
00082
00083 typedef float _roll_rate_type;
00084 float roll_rate;
00085
00086 typedef float _left_wheel_velocity_type;
00087 float left_wheel_velocity;
00088
00089 typedef float _right_wheel_velocity_type;
00090 float right_wheel_velocity;
00091
00092 typedef float _yaw_rate_type;
00093 float yaw_rate;
00094
00095 typedef float _uptime_type;
00096 float uptime;
00097
00098 typedef float _left_wheel_displacement_type;
00099 float left_wheel_displacement;
00100
00101 typedef float _right_wheel_displacement_type;
00102 float right_wheel_displacement;
00103
00104 typedef float _forward_displacement_type;
00105 float forward_displacement;
00106
00107 typedef float _yaw_displacement_type;
00108 float yaw_displacement;
00109
00110 typedef float _left_motor_torque_type;
00111 float left_motor_torque;
00112
00113 typedef float _right_motor_torque_type;
00114 float right_motor_torque;
00115
00116 typedef int8_t _operation_mode_type;
00117 int8_t operation_mode;
00118
00119 typedef int8_t _gain_schedule_type;
00120 int8_t gain_schedule;
00121
00122 typedef float _ui_battery_type;
00123 float ui_battery;
00124
00125 typedef float _powerbase_battery_type;
00126 float powerbase_battery;
00127
00128
00129 typedef boost::shared_ptr< ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> > Ptr;
00130 typedef boost::shared_ptr< ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> const> ConstPtr;
00131 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00132 };
00133 typedef ::iri_segway_rmp_msgs::SegwayRMP200Status_<std::allocator<void> > SegwayRMP200Status;
00134
00135 typedef boost::shared_ptr< ::iri_segway_rmp_msgs::SegwayRMP200Status> SegwayRMP200StatusPtr;
00136 typedef boost::shared_ptr< ::iri_segway_rmp_msgs::SegwayRMP200Status const> SegwayRMP200StatusConstPtr;
00137
00138
00139 template<typename ContainerAllocator>
00140 std::ostream& operator<<(std::ostream& s, const ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> & v)
00141 {
00142 ros::message_operations::Printer< ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> >::stream(s, "", v);
00143 return s;}
00144
00145 }
00146
00147 namespace ros
00148 {
00149 namespace message_traits
00150 {
00151 template<class ContainerAllocator> struct IsMessage< ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> > : public TrueType {};
00152 template<class ContainerAllocator> struct IsMessage< ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> const> : public TrueType {};
00153 template<class ContainerAllocator>
00154 struct MD5Sum< ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> > {
00155 static const char* value()
00156 {
00157 return "ee83912171465b6bc0a6397a2c596ee1";
00158 }
00159
00160 static const char* value(const ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> &) { return value(); }
00161 static const uint64_t static_value1 = 0xee83912171465b6bULL;
00162 static const uint64_t static_value2 = 0xc0a6397a2c596ee1ULL;
00163 };
00164
00165 template<class ContainerAllocator>
00166 struct DataType< ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> > {
00167 static const char* value()
00168 {
00169 return "iri_segway_rmp_msgs/SegwayRMP200Status";
00170 }
00171
00172 static const char* value(const ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> &) { return value(); }
00173 };
00174
00175 template<class ContainerAllocator>
00176 struct Definition< ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> > {
00177 static const char* value()
00178 {
00179 return "Header header\n\
00180 float32 pitch_angle\n\
00181 float32 pitch_rate\n\
00182 float32 roll_angle\n\
00183 float32 roll_rate\n\
00184 float32 left_wheel_velocity\n\
00185 float32 right_wheel_velocity\n\
00186 float32 yaw_rate\n\
00187 float32 uptime\n\
00188 float32 left_wheel_displacement\n\
00189 float32 right_wheel_displacement\n\
00190 float32 forward_displacement\n\
00191 float32 yaw_displacement\n\
00192 float32 left_motor_torque\n\
00193 float32 right_motor_torque\n\
00194 int8 operation_mode\n\
00195 int8 gain_schedule\n\
00196 float32 ui_battery\n\
00197 float32 powerbase_battery\n\
00198 \n\
00199 ================================================================================\n\
00200 MSG: std_msgs/Header\n\
00201 # Standard metadata for higher-level stamped data types.\n\
00202 # This is generally used to communicate timestamped data \n\
00203 # in a particular coordinate frame.\n\
00204 # \n\
00205 # sequence ID: consecutively increasing ID \n\
00206 uint32 seq\n\
00207 #Two-integer timestamp that is expressed as:\n\
00208 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00209 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00210 # time-handling sugar is provided by the client library\n\
00211 time stamp\n\
00212 #Frame this data is associated with\n\
00213 # 0: no frame\n\
00214 # 1: global frame\n\
00215 string frame_id\n\
00216 \n\
00217 ";
00218 }
00219
00220 static const char* value(const ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> &) { return value(); }
00221 };
00222
00223 template<class ContainerAllocator> struct HasHeader< ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> > : public TrueType {};
00224 template<class ContainerAllocator> struct HasHeader< const ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> > : public TrueType {};
00225 }
00226 }
00227
00228 namespace ros
00229 {
00230 namespace serialization
00231 {
00232
00233 template<class ContainerAllocator> struct Serializer< ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> >
00234 {
00235 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00236 {
00237 stream.next(m.header);
00238 stream.next(m.pitch_angle);
00239 stream.next(m.pitch_rate);
00240 stream.next(m.roll_angle);
00241 stream.next(m.roll_rate);
00242 stream.next(m.left_wheel_velocity);
00243 stream.next(m.right_wheel_velocity);
00244 stream.next(m.yaw_rate);
00245 stream.next(m.uptime);
00246 stream.next(m.left_wheel_displacement);
00247 stream.next(m.right_wheel_displacement);
00248 stream.next(m.forward_displacement);
00249 stream.next(m.yaw_displacement);
00250 stream.next(m.left_motor_torque);
00251 stream.next(m.right_motor_torque);
00252 stream.next(m.operation_mode);
00253 stream.next(m.gain_schedule);
00254 stream.next(m.ui_battery);
00255 stream.next(m.powerbase_battery);
00256 }
00257
00258 ROS_DECLARE_ALLINONE_SERIALIZER;
00259 };
00260 }
00261 }
00262
00263 namespace ros
00264 {
00265 namespace message_operations
00266 {
00267
00268 template<class ContainerAllocator>
00269 struct Printer< ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> >
00270 {
00271 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::iri_segway_rmp_msgs::SegwayRMP200Status_<ContainerAllocator> & v)
00272 {
00273 s << indent << "header: ";
00274 s << std::endl;
00275 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00276 s << indent << "pitch_angle: ";
00277 Printer<float>::stream(s, indent + " ", v.pitch_angle);
00278 s << indent << "pitch_rate: ";
00279 Printer<float>::stream(s, indent + " ", v.pitch_rate);
00280 s << indent << "roll_angle: ";
00281 Printer<float>::stream(s, indent + " ", v.roll_angle);
00282 s << indent << "roll_rate: ";
00283 Printer<float>::stream(s, indent + " ", v.roll_rate);
00284 s << indent << "left_wheel_velocity: ";
00285 Printer<float>::stream(s, indent + " ", v.left_wheel_velocity);
00286 s << indent << "right_wheel_velocity: ";
00287 Printer<float>::stream(s, indent + " ", v.right_wheel_velocity);
00288 s << indent << "yaw_rate: ";
00289 Printer<float>::stream(s, indent + " ", v.yaw_rate);
00290 s << indent << "uptime: ";
00291 Printer<float>::stream(s, indent + " ", v.uptime);
00292 s << indent << "left_wheel_displacement: ";
00293 Printer<float>::stream(s, indent + " ", v.left_wheel_displacement);
00294 s << indent << "right_wheel_displacement: ";
00295 Printer<float>::stream(s, indent + " ", v.right_wheel_displacement);
00296 s << indent << "forward_displacement: ";
00297 Printer<float>::stream(s, indent + " ", v.forward_displacement);
00298 s << indent << "yaw_displacement: ";
00299 Printer<float>::stream(s, indent + " ", v.yaw_displacement);
00300 s << indent << "left_motor_torque: ";
00301 Printer<float>::stream(s, indent + " ", v.left_motor_torque);
00302 s << indent << "right_motor_torque: ";
00303 Printer<float>::stream(s, indent + " ", v.right_motor_torque);
00304 s << indent << "operation_mode: ";
00305 Printer<int8_t>::stream(s, indent + " ", v.operation_mode);
00306 s << indent << "gain_schedule: ";
00307 Printer<int8_t>::stream(s, indent + " ", v.gain_schedule);
00308 s << indent << "ui_battery: ";
00309 Printer<float>::stream(s, indent + " ", v.ui_battery);
00310 s << indent << "powerbase_battery: ";
00311 Printer<float>::stream(s, indent + " ", v.powerbase_battery);
00312 }
00313 };
00314
00315
00316 }
00317 }
00318
00319 #endif // IRI_SEGWAY_RMP_MSGS_MESSAGE_SEGWAYRMP200STATUS_H
00320