This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial.

Dependencies:  

Dependents:   rosserial_mbed robot_S2

Committer:
nucho
Date:
Wed Feb 29 23:00:21 2012 +0000
Revision:
4:684f39d0c346
Parent:
3:1cf99502f396

        

Who changed what in which revision?

UserRevisionLine numberNew contents of line
nucho 3:1cf99502f396 1 #ifndef _ROS_geometry_msgs_Point_h
nucho 3:1cf99502f396 2 #define _ROS_geometry_msgs_Point_h
nucho 0:77afd7560544 3
nucho 0:77afd7560544 4 #include <stdint.h>
nucho 0:77afd7560544 5 #include <string.h>
nucho 0:77afd7560544 6 #include <stdlib.h>
nucho 3:1cf99502f396 7 #include "ros/msg.h"
nucho 0:77afd7560544 8
nucho 3:1cf99502f396 9 namespace geometry_msgs
nucho 3:1cf99502f396 10 {
nucho 0:77afd7560544 11
nucho 3:1cf99502f396 12 class Point : public ros::Msg
nucho 3:1cf99502f396 13 {
nucho 3:1cf99502f396 14 public:
nucho 3:1cf99502f396 15 float x;
nucho 3:1cf99502f396 16 float y;
nucho 3:1cf99502f396 17 float z;
nucho 0:77afd7560544 18
nucho 3:1cf99502f396 19 virtual int serialize(unsigned char *outbuffer) const
nucho 3:1cf99502f396 20 {
nucho 3:1cf99502f396 21 int offset = 0;
nucho 3:1cf99502f396 22 int32_t * val_x = (long *) &(this->x);
nucho 3:1cf99502f396 23 int32_t exp_x = (((*val_x)>>23)&255);
nucho 3:1cf99502f396 24 if(exp_x != 0)
nucho 3:1cf99502f396 25 exp_x += 1023-127;
nucho 3:1cf99502f396 26 int32_t sig_x = *val_x;
nucho 3:1cf99502f396 27 *(outbuffer + offset++) = 0;
nucho 3:1cf99502f396 28 *(outbuffer + offset++) = 0;
nucho 3:1cf99502f396 29 *(outbuffer + offset++) = 0;
nucho 3:1cf99502f396 30 *(outbuffer + offset++) = (sig_x<<5) & 0xff;
nucho 3:1cf99502f396 31 *(outbuffer + offset++) = (sig_x>>3) & 0xff;
nucho 3:1cf99502f396 32 *(outbuffer + offset++) = (sig_x>>11) & 0xff;
nucho 3:1cf99502f396 33 *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F);
nucho 3:1cf99502f396 34 *(outbuffer + offset++) = (exp_x>>4) & 0x7F;
nucho 3:1cf99502f396 35 if(this->x < 0) *(outbuffer + offset -1) |= 0x80;
nucho 3:1cf99502f396 36 int32_t * val_y = (long *) &(this->y);
nucho 3:1cf99502f396 37 int32_t exp_y = (((*val_y)>>23)&255);
nucho 3:1cf99502f396 38 if(exp_y != 0)
nucho 3:1cf99502f396 39 exp_y += 1023-127;
nucho 3:1cf99502f396 40 int32_t sig_y = *val_y;
nucho 3:1cf99502f396 41 *(outbuffer + offset++) = 0;
nucho 3:1cf99502f396 42 *(outbuffer + offset++) = 0;
nucho 3:1cf99502f396 43 *(outbuffer + offset++) = 0;
nucho 3:1cf99502f396 44 *(outbuffer + offset++) = (sig_y<<5) & 0xff;
nucho 3:1cf99502f396 45 *(outbuffer + offset++) = (sig_y>>3) & 0xff;
nucho 3:1cf99502f396 46 *(outbuffer + offset++) = (sig_y>>11) & 0xff;
nucho 3:1cf99502f396 47 *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F);
nucho 3:1cf99502f396 48 *(outbuffer + offset++) = (exp_y>>4) & 0x7F;
nucho 3:1cf99502f396 49 if(this->y < 0) *(outbuffer + offset -1) |= 0x80;
nucho 3:1cf99502f396 50 int32_t * val_z = (long *) &(this->z);
nucho 3:1cf99502f396 51 int32_t exp_z = (((*val_z)>>23)&255);
nucho 3:1cf99502f396 52 if(exp_z != 0)
nucho 3:1cf99502f396 53 exp_z += 1023-127;
nucho 3:1cf99502f396 54 int32_t sig_z = *val_z;
nucho 3:1cf99502f396 55 *(outbuffer + offset++) = 0;
nucho 3:1cf99502f396 56 *(outbuffer + offset++) = 0;
nucho 3:1cf99502f396 57 *(outbuffer + offset++) = 0;
nucho 3:1cf99502f396 58 *(outbuffer + offset++) = (sig_z<<5) & 0xff;
nucho 3:1cf99502f396 59 *(outbuffer + offset++) = (sig_z>>3) & 0xff;
nucho 3:1cf99502f396 60 *(outbuffer + offset++) = (sig_z>>11) & 0xff;
nucho 3:1cf99502f396 61 *(outbuffer + offset++) = ((exp_z<<4) & 0xF0) | ((sig_z>>19)&0x0F);
nucho 3:1cf99502f396 62 *(outbuffer + offset++) = (exp_z>>4) & 0x7F;
nucho 3:1cf99502f396 63 if(this->z < 0) *(outbuffer + offset -1) |= 0x80;
nucho 3:1cf99502f396 64 return offset;
nucho 0:77afd7560544 65 }
nucho 0:77afd7560544 66
nucho 3:1cf99502f396 67 virtual int deserialize(unsigned char *inbuffer)
nucho 3:1cf99502f396 68 {
nucho 3:1cf99502f396 69 int offset = 0;
nucho 3:1cf99502f396 70 uint32_t * val_x = (uint32_t*) &(this->x);
nucho 3:1cf99502f396 71 offset += 3;
nucho 3:1cf99502f396 72 *val_x = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
nucho 3:1cf99502f396 73 *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
nucho 3:1cf99502f396 74 *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
nucho 3:1cf99502f396 75 *val_x |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
nucho 3:1cf99502f396 76 uint32_t exp_x = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
nucho 3:1cf99502f396 77 exp_x |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
nucho 3:1cf99502f396 78 if(exp_x !=0)
nucho 3:1cf99502f396 79 *val_x |= ((exp_x)-1023+127)<<23;
nucho 3:1cf99502f396 80 if( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x;
nucho 3:1cf99502f396 81 uint32_t * val_y = (uint32_t*) &(this->y);
nucho 3:1cf99502f396 82 offset += 3;
nucho 3:1cf99502f396 83 *val_y = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
nucho 3:1cf99502f396 84 *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
nucho 3:1cf99502f396 85 *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
nucho 3:1cf99502f396 86 *val_y |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
nucho 3:1cf99502f396 87 uint32_t exp_y = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
nucho 3:1cf99502f396 88 exp_y |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
nucho 3:1cf99502f396 89 if(exp_y !=0)
nucho 3:1cf99502f396 90 *val_y |= ((exp_y)-1023+127)<<23;
nucho 3:1cf99502f396 91 if( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y;
nucho 3:1cf99502f396 92 uint32_t * val_z = (uint32_t*) &(this->z);
nucho 3:1cf99502f396 93 offset += 3;
nucho 3:1cf99502f396 94 *val_z = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
nucho 3:1cf99502f396 95 *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
nucho 3:1cf99502f396 96 *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
nucho 3:1cf99502f396 97 *val_z |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
nucho 3:1cf99502f396 98 uint32_t exp_z = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
nucho 3:1cf99502f396 99 exp_z |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
nucho 3:1cf99502f396 100 if(exp_z !=0)
nucho 3:1cf99502f396 101 *val_z |= ((exp_z)-1023+127)<<23;
nucho 3:1cf99502f396 102 if( ((*(inbuffer+offset++)) & 0x80) > 0) this->z = -this->z;
nucho 3:1cf99502f396 103 return offset;
nucho 0:77afd7560544 104 }
nucho 0:77afd7560544 105
nucho 3:1cf99502f396 106 virtual const char * getType(){ return "geometry_msgs/Point"; };
nucho 3:1cf99502f396 107 virtual const char * getMD5(){ return "4a842b65f413084dc2b10fb484ea7f17"; };
nucho 0:77afd7560544 108
nucho 3:1cf99502f396 109 };
nucho 0:77afd7560544 110
nucho 0:77afd7560544 111 }
nucho 0:77afd7560544 112 #endif