modify for Hydro version

Dependencies:   MODSERIAL

Fork of rosserial_mbed_lib by nucho

Committer:
jjzak
Date:
Sat Oct 26 15:39:01 2013 +0000
Revision:
6:3c54bc7badd4
modify for Hydro version;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
jjzak 6:3c54bc7badd4 1 #ifndef _ROS_sensor_msgs_NavSatStatus_h
jjzak 6:3c54bc7badd4 2 #define _ROS_sensor_msgs_NavSatStatus_h
jjzak 6:3c54bc7badd4 3
jjzak 6:3c54bc7badd4 4 #include <stdint.h>
jjzak 6:3c54bc7badd4 5 #include <string.h>
jjzak 6:3c54bc7badd4 6 #include <stdlib.h>
jjzak 6:3c54bc7badd4 7 #include "ros/msg.h"
jjzak 6:3c54bc7badd4 8
jjzak 6:3c54bc7badd4 9 namespace sensor_msgs
jjzak 6:3c54bc7badd4 10 {
jjzak 6:3c54bc7badd4 11
jjzak 6:3c54bc7badd4 12 class NavSatStatus : public ros::Msg
jjzak 6:3c54bc7badd4 13 {
jjzak 6:3c54bc7badd4 14 public:
jjzak 6:3c54bc7badd4 15 int8_t status;
jjzak 6:3c54bc7badd4 16 uint16_t service;
jjzak 6:3c54bc7badd4 17 enum { STATUS_NO_FIX = -1 };
jjzak 6:3c54bc7badd4 18 enum { STATUS_FIX = 0 };
jjzak 6:3c54bc7badd4 19 enum { STATUS_SBAS_FIX = 1 };
jjzak 6:3c54bc7badd4 20 enum { STATUS_GBAS_FIX = 2 };
jjzak 6:3c54bc7badd4 21 enum { SERVICE_GPS = 1 };
jjzak 6:3c54bc7badd4 22 enum { SERVICE_GLONASS = 2 };
jjzak 6:3c54bc7badd4 23 enum { SERVICE_COMPASS = 4 };
jjzak 6:3c54bc7badd4 24 enum { SERVICE_GALILEO = 8 };
jjzak 6:3c54bc7badd4 25
jjzak 6:3c54bc7badd4 26 virtual int serialize(unsigned char *outbuffer) const
jjzak 6:3c54bc7badd4 27 {
jjzak 6:3c54bc7badd4 28 int offset = 0;
jjzak 6:3c54bc7badd4 29 union {
jjzak 6:3c54bc7badd4 30 int8_t real;
jjzak 6:3c54bc7badd4 31 uint8_t base;
jjzak 6:3c54bc7badd4 32 } u_status;
jjzak 6:3c54bc7badd4 33 u_status.real = this->status;
jjzak 6:3c54bc7badd4 34 *(outbuffer + offset + 0) = (u_status.base >> (8 * 0)) & 0xFF;
jjzak 6:3c54bc7badd4 35 offset += sizeof(this->status);
jjzak 6:3c54bc7badd4 36 *(outbuffer + offset + 0) = (this->service >> (8 * 0)) & 0xFF;
jjzak 6:3c54bc7badd4 37 *(outbuffer + offset + 1) = (this->service >> (8 * 1)) & 0xFF;
jjzak 6:3c54bc7badd4 38 offset += sizeof(this->service);
jjzak 6:3c54bc7badd4 39 return offset;
jjzak 6:3c54bc7badd4 40 }
jjzak 6:3c54bc7badd4 41
jjzak 6:3c54bc7badd4 42 virtual int deserialize(unsigned char *inbuffer)
jjzak 6:3c54bc7badd4 43 {
jjzak 6:3c54bc7badd4 44 int offset = 0;
jjzak 6:3c54bc7badd4 45 union {
jjzak 6:3c54bc7badd4 46 int8_t real;
jjzak 6:3c54bc7badd4 47 uint8_t base;
jjzak 6:3c54bc7badd4 48 } u_status;
jjzak 6:3c54bc7badd4 49 u_status.base = 0;
jjzak 6:3c54bc7badd4 50 u_status.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
jjzak 6:3c54bc7badd4 51 this->status = u_status.real;
jjzak 6:3c54bc7badd4 52 offset += sizeof(this->status);
jjzak 6:3c54bc7badd4 53 this->service = ((uint16_t) (*(inbuffer + offset)));
jjzak 6:3c54bc7badd4 54 this->service |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
jjzak 6:3c54bc7badd4 55 offset += sizeof(this->service);
jjzak 6:3c54bc7badd4 56 return offset;
jjzak 6:3c54bc7badd4 57 }
jjzak 6:3c54bc7badd4 58
jjzak 6:3c54bc7badd4 59 const char * getType(){ return "sensor_msgs/NavSatStatus"; };
jjzak 6:3c54bc7badd4 60 const char * getMD5(){ return "331cdbddfa4bc96ffc3b9ad98900a54c"; };
jjzak 6:3c54bc7badd4 61
jjzak 6:3c54bc7badd4 62 };
jjzak 6:3c54bc7badd4 63
jjzak 6:3c54bc7badd4 64 }
jjzak 6:3c54bc7badd4 65 #endif