Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Fork of rosserial_mbed_lib by
Diff: geometry_msgs/TwistWithCovariance.h
- Revision:
- 3:1cf99502f396
- Parent:
- 1:ff0ec969dad1
--- a/geometry_msgs/TwistWithCovariance.h Sun Oct 16 09:35:11 2011 +0000 +++ b/geometry_msgs/TwistWithCovariance.h Sat Nov 12 23:54:45 2011 +0000 @@ -1,10 +1,10 @@ -#ifndef ros_geometry_msgs_TwistWithCovariance_h -#define ros_geometry_msgs_TwistWithCovariance_h +#ifndef _ROS_geometry_msgs_TwistWithCovariance_h +#define _ROS_geometry_msgs_TwistWithCovariance_h #include <stdint.h> #include <string.h> #include <stdlib.h> -#include "../ros/msg.h" +#include "ros/msg.h" #include "geometry_msgs/Twist.h" namespace geometry_msgs @@ -16,17 +16,17 @@ geometry_msgs::Twist twist; float covariance[36]; - virtual int serialize(unsigned char *outbuffer) + virtual int serialize(unsigned char *outbuffer) const { int offset = 0; offset += this->twist.serialize(outbuffer + offset); unsigned char * covariance_val = (unsigned char *) this->covariance; - for( unsigned char i = 0; i < 36; i++){ - long * val_covariancei = (long *) &(this->covariance[i]); - long exp_covariancei = (((*val_covariancei)>>23)&255); + for( uint8_t i = 0; i < 36; i++){ + int32_t * val_covariancei = (long *) &(this->covariance[i]); + int32_t exp_covariancei = (((*val_covariancei)>>23)&255); if(exp_covariancei != 0) exp_covariancei += 1023-127; - long sig_covariancei = *val_covariancei; + int32_t sig_covariancei = *val_covariancei; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; @@ -44,16 +44,16 @@ { int offset = 0; offset += this->twist.deserialize(inbuffer + offset); - unsigned char * covariance_val = (unsigned char *) this->covariance; - for( unsigned char i = 0; i < 36; i++){ - unsigned long * val_covariancei = (unsigned long*) &(this->covariance[i]); + uint8_t * covariance_val = (uint8_t*) this->covariance; + for( uint8_t i = 0; i < 36; i++){ + uint32_t * val_covariancei = (uint32_t*) &(this->covariance[i]); offset += 3; - *val_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07); - *val_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3; - *val_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11; - *val_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19; - unsigned long exp_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4; - exp_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4; + *val_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; if(exp_covariancei !=0) *val_covariancei |= ((exp_covariancei)-1023+127)<<23; if( ((*(inbuffer+offset++)) & 0x80) > 0) this->covariance[i] = -this->covariance[i]; @@ -61,7 +61,8 @@ return offset; } - virtual const char * getType(){ return "geometry_msgs/TwistWithCovariance"; }; + virtual const char * getType(){ return "geometry_msgs/TwistWithCovariance"; }; + virtual const char * getMD5(){ return "1fe8a28e6890a4cc3ae4c3ca5c7d82e6"; }; };