Go to the documentation of this file.00001 #ifndef ros_geometry_msgs_TwistWithCovariance_h
00002 #define ros_geometry_msgs_TwistWithCovariance_h
00003
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "../ros/msg.h"
00008 #include "geometry_msgs/Twist.h"
00009
00010 namespace geometry_msgs
00011 {
00012
00013 class TwistWithCovariance : public ros::Msg
00014 {
00015 public:
00016 geometry_msgs::Twist twist;
00017 float covariance[36];
00018
00019 virtual int serialize(unsigned char *outbuffer)
00020 {
00021 int offset = 0;
00022 offset += this->twist.serialize(outbuffer + offset);
00023 unsigned char * covariance_val = (unsigned char *) this->covariance;
00024 for( unsigned char i = 0; i < 36; i++){
00025 long * val_covariancei = (long *) &(this->covariance[i]);
00026 long exp_covariancei = (((*val_covariancei)>>23)&255);
00027 if(exp_covariancei != 0)
00028 exp_covariancei += 1023-127;
00029 long sig_covariancei = *val_covariancei;
00030 *(outbuffer + offset++) = 0;
00031 *(outbuffer + offset++) = 0;
00032 *(outbuffer + offset++) = 0;
00033 *(outbuffer + offset++) = (sig_covariancei<<5) & 0xff;
00034 *(outbuffer + offset++) = (sig_covariancei>>3) & 0xff;
00035 *(outbuffer + offset++) = (sig_covariancei>>11) & 0xff;
00036 *(outbuffer + offset++) = ((exp_covariancei<<4) & 0xF0) | ((sig_covariancei>>19)&0x0F);
00037 *(outbuffer + offset++) = (exp_covariancei>>4) & 0x7F;
00038 if(this->covariance[i] < 0) *(outbuffer + offset -1) |= 0x80;
00039 }
00040 return offset;
00041 }
00042
00043 virtual int deserialize(unsigned char *inbuffer)
00044 {
00045 int offset = 0;
00046 offset += this->twist.deserialize(inbuffer + offset);
00047 unsigned char * covariance_val = (unsigned char *) this->covariance;
00048 for( unsigned char i = 0; i < 36; i++){
00049 unsigned long * val_covariancei = (unsigned long*) &(this->covariance[i]);
00050 offset += 3;
00051 *val_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
00052 *val_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
00053 *val_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
00054 *val_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
00055 unsigned long exp_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
00056 exp_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
00057 if(exp_covariancei !=0)
00058 *val_covariancei |= ((exp_covariancei)-1023+127)<<23;
00059 if( ((*(inbuffer+offset++)) & 0x80) > 0) this->covariance[i] = -this->covariance[i];
00060 }
00061 return offset;
00062 }
00063
00064 const char * getType(){ return "geometry_msgs/TwistWithCovariance"; };
00065
00066 };
00067
00068 }
00069 #endif