This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial. This program contains an example.
Dependencies: rosserial_mbed_lib mbed Servo
Diff: sensor_msgs/Imu.h
- Revision:
- 3:dff241b66f84
- Parent:
- 0:06fc856e99ca
diff -r 094e5153a559 -r dff241b66f84 sensor_msgs/Imu.h --- a/sensor_msgs/Imu.h Sun Oct 16 09:33:53 2011 +0000 +++ b/sensor_msgs/Imu.h Sat Nov 12 23:53:04 2011 +0000 @@ -1,10 +1,10 @@ -#ifndef ros_Imu_h -#define ros_Imu_h +#ifndef _ROS_sensor_msgs_Imu_h +#define _ROS_sensor_msgs_Imu_h #include <stdint.h> #include <string.h> #include <stdlib.h> -#include "../ros/msg.h" +#include "ros/msg.h" #include "std_msgs/Header.h" #include "geometry_msgs/Quaternion.h" #include "geometry_msgs/Vector3.h" @@ -23,18 +23,18 @@ geometry_msgs::Vector3 linear_acceleration; float linear_acceleration_covariance[9]; - virtual int serialize(unsigned char *outbuffer) + virtual int serialize(unsigned char *outbuffer) const { int offset = 0; offset += this->header.serialize(outbuffer + offset); offset += this->orientation.serialize(outbuffer + offset); unsigned char * orientation_covariance_val = (unsigned char *) this->orientation_covariance; - for( unsigned char i = 0; i < 9; i++){ - long * val_orientation_covariancei = (long *) &(this->orientation_covariance[i]); - long exp_orientation_covariancei = (((*val_orientation_covariancei)>>23)&255); + for( uint8_t i = 0; i < 9; i++){ + int32_t * val_orientation_covariancei = (long *) &(this->orientation_covariance[i]); + int32_t exp_orientation_covariancei = (((*val_orientation_covariancei)>>23)&255); if(exp_orientation_covariancei != 0) exp_orientation_covariancei += 1023-127; - long sig_orientation_covariancei = *val_orientation_covariancei; + int32_t sig_orientation_covariancei = *val_orientation_covariancei; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; @@ -47,12 +47,12 @@ } offset += this->angular_velocity.serialize(outbuffer + offset); unsigned char * angular_velocity_covariance_val = (unsigned char *) this->angular_velocity_covariance; - for( unsigned char i = 0; i < 9; i++){ - long * val_angular_velocity_covariancei = (long *) &(this->angular_velocity_covariance[i]); - long exp_angular_velocity_covariancei = (((*val_angular_velocity_covariancei)>>23)&255); + for( uint8_t i = 0; i < 9; i++){ + int32_t * val_angular_velocity_covariancei = (long *) &(this->angular_velocity_covariance[i]); + int32_t exp_angular_velocity_covariancei = (((*val_angular_velocity_covariancei)>>23)&255); if(exp_angular_velocity_covariancei != 0) exp_angular_velocity_covariancei += 1023-127; - long sig_angular_velocity_covariancei = *val_angular_velocity_covariancei; + int32_t sig_angular_velocity_covariancei = *val_angular_velocity_covariancei; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; @@ -65,12 +65,12 @@ } offset += this->linear_acceleration.serialize(outbuffer + offset); unsigned char * linear_acceleration_covariance_val = (unsigned char *) this->linear_acceleration_covariance; - for( unsigned char i = 0; i < 9; i++){ - long * val_linear_acceleration_covariancei = (long *) &(this->linear_acceleration_covariance[i]); - long exp_linear_acceleration_covariancei = (((*val_linear_acceleration_covariancei)>>23)&255); + for( uint8_t i = 0; i < 9; i++){ + int32_t * val_linear_acceleration_covariancei = (long *) &(this->linear_acceleration_covariance[i]); + int32_t exp_linear_acceleration_covariancei = (((*val_linear_acceleration_covariancei)>>23)&255); if(exp_linear_acceleration_covariancei != 0) exp_linear_acceleration_covariancei += 1023-127; - long sig_linear_acceleration_covariancei = *val_linear_acceleration_covariancei; + int32_t sig_linear_acceleration_covariancei = *val_linear_acceleration_covariancei; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; @@ -89,46 +89,46 @@ int offset = 0; offset += this->header.deserialize(inbuffer + offset); offset += this->orientation.deserialize(inbuffer + offset); - unsigned char * orientation_covariance_val = (unsigned char *) this->orientation_covariance; - for( unsigned char i = 0; i < 9; i++){ - unsigned long * val_orientation_covariancei = (unsigned long*) &(this->orientation_covariance[i]); + uint8_t * orientation_covariance_val = (uint8_t*) this->orientation_covariance; + for( uint8_t i = 0; i < 9; i++){ + uint32_t * val_orientation_covariancei = (uint32_t*) &(this->orientation_covariance[i]); offset += 3; - *val_orientation_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07); - *val_orientation_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3; - *val_orientation_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11; - *val_orientation_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19; - unsigned long exp_orientation_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4; - exp_orientation_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4; + *val_orientation_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_orientation_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; if(exp_orientation_covariancei !=0) *val_orientation_covariancei |= ((exp_orientation_covariancei)-1023+127)<<23; if( ((*(inbuffer+offset++)) & 0x80) > 0) this->orientation_covariance[i] = -this->orientation_covariance[i]; } offset += this->angular_velocity.deserialize(inbuffer + offset); - unsigned char * angular_velocity_covariance_val = (unsigned char *) this->angular_velocity_covariance; - for( unsigned char i = 0; i < 9; i++){ - unsigned long * val_angular_velocity_covariancei = (unsigned long*) &(this->angular_velocity_covariance[i]); + uint8_t * angular_velocity_covariance_val = (uint8_t*) this->angular_velocity_covariance; + for( uint8_t i = 0; i < 9; i++){ + uint32_t * val_angular_velocity_covariancei = (uint32_t*) &(this->angular_velocity_covariance[i]); offset += 3; - *val_angular_velocity_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07); - *val_angular_velocity_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3; - *val_angular_velocity_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11; - *val_angular_velocity_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19; - unsigned long exp_angular_velocity_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4; - exp_angular_velocity_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4; + *val_angular_velocity_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_angular_velocity_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; if(exp_angular_velocity_covariancei !=0) *val_angular_velocity_covariancei |= ((exp_angular_velocity_covariancei)-1023+127)<<23; if( ((*(inbuffer+offset++)) & 0x80) > 0) this->angular_velocity_covariance[i] = -this->angular_velocity_covariance[i]; } offset += this->linear_acceleration.deserialize(inbuffer + offset); - unsigned char * linear_acceleration_covariance_val = (unsigned char *) this->linear_acceleration_covariance; - for( unsigned char i = 0; i < 9; i++){ - unsigned long * val_linear_acceleration_covariancei = (unsigned long*) &(this->linear_acceleration_covariance[i]); + uint8_t * linear_acceleration_covariance_val = (uint8_t*) this->linear_acceleration_covariance; + for( uint8_t i = 0; i < 9; i++){ + uint32_t * val_linear_acceleration_covariancei = (uint32_t*) &(this->linear_acceleration_covariance[i]); offset += 3; - *val_linear_acceleration_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07); - *val_linear_acceleration_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3; - *val_linear_acceleration_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11; - *val_linear_acceleration_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19; - unsigned long exp_linear_acceleration_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4; - exp_linear_acceleration_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4; + *val_linear_acceleration_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_linear_acceleration_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; if(exp_linear_acceleration_covariancei !=0) *val_linear_acceleration_covariancei |= ((exp_linear_acceleration_covariancei)-1023+127)<<23; if( ((*(inbuffer+offset++)) & 0x80) > 0) this->linear_acceleration_covariance[i] = -this->linear_acceleration_covariance[i]; @@ -136,7 +136,8 @@ return offset; } - virtual const char * getType(){ return "sensor_msgs/Imu"; }; + virtual const char * getType(){ return "sensor_msgs/Imu"; }; + virtual const char * getMD5(){ return "6a62c6daae103f4ff57a132d6f95cec2"; }; };