modify for Hydro version
Fork of rosserial_mbed_lib by
Revision 6:3c54bc7badd4, committed 2013-10-26
- Comitter:
- jjzak
- Date:
- Sat Oct 26 15:39:01 2013 +0000
- Parent:
- 5:8cd48977ec68
- Commit message:
- modify for Hydro version;
Changed in this revision
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dianostic_msgs/DiagnosticArray.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,58 @@ +#ifndef _ROS_diagnostic_msgs_DiagnosticArray_h +#define _ROS_diagnostic_msgs_DiagnosticArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "diagnostic_msgs/DiagnosticStatus.h" + +namespace diagnostic_msgs +{ + + class DiagnosticArray : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t status_length; + diagnostic_msgs::DiagnosticStatus st_status; + diagnostic_msgs::DiagnosticStatus * status; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = status_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < status_length; i++){ + offset += this->status[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t status_lengthT = *(inbuffer + offset++); + if(status_lengthT > status_length) + this->status = (diagnostic_msgs::DiagnosticStatus*)realloc(this->status, status_lengthT * sizeof(diagnostic_msgs::DiagnosticStatus)); + offset += 3; + status_length = status_lengthT; + for( uint8_t i = 0; i < status_length; i++){ + offset += this->st_status.deserialize(inbuffer + offset); + memcpy( &(this->status[i]), &(this->st_status), sizeof(diagnostic_msgs::DiagnosticStatus)); + } + return offset; + } + + const char * getType(){ return "diagnostic_msgs/DiagnosticArray"; }; + const char * getMD5(){ return "3cfbeff055e708a24c3d946a5c8139cd"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dianostic_msgs/DiagnosticStatus.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,118 @@ +#ifndef _ROS_diagnostic_msgs_DiagnosticStatus_h +#define _ROS_diagnostic_msgs_DiagnosticStatus_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "diagnostic_msgs/KeyValue.h" + +namespace diagnostic_msgs +{ + + class DiagnosticStatus : public ros::Msg + { + public: + int8_t level; + char * name; + char * message; + char * hardware_id; + uint8_t values_length; + diagnostic_msgs::KeyValue st_values; + diagnostic_msgs::KeyValue * values; + enum { OK = 0 }; + enum { WARN = 1 }; + enum { ERROR = 2 }; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_level; + u_level.real = this->level; + *(outbuffer + offset + 0) = (u_level.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->level); + uint32_t length_name = strlen( (const char*) this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_message = strlen( (const char*) this->message); + memcpy(outbuffer + offset, &length_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->message, length_message); + offset += length_message; + uint32_t length_hardware_id = strlen( (const char*) this->hardware_id); + memcpy(outbuffer + offset, &length_hardware_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->hardware_id, length_hardware_id); + offset += length_hardware_id; + *(outbuffer + offset++) = values_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < values_length; i++){ + offset += this->values[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_level; + u_level.base = 0; + u_level.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->level = u_level.real; + offset += sizeof(this->level); + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_message; + memcpy(&length_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_message-1]=0; + this->message = (char *)(inbuffer + offset-1); + offset += length_message; + uint32_t length_hardware_id; + memcpy(&length_hardware_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_hardware_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_hardware_id-1]=0; + this->hardware_id = (char *)(inbuffer + offset-1); + offset += length_hardware_id; + uint8_t values_lengthT = *(inbuffer + offset++); + if(values_lengthT > values_length) + this->values = (diagnostic_msgs::KeyValue*)realloc(this->values, values_lengthT * sizeof(diagnostic_msgs::KeyValue)); + offset += 3; + values_length = values_lengthT; + for( uint8_t i = 0; i < values_length; i++){ + offset += this->st_values.deserialize(inbuffer + offset); + memcpy( &(this->values[i]), &(this->st_values), sizeof(diagnostic_msgs::KeyValue)); + } + return offset; + } + + const char * getType(){ return "diagnostic_msgs/DiagnosticStatus"; }; + const char * getMD5(){ return "67d15a62edb26e9d52b0f0efa3ef9da7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dianostic_msgs/KeyValue.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_diagnostic_msgs_KeyValue_h +#define _ROS_diagnostic_msgs_KeyValue_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace diagnostic_msgs +{ + + class KeyValue : public ros::Msg + { + public: + char * key; + char * value; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_key = strlen( (const char*) this->key); + memcpy(outbuffer + offset, &length_key, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->key, length_key); + offset += length_key; + uint32_t length_value = strlen( (const char*) this->value); + memcpy(outbuffer + offset, &length_value, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->value, length_value); + offset += length_value; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_key; + memcpy(&length_key, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_key; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_key-1]=0; + this->key = (char *)(inbuffer + offset-1); + offset += length_key; + uint32_t length_value; + memcpy(&length_value, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_value; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_value-1]=0; + this->value = (char *)(inbuffer + offset-1); + offset += length_value; + return offset; + } + + const char * getType(){ return "diagnostic_msgs/KeyValue"; }; + const char * getMD5(){ return "cf57fdc6617a881a88c16e768132149c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/dianostic_msgs/SelfTest.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,114 @@ +#ifndef _ROS_SERVICE_SelfTest_h +#define _ROS_SERVICE_SelfTest_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "diagnostic_msgs/DiagnosticStatus.h" + +namespace diagnostic_msgs +{ + +static const char SELFTEST[] = "diagnostic_msgs/SelfTest"; + + class SelfTestRequest : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return SELFTEST; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class SelfTestResponse : public ros::Msg + { + public: + char * id; + int8_t passed; + uint8_t status_length; + diagnostic_msgs::DiagnosticStatus st_status; + diagnostic_msgs::DiagnosticStatus * status; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_id = strlen( (const char*) this->id); + memcpy(outbuffer + offset, &length_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->id, length_id); + offset += length_id; + union { + int8_t real; + uint8_t base; + } u_passed; + u_passed.real = this->passed; + *(outbuffer + offset + 0) = (u_passed.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->passed); + *(outbuffer + offset++) = status_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < status_length; i++){ + offset += this->status[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_id; + memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_id-1]=0; + this->id = (char *)(inbuffer + offset-1); + offset += length_id; + union { + int8_t real; + uint8_t base; + } u_passed; + u_passed.base = 0; + u_passed.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->passed = u_passed.real; + offset += sizeof(this->passed); + uint8_t status_lengthT = *(inbuffer + offset++); + if(status_lengthT > status_length) + this->status = (diagnostic_msgs::DiagnosticStatus*)realloc(this->status, status_lengthT * sizeof(diagnostic_msgs::DiagnosticStatus)); + offset += 3; + status_length = status_lengthT; + for( uint8_t i = 0; i < status_length; i++){ + offset += this->st_status.deserialize(inbuffer + offset); + memcpy( &(this->status[i]), &(this->st_status), sizeof(diagnostic_msgs::DiagnosticStatus)); + } + return offset; + } + + const char * getType(){ return SELFTEST; }; + const char * getMD5(){ return "74c9372c870a76da4fc2b3973978b898"; }; + + }; + + class SelfTest { + public: + typedef SelfTestRequest Request; + typedef SelfTestResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Point.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,112 @@ +#ifndef _ROS_geometry_msgs_Point_h +#define _ROS_geometry_msgs_Point_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace geometry_msgs +{ + + class Point : public ros::Msg + { + public: + float x; + float y; + float z; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + int32_t * val_x = (int32_t *) &(this->x); + int32_t exp_x = (((*val_x)>>23)&255); + if(exp_x != 0) + exp_x += 1023-127; + int32_t sig_x = *val_x; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_x<<5) & 0xff; + *(outbuffer + offset++) = (sig_x>>3) & 0xff; + *(outbuffer + offset++) = (sig_x>>11) & 0xff; + *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F); + *(outbuffer + offset++) = (exp_x>>4) & 0x7F; + if(this->x < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_y = (int32_t *) &(this->y); + int32_t exp_y = (((*val_y)>>23)&255); + if(exp_y != 0) + exp_y += 1023-127; + int32_t sig_y = *val_y; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_y<<5) & 0xff; + *(outbuffer + offset++) = (sig_y>>3) & 0xff; + *(outbuffer + offset++) = (sig_y>>11) & 0xff; + *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F); + *(outbuffer + offset++) = (exp_y>>4) & 0x7F; + if(this->y < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_z = (int32_t *) &(this->z); + int32_t exp_z = (((*val_z)>>23)&255); + if(exp_z != 0) + exp_z += 1023-127; + int32_t sig_z = *val_z; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_z<<5) & 0xff; + *(outbuffer + offset++) = (sig_z>>3) & 0xff; + *(outbuffer + offset++) = (sig_z>>11) & 0xff; + *(outbuffer + offset++) = ((exp_z<<4) & 0xF0) | ((sig_z>>19)&0x0F); + *(outbuffer + offset++) = (exp_z>>4) & 0x7F; + if(this->z < 0) *(outbuffer + offset -1) |= 0x80; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t * val_x = (uint32_t*) &(this->x); + offset += 3; + *val_x = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_x |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_x = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_x |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_x !=0) + *val_x |= ((exp_x)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x; + uint32_t * val_y = (uint32_t*) &(this->y); + offset += 3; + *val_y = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_y |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_y = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_y |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_y !=0) + *val_y |= ((exp_y)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y; + uint32_t * val_z = (uint32_t*) &(this->z); + offset += 3; + *val_z = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_z |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_z = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_z |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_z !=0) + *val_z |= ((exp_z)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->z = -this->z; + return offset; + } + + const char * getType(){ return "geometry_msgs/Point"; }; + const char * getMD5(){ return "4a842b65f413084dc2b10fb484ea7f17"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Point32.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,100 @@ +#ifndef _ROS_geometry_msgs_Point32_h +#define _ROS_geometry_msgs_Point32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace geometry_msgs +{ + + class Point32 : public ros::Msg + { + public: + float x; + float y; + float z; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_x; + u_x.real = this->x; + *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->x); + union { + float real; + uint32_t base; + } u_y; + u_y.real = this->y; + *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->y); + union { + float real; + uint32_t base; + } u_z; + u_z.real = this->z; + *(outbuffer + offset + 0) = (u_z.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_z.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_z.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_z.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->z); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_x; + u_x.base = 0; + u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->x = u_x.real; + offset += sizeof(this->x); + union { + float real; + uint32_t base; + } u_y; + u_y.base = 0; + u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->y = u_y.real; + offset += sizeof(this->y); + union { + float real; + uint32_t base; + } u_z; + u_z.base = 0; + u_z.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_z.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_z.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_z.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->z = u_z.real; + offset += sizeof(this->z); + return offset; + } + + const char * getType(){ return "geometry_msgs/Point32"; }; + const char * getMD5(){ return "cc153912f1453b708d221682bc23d9ac"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/PointStamped.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_PointStamped_h +#define _ROS_geometry_msgs_PointStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Point.h" + +namespace geometry_msgs +{ + + class PointStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Point point; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->point.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->point.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/PointStamped"; }; + const char * getMD5(){ return "c63aecb41bfdfd6b7e1fac37c7cbe7bf"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Polygon.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,54 @@ +#ifndef _ROS_geometry_msgs_Polygon_h +#define _ROS_geometry_msgs_Polygon_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Point32.h" + +namespace geometry_msgs +{ + + class Polygon : public ros::Msg + { + public: + uint8_t points_length; + geometry_msgs::Point32 st_points; + geometry_msgs::Point32 * points; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = points_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->points[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t points_lengthT = *(inbuffer + offset++); + if(points_lengthT > points_length) + this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32)); + offset += 3; + points_length = points_lengthT; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->st_points.deserialize(inbuffer + offset); + memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32)); + } + return offset; + } + + const char * getType(){ return "geometry_msgs/Polygon"; }; + const char * getMD5(){ return "cd60a26494a087f577976f0329fa120e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/PolygonStamped.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_PolygonStamped_h +#define _ROS_geometry_msgs_PolygonStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Polygon.h" + +namespace geometry_msgs +{ + + class PolygonStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Polygon polygon; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->polygon.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->polygon.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/PolygonStamped"; }; + const char * getMD5(){ return "c6be8f7dc3bee7fe9e8d296070f53340"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Pose.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_Pose_h +#define _ROS_geometry_msgs_Pose_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Point.h" +#include "geometry_msgs/Quaternion.h" + +namespace geometry_msgs +{ + + class Pose : public ros::Msg + { + public: + geometry_msgs::Point position; + geometry_msgs::Quaternion orientation; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->position.serialize(outbuffer + offset); + offset += this->orientation.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->position.deserialize(inbuffer + offset); + offset += this->orientation.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/Pose"; }; + const char * getMD5(){ return "e45d45a5a1ce597b249e23fb30fc871f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Pose2D.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,112 @@ +#ifndef _ROS_geometry_msgs_Pose2D_h +#define _ROS_geometry_msgs_Pose2D_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace geometry_msgs +{ + + class Pose2D : public ros::Msg + { + public: + float x; + float y; + float theta; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + int32_t * val_x = (int32_t *) &(this->x); + int32_t exp_x = (((*val_x)>>23)&255); + if(exp_x != 0) + exp_x += 1023-127; + int32_t sig_x = *val_x; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_x<<5) & 0xff; + *(outbuffer + offset++) = (sig_x>>3) & 0xff; + *(outbuffer + offset++) = (sig_x>>11) & 0xff; + *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F); + *(outbuffer + offset++) = (exp_x>>4) & 0x7F; + if(this->x < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_y = (int32_t *) &(this->y); + int32_t exp_y = (((*val_y)>>23)&255); + if(exp_y != 0) + exp_y += 1023-127; + int32_t sig_y = *val_y; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_y<<5) & 0xff; + *(outbuffer + offset++) = (sig_y>>3) & 0xff; + *(outbuffer + offset++) = (sig_y>>11) & 0xff; + *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F); + *(outbuffer + offset++) = (exp_y>>4) & 0x7F; + if(this->y < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_theta = (int32_t *) &(this->theta); + int32_t exp_theta = (((*val_theta)>>23)&255); + if(exp_theta != 0) + exp_theta += 1023-127; + int32_t sig_theta = *val_theta; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_theta<<5) & 0xff; + *(outbuffer + offset++) = (sig_theta>>3) & 0xff; + *(outbuffer + offset++) = (sig_theta>>11) & 0xff; + *(outbuffer + offset++) = ((exp_theta<<4) & 0xF0) | ((sig_theta>>19)&0x0F); + *(outbuffer + offset++) = (exp_theta>>4) & 0x7F; + if(this->theta < 0) *(outbuffer + offset -1) |= 0x80; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t * val_x = (uint32_t*) &(this->x); + offset += 3; + *val_x = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_x |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_x = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_x |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_x !=0) + *val_x |= ((exp_x)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x; + uint32_t * val_y = (uint32_t*) &(this->y); + offset += 3; + *val_y = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_y |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_y = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_y |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_y !=0) + *val_y |= ((exp_y)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y; + uint32_t * val_theta = (uint32_t*) &(this->theta); + offset += 3; + *val_theta = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_theta |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_theta |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_theta |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_theta = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_theta |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_theta !=0) + *val_theta |= ((exp_theta)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->theta = -this->theta; + return offset; + } + + const char * getType(){ return "geometry_msgs/Pose2D"; }; + const char * getMD5(){ return "938fa65709584ad8e77d238529be13b8"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/PoseArray.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,58 @@ +#ifndef _ROS_geometry_msgs_PoseArray_h +#define _ROS_geometry_msgs_PoseArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Pose.h" + +namespace geometry_msgs +{ + + class PoseArray : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t poses_length; + geometry_msgs::Pose st_poses; + geometry_msgs::Pose * poses; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = poses_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < poses_length; i++){ + offset += this->poses[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t poses_lengthT = *(inbuffer + offset++); + if(poses_lengthT > poses_length) + this->poses = (geometry_msgs::Pose*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::Pose)); + offset += 3; + poses_length = poses_lengthT; + for( uint8_t i = 0; i < poses_length; i++){ + offset += this->st_poses.deserialize(inbuffer + offset); + memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::Pose)); + } + return offset; + } + + const char * getType(){ return "geometry_msgs/PoseArray"; }; + const char * getMD5(){ return "916c28c5764443f268b296bb671b9d97"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/PoseStamped.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_PoseStamped_h +#define _ROS_geometry_msgs_PoseStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Pose.h" + +namespace geometry_msgs +{ + + class PoseStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Pose pose; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->pose.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->pose.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/PoseStamped"; }; + const char * getMD5(){ return "d3812c3cbc69362b77dc0b19b345f8f5"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/PoseWithCovariance.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,70 @@ +#ifndef _ROS_geometry_msgs_PoseWithCovariance_h +#define _ROS_geometry_msgs_PoseWithCovariance_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Pose.h" + +namespace geometry_msgs +{ + + class PoseWithCovariance : public ros::Msg + { + public: + geometry_msgs::Pose pose; + float covariance[36]; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->pose.serialize(outbuffer + offset); + unsigned char * covariance_val = (unsigned char *) this->covariance; + for( uint8_t i = 0; i < 36; i++){ + int32_t * val_covariancei = (int32_t *) &(this->covariance[i]); + int32_t exp_covariancei = (((*val_covariancei)>>23)&255); + if(exp_covariancei != 0) + exp_covariancei += 1023-127; + int32_t sig_covariancei = *val_covariancei; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_covariancei<<5) & 0xff; + *(outbuffer + offset++) = (sig_covariancei>>3) & 0xff; + *(outbuffer + offset++) = (sig_covariancei>>11) & 0xff; + *(outbuffer + offset++) = ((exp_covariancei<<4) & 0xF0) | ((sig_covariancei>>19)&0x0F); + *(outbuffer + offset++) = (exp_covariancei>>4) & 0x7F; + if(this->covariance[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->pose.deserialize(inbuffer + offset); + 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 = ((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]; + } + return offset; + } + + const char * getType(){ return "geometry_msgs/PoseWithCovariance"; }; + const char * getMD5(){ return "c23e848cf1b7533a8d7c259073a97e6f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/PoseWithCovarianceStamped.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_PoseWithCovarianceStamped_h +#define _ROS_geometry_msgs_PoseWithCovarianceStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/PoseWithCovariance.h" + +namespace geometry_msgs +{ + + class PoseWithCovarianceStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::PoseWithCovariance pose; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->pose.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->pose.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/PoseWithCovarianceStamped"; }; + const char * getMD5(){ return "953b798c0f514ff060a53a3498ce6246"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Quaternion.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,138 @@ +#ifndef _ROS_geometry_msgs_Quaternion_h +#define _ROS_geometry_msgs_Quaternion_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace geometry_msgs +{ + + class Quaternion : public ros::Msg + { + public: + float x; + float y; + float z; + float w; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + int32_t * val_x = (int32_t *) &(this->x); + int32_t exp_x = (((*val_x)>>23)&255); + if(exp_x != 0) + exp_x += 1023-127; + int32_t sig_x = *val_x; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_x<<5) & 0xff; + *(outbuffer + offset++) = (sig_x>>3) & 0xff; + *(outbuffer + offset++) = (sig_x>>11) & 0xff; + *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F); + *(outbuffer + offset++) = (exp_x>>4) & 0x7F; + if(this->x < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_y = (int32_t *) &(this->y); + int32_t exp_y = (((*val_y)>>23)&255); + if(exp_y != 0) + exp_y += 1023-127; + int32_t sig_y = *val_y; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_y<<5) & 0xff; + *(outbuffer + offset++) = (sig_y>>3) & 0xff; + *(outbuffer + offset++) = (sig_y>>11) & 0xff; + *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F); + *(outbuffer + offset++) = (exp_y>>4) & 0x7F; + if(this->y < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_z = (int32_t *) &(this->z); + int32_t exp_z = (((*val_z)>>23)&255); + if(exp_z != 0) + exp_z += 1023-127; + int32_t sig_z = *val_z; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_z<<5) & 0xff; + *(outbuffer + offset++) = (sig_z>>3) & 0xff; + *(outbuffer + offset++) = (sig_z>>11) & 0xff; + *(outbuffer + offset++) = ((exp_z<<4) & 0xF0) | ((sig_z>>19)&0x0F); + *(outbuffer + offset++) = (exp_z>>4) & 0x7F; + if(this->z < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_w = (int32_t *) &(this->w); + int32_t exp_w = (((*val_w)>>23)&255); + if(exp_w != 0) + exp_w += 1023-127; + int32_t sig_w = *val_w; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_w<<5) & 0xff; + *(outbuffer + offset++) = (sig_w>>3) & 0xff; + *(outbuffer + offset++) = (sig_w>>11) & 0xff; + *(outbuffer + offset++) = ((exp_w<<4) & 0xF0) | ((sig_w>>19)&0x0F); + *(outbuffer + offset++) = (exp_w>>4) & 0x7F; + if(this->w < 0) *(outbuffer + offset -1) |= 0x80; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t * val_x = (uint32_t*) &(this->x); + offset += 3; + *val_x = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_x |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_x = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_x |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_x !=0) + *val_x |= ((exp_x)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x; + uint32_t * val_y = (uint32_t*) &(this->y); + offset += 3; + *val_y = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_y |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_y = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_y |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_y !=0) + *val_y |= ((exp_y)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y; + uint32_t * val_z = (uint32_t*) &(this->z); + offset += 3; + *val_z = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_z |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_z = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_z |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_z !=0) + *val_z |= ((exp_z)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->z = -this->z; + uint32_t * val_w = (uint32_t*) &(this->w); + offset += 3; + *val_w = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_w |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_w |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_w |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_w = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_w |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_w !=0) + *val_w |= ((exp_w)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->w = -this->w; + return offset; + } + + const char * getType(){ return "geometry_msgs/Quaternion"; }; + const char * getMD5(){ return "a779879fadf0160734f906b8c19c7004"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/QuaternionStamped.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_QuaternionStamped_h +#define _ROS_geometry_msgs_QuaternionStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Quaternion.h" + +namespace geometry_msgs +{ + + class QuaternionStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Quaternion quaternion; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->quaternion.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->quaternion.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/QuaternionStamped"; }; + const char * getMD5(){ return "e57f1e547e0e1fd13504588ffc8334e2"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Transform.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_Transform_h +#define _ROS_geometry_msgs_Transform_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Vector3.h" +#include "geometry_msgs/Quaternion.h" + +namespace geometry_msgs +{ + + class Transform : public ros::Msg + { + public: + geometry_msgs::Vector3 translation; + geometry_msgs::Quaternion rotation; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->translation.serialize(outbuffer + offset); + offset += this->rotation.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->translation.deserialize(inbuffer + offset); + offset += this->rotation.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/Transform"; }; + const char * getMD5(){ return "ac9eff44abf714214112b05d54a3cf9b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/TransformStamped.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,57 @@ +#ifndef _ROS_geometry_msgs_TransformStamped_h +#define _ROS_geometry_msgs_TransformStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Transform.h" + +namespace geometry_msgs +{ + + class TransformStamped : public ros::Msg + { + public: + std_msgs::Header header; + char * child_frame_id; + geometry_msgs::Transform transform; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t length_child_frame_id = strlen( (const char*) this->child_frame_id); + memcpy(outbuffer + offset, &length_child_frame_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->child_frame_id, length_child_frame_id); + offset += length_child_frame_id; + offset += this->transform.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_child_frame_id; + memcpy(&length_child_frame_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_child_frame_id-1]=0; + this->child_frame_id = (char *)(inbuffer + offset-1); + offset += length_child_frame_id; + offset += this->transform.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/TransformStamped"; }; + const char * getMD5(){ return "b5764a33bfeb3588febc2682852579b0"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Twist.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,41 @@ +#ifndef _ROS_geometry_msgs_Twist_h +#define _ROS_geometry_msgs_Twist_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Vector3.h" + +namespace geometry_msgs +{ + + class Twist : public ros::Msg + { + public: + geometry_msgs::Vector3 linear; + geometry_msgs::Vector3 angular; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->linear.serialize(outbuffer + offset); + offset += this->angular.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->linear.deserialize(inbuffer + offset); + offset += this->angular.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/Twist"; }; + const char * getMD5(){ return "9f195f881246fdfa2798d1d3eebca84a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/TwistStamped.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_TwistStamped_h +#define _ROS_geometry_msgs_TwistStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Twist.h" + +namespace geometry_msgs +{ + + class TwistStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Twist twist; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->twist.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->twist.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/TwistStamped"; }; + const char * getMD5(){ return "98d34b0043a2093cf9d9345ab6eef12e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/TwistWithCovariance.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,70 @@ +#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 "geometry_msgs/Twist.h" + +namespace geometry_msgs +{ + + class TwistWithCovariance : public ros::Msg + { + public: + geometry_msgs::Twist twist; + float covariance[36]; + + 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( uint8_t i = 0; i < 36; i++){ + int32_t * val_covariancei = (int32_t *) &(this->covariance[i]); + int32_t exp_covariancei = (((*val_covariancei)>>23)&255); + if(exp_covariancei != 0) + exp_covariancei += 1023-127; + int32_t sig_covariancei = *val_covariancei; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_covariancei<<5) & 0xff; + *(outbuffer + offset++) = (sig_covariancei>>3) & 0xff; + *(outbuffer + offset++) = (sig_covariancei>>11) & 0xff; + *(outbuffer + offset++) = ((exp_covariancei<<4) & 0xF0) | ((sig_covariancei>>19)&0x0F); + *(outbuffer + offset++) = (exp_covariancei>>4) & 0x7F; + if(this->covariance[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->twist.deserialize(inbuffer + offset); + 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 = ((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]; + } + return offset; + } + + const char * getType(){ return "geometry_msgs/TwistWithCovariance"; }; + const char * getMD5(){ return "1fe8a28e6890a4cc3ae4c3ca5c7d82e6"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/TwistWithCovarianceStamped.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_TwistWithCovarianceStamped_h +#define _ROS_geometry_msgs_TwistWithCovarianceStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/TwistWithCovariance.h" + +namespace geometry_msgs +{ + + class TwistWithCovarianceStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::TwistWithCovariance twist; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->twist.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->twist.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/TwistWithCovarianceStamped"; }; + const char * getMD5(){ return "8927a1a12fb2607ceea095b2dc440a96"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Vector3.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,112 @@ +#ifndef _ROS_geometry_msgs_Vector3_h +#define _ROS_geometry_msgs_Vector3_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace geometry_msgs +{ + + class Vector3 : public ros::Msg + { + public: + float x; + float y; + float z; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + int32_t * val_x = (int32_t *) &(this->x); + int32_t exp_x = (((*val_x)>>23)&255); + if(exp_x != 0) + exp_x += 1023-127; + int32_t sig_x = *val_x; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_x<<5) & 0xff; + *(outbuffer + offset++) = (sig_x>>3) & 0xff; + *(outbuffer + offset++) = (sig_x>>11) & 0xff; + *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F); + *(outbuffer + offset++) = (exp_x>>4) & 0x7F; + if(this->x < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_y = (int32_t *) &(this->y); + int32_t exp_y = (((*val_y)>>23)&255); + if(exp_y != 0) + exp_y += 1023-127; + int32_t sig_y = *val_y; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_y<<5) & 0xff; + *(outbuffer + offset++) = (sig_y>>3) & 0xff; + *(outbuffer + offset++) = (sig_y>>11) & 0xff; + *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F); + *(outbuffer + offset++) = (exp_y>>4) & 0x7F; + if(this->y < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_z = (int32_t *) &(this->z); + int32_t exp_z = (((*val_z)>>23)&255); + if(exp_z != 0) + exp_z += 1023-127; + int32_t sig_z = *val_z; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_z<<5) & 0xff; + *(outbuffer + offset++) = (sig_z>>3) & 0xff; + *(outbuffer + offset++) = (sig_z>>11) & 0xff; + *(outbuffer + offset++) = ((exp_z<<4) & 0xF0) | ((sig_z>>19)&0x0F); + *(outbuffer + offset++) = (exp_z>>4) & 0x7F; + if(this->z < 0) *(outbuffer + offset -1) |= 0x80; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t * val_x = (uint32_t*) &(this->x); + offset += 3; + *val_x = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_x |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_x = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_x |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_x !=0) + *val_x |= ((exp_x)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x; + uint32_t * val_y = (uint32_t*) &(this->y); + offset += 3; + *val_y = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_y |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_y = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_y |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_y !=0) + *val_y |= ((exp_y)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y; + uint32_t * val_z = (uint32_t*) &(this->z); + offset += 3; + *val_z = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_z |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_z = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_z |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_z !=0) + *val_z |= ((exp_z)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->z = -this->z; + return offset; + } + + const char * getType(){ return "geometry_msgs/Vector3"; }; + const char * getMD5(){ return "4a842b65f413084dc2b10fb484ea7f17"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Vector3Stamped.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_Vector3Stamped_h +#define _ROS_geometry_msgs_Vector3Stamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Vector3.h" + +namespace geometry_msgs +{ + + class Vector3Stamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Vector3 vector; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->vector.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->vector.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/Vector3Stamped"; }; + const char * getMD5(){ return "7b324c7325e683bf02a9b14b01090ec7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/Wrench.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,41 @@ +#ifndef _ROS_geometry_msgs_Wrench_h +#define _ROS_geometry_msgs_Wrench_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/Vector3.h" + +namespace geometry_msgs +{ + + class Wrench : public ros::Msg + { + public: + geometry_msgs::Vector3 force; + geometry_msgs::Vector3 torque; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->force.serialize(outbuffer + offset); + offset += this->torque.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->force.deserialize(inbuffer + offset); + offset += this->torque.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/Wrench"; }; + const char * getMD5(){ return "4f539cf138b23283b520fd271b567936"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/geometry_msgs/WrenchStamped.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,42 @@ +#ifndef _ROS_geometry_msgs_WrenchStamped_h +#define _ROS_geometry_msgs_WrenchStamped_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Wrench.h" + +namespace geometry_msgs +{ + + class WrenchStamped : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Wrench wrench; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->wrench.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->wrench.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "geometry_msgs/WrenchStamped"; }; + const char * getMD5(){ return "d78d3cb249ce23087ade7e7d0c40cfa7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/GetMap.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,67 @@ +#ifndef _ROS_SERVICE_GetMap_h +#define _ROS_SERVICE_GetMap_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "nav_msgs/OccupancyGrid.h" + +namespace nav_msgs +{ + +static const char GETMAP[] = "nav_msgs/GetMap"; + + class GetMapRequest : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return GETMAP; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class GetMapResponse : public ros::Msg + { + public: + nav_msgs::OccupancyGrid map; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->map.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->map.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETMAP; }; + const char * getMD5(){ return "6cdd0a18e0aff5b0a3ca2326a89b54ff"; }; + + }; + + class GetMap { + public: + typedef GetMapRequest Request; + typedef GetMapResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/GetPlan.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,96 @@ +#ifndef _ROS_SERVICE_GetPlan_h +#define _ROS_SERVICE_GetPlan_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/PoseStamped.h" +#include "nav_msgs/Path.h" + +namespace nav_msgs +{ + +static const char GETPLAN[] = "nav_msgs/GetPlan"; + + class GetPlanRequest : public ros::Msg + { + public: + geometry_msgs::PoseStamped start; + geometry_msgs::PoseStamped goal; + float tolerance; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->start.serialize(outbuffer + offset); + offset += this->goal.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_tolerance; + u_tolerance.real = this->tolerance; + *(outbuffer + offset + 0) = (u_tolerance.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_tolerance.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_tolerance.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_tolerance.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->tolerance); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->start.deserialize(inbuffer + offset); + offset += this->goal.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_tolerance; + u_tolerance.base = 0; + u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->tolerance = u_tolerance.real; + offset += sizeof(this->tolerance); + return offset; + } + + const char * getType(){ return GETPLAN; }; + const char * getMD5(){ return "e25a43e0752bcca599a8c2eef8282df8"; }; + + }; + + class GetPlanResponse : public ros::Msg + { + public: + nav_msgs::Path plan; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->plan.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->plan.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETPLAN; }; + const char * getMD5(){ return "0002bc113c0259d71f6cf8cbc9430e18"; }; + + }; + + class GetPlan { + public: + typedef GetPlanRequest Request; + typedef GetPlanResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/GridCells.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,102 @@ +#ifndef _ROS_nav_msgs_GridCells_h +#define _ROS_nav_msgs_GridCells_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Point.h" + +namespace nav_msgs +{ + + class GridCells : public ros::Msg + { + public: + std_msgs::Header header; + float cell_width; + float cell_height; + uint8_t cells_length; + geometry_msgs::Point st_cells; + geometry_msgs::Point * cells; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_cell_width; + u_cell_width.real = this->cell_width; + *(outbuffer + offset + 0) = (u_cell_width.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_cell_width.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_cell_width.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_cell_width.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->cell_width); + union { + float real; + uint32_t base; + } u_cell_height; + u_cell_height.real = this->cell_height; + *(outbuffer + offset + 0) = (u_cell_height.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_cell_height.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_cell_height.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_cell_height.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->cell_height); + *(outbuffer + offset++) = cells_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < cells_length; i++){ + offset += this->cells[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_cell_width; + u_cell_width.base = 0; + u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->cell_width = u_cell_width.real; + offset += sizeof(this->cell_width); + union { + float real; + uint32_t base; + } u_cell_height; + u_cell_height.base = 0; + u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->cell_height = u_cell_height.real; + offset += sizeof(this->cell_height); + uint8_t cells_lengthT = *(inbuffer + offset++); + if(cells_lengthT > cells_length) + this->cells = (geometry_msgs::Point*)realloc(this->cells, cells_lengthT * sizeof(geometry_msgs::Point)); + offset += 3; + cells_length = cells_lengthT; + for( uint8_t i = 0; i < cells_length; i++){ + offset += this->st_cells.deserialize(inbuffer + offset); + memcpy( &(this->cells[i]), &(this->st_cells), sizeof(geometry_msgs::Point)); + } + return offset; + } + + const char * getType(){ return "nav_msgs/GridCells"; }; + const char * getMD5(){ return "b9e4f5df6d28e272ebde00a3994830f5"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/MapMetaData.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,104 @@ +#ifndef _ROS_nav_msgs_MapMetaData_h +#define _ROS_nav_msgs_MapMetaData_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" +#include "geometry_msgs/Pose.h" + +namespace nav_msgs +{ + + class MapMetaData : public ros::Msg + { + public: + ros::Time map_load_time; + float resolution; + uint32_t width; + uint32_t height; + geometry_msgs::Pose origin; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->map_load_time.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->map_load_time.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->map_load_time.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->map_load_time.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->map_load_time.sec); + *(outbuffer + offset + 0) = (this->map_load_time.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->map_load_time.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->map_load_time.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->map_load_time.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->map_load_time.nsec); + union { + float real; + uint32_t base; + } u_resolution; + u_resolution.real = this->resolution; + *(outbuffer + offset + 0) = (u_resolution.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_resolution.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_resolution.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_resolution.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->resolution); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; + offset += sizeof(this->width); + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; + offset += sizeof(this->height); + offset += this->origin.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->map_load_time.sec = ((uint32_t) (*(inbuffer + offset))); + this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->map_load_time.sec); + this->map_load_time.nsec = ((uint32_t) (*(inbuffer + offset))); + this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->map_load_time.nsec); + union { + float real; + uint32_t base; + } u_resolution; + u_resolution.base = 0; + u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->resolution = u_resolution.real; + offset += sizeof(this->resolution); + this->width = ((uint32_t) (*(inbuffer + offset))); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->width); + this->height = ((uint32_t) (*(inbuffer + offset))); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->height); + offset += this->origin.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "nav_msgs/MapMetaData"; }; + const char * getMD5(){ return "10cfc8a2818024d3248802c00c95f11b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/OccupancyGrid.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,74 @@ +#ifndef _ROS_nav_msgs_OccupancyGrid_h +#define _ROS_nav_msgs_OccupancyGrid_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "nav_msgs/MapMetaData.h" + +namespace nav_msgs +{ + + class OccupancyGrid : public ros::Msg + { + public: + std_msgs::Header header; + nav_msgs::MapMetaData info; + uint8_t data_length; + int8_t st_data; + int8_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->info.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->info.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); + } + return offset; + } + + const char * getType(){ return "nav_msgs/OccupancyGrid"; }; + const char * getMD5(){ return "3381f2d731d4076ec5c71b0759edbe4e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/Odometry.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_nav_msgs_Odometry_h +#define _ROS_nav_msgs_Odometry_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/PoseWithCovariance.h" +#include "geometry_msgs/TwistWithCovariance.h" + +namespace nav_msgs +{ + + class Odometry : public ros::Msg + { + public: + std_msgs::Header header; + char * child_frame_id; + geometry_msgs::PoseWithCovariance pose; + geometry_msgs::TwistWithCovariance twist; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t length_child_frame_id = strlen( (const char*) this->child_frame_id); + memcpy(outbuffer + offset, &length_child_frame_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->child_frame_id, length_child_frame_id); + offset += length_child_frame_id; + offset += this->pose.serialize(outbuffer + offset); + offset += this->twist.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_child_frame_id; + memcpy(&length_child_frame_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_child_frame_id-1]=0; + this->child_frame_id = (char *)(inbuffer + offset-1); + offset += length_child_frame_id; + offset += this->pose.deserialize(inbuffer + offset); + offset += this->twist.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "nav_msgs/Odometry"; }; + const char * getMD5(){ return "cd5e73d190d741a2f92e81eda573aca7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/nav_msgs/Path.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,58 @@ +#ifndef _ROS_nav_msgs_Path_h +#define _ROS_nav_msgs_Path_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/PoseStamped.h" + +namespace nav_msgs +{ + + class Path : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t poses_length; + geometry_msgs::PoseStamped st_poses; + geometry_msgs::PoseStamped * poses; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = poses_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < poses_length; i++){ + offset += this->poses[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t poses_lengthT = *(inbuffer + offset++); + if(poses_lengthT > poses_length) + this->poses = (geometry_msgs::PoseStamped*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::PoseStamped)); + offset += 3; + poses_length = poses_lengthT; + for( uint8_t i = 0; i < poses_length; i++){ + offset += this->st_poses.deserialize(inbuffer + offset); + memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::PoseStamped)); + } + return offset; + } + + const char * getType(){ return "nav_msgs/Path"; }; + const char * getMD5(){ return "6227e2b7e9cce15051f669a5e197bbf7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/msg.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,53 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_MSG_H_ +#define _ROS_MSG_H_ + +namespace ros { + + /* Base Message Type */ + class Msg + { + public: + virtual int serialize(unsigned char *outbuffer) const = 0; + virtual int deserialize(unsigned char *data) = 0; + virtual const char * getType() = 0; + virtual const char * getMD5() = 0; + }; + +} + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/node_handle.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,535 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROS_NODE_HANDLE_H_ +#define ROS_NODE_HANDLE_H_ + +#include "std_msgs/Time.h" +#include "rosserial_msgs/TopicInfo.h" +#include "rosserial_msgs/Log.h" +#include "rosserial_msgs/RequestParam.h" + +#define SYNC_SECONDS 5 + +#define MODE_FIRST_FF 0 +/* + * The second sync byte is a protocol version. It's value is 0xff for the first + * version of the rosserial protocol (used up to hydro), 0xfe for the second version + * (introduced in hydro), 0xfd for the next, and so on. Its purpose is to enable + * detection of mismatched protocol versions (e.g. hydro rosserial_python with groovy + * rosserial_arduino. It must be changed in both this file and in + * rosserial_python/src/rosserial_python/SerialClient.py + */ +#define MODE_PROTOCOL_VER 1 +#define PROTOCOL_VER1 0xff // through groovy +#define PROTOCOL_VER2 0xfe // in hydro +#define PROTOCOL_VER PROTOCOL_VER2 +#define MODE_SIZE_L 2 +#define MODE_SIZE_H 3 +#define MODE_SIZE_CHECKSUM 4 // checksum for msg size received from size L and H +#define MODE_TOPIC_L 5 // waiting for topic id +#define MODE_TOPIC_H 6 +#define MODE_MESSAGE 7 +#define MODE_MSG_CHECKSUM 8 // checksum for msg and topic id + + + +#define MSG_TIMEOUT 20 //20 milliseconds to recieve all of message data + +#include "msg.h" + +namespace ros { + + class NodeHandleBase_{ + public: + virtual int publish(int id, const Msg* msg)=0; + virtual int spinOnce()=0; + virtual bool connected()=0; + }; +} + +#include "publisher.h" +#include "subscriber.h" +#include "service_server.h" +#include "service_client.h" + +namespace ros { + + using rosserial_msgs::TopicInfo; + + /* Node Handle */ + template<class Hardware, + int MAX_SUBSCRIBERS=25, + int MAX_PUBLISHERS=25, + int INPUT_SIZE=512, + int OUTPUT_SIZE=512> + class NodeHandle_ : public NodeHandleBase_ + { + protected: + Hardware hardware_; + + /* time used for syncing */ + unsigned long rt_time; + + /* used for computing current time */ + unsigned long sec_offset, nsec_offset; + + unsigned char message_in[INPUT_SIZE]; + unsigned char message_out[OUTPUT_SIZE]; + + Publisher * publishers[MAX_PUBLISHERS]; + Subscriber_ * subscribers[MAX_SUBSCRIBERS]; + + /* + * Setup Functions + */ + public: + NodeHandle_() : configured_(false) { + + for(unsigned int i=0; i< MAX_PUBLISHERS; i++) + publishers[i] = 0; + + for(unsigned int i=0; i< MAX_SUBSCRIBERS; i++) + subscribers[i] = 0; + + for(unsigned int i=0; i< INPUT_SIZE; i++) + message_in[i] = 0; + + for(unsigned int i=0; i< OUTPUT_SIZE; i++) + message_out[i] = 0; + + req_param_resp.ints_length = 0; + req_param_resp.ints = NULL; + req_param_resp.floats_length = 0; + req_param_resp.floats = NULL; + req_param_resp.ints_length = 0; + req_param_resp.ints = NULL; + } + + Hardware* getHardware(){ + return &hardware_; + } + + /* Start serial, initialize buffers */ + void initNode(){ + hardware_.init(); + mode_ = 0; + bytes_ = 0; + index_ = 0; + topic_ = 0; + }; + + /* Start a named port, which may be network server IP, initialize buffers */ + void initNode(char *portName){ + hardware_.init(portName); + mode_ = 0; + bytes_ = 0; + index_ = 0; + topic_ = 0; + }; + + protected: + //State machine variables for spinOnce + int mode_; + int bytes_; + int topic_; + int index_; + int checksum_; + + bool configured_; + + /* used for syncing the time */ + unsigned long last_sync_time; + unsigned long last_sync_receive_time; + unsigned long last_msg_timeout_time; + + public: + /* This function goes in your loop() function, it handles + * serial input and callbacks for subscribers. + */ + + + virtual int spinOnce(){ + + /* restart if timed out */ + unsigned long c_time = hardware_.time(); + if( (c_time - last_sync_receive_time) > (SYNC_SECONDS*2200) ){ + configured_ = false; + } + + /* reset if message has timed out */ + if ( mode_ != MODE_FIRST_FF){ + if (c_time > last_msg_timeout_time){ + mode_ = MODE_FIRST_FF; + } + } + + /* while available buffer, read data */ + while( true ) + { + int data = hardware_.read(); + if( data < 0 ) + break; + checksum_ += data; + if( mode_ == MODE_MESSAGE ){ /* message data being recieved */ + message_in[index_++] = data; + bytes_--; + if(bytes_ == 0) /* is message complete? if so, checksum */ + mode_ = MODE_MSG_CHECKSUM; + }else if( mode_ == MODE_FIRST_FF ){ + if(data == 0xff){ + mode_++; + last_msg_timeout_time = c_time + MSG_TIMEOUT; + } + }else if( mode_ == MODE_PROTOCOL_VER ){ + if(data == PROTOCOL_VER){ + mode_++; + }else{ + mode_ = MODE_FIRST_FF; + if (configured_ == false) + requestSyncTime(); /* send a msg back showing our protocol version */ + } + }else if( mode_ == MODE_SIZE_L ){ /* bottom half of message size */ + bytes_ = data; + index_ = 0; + mode_++; + checksum_ = data; /* first byte for calculating size checksum */ + }else if( mode_ == MODE_SIZE_H ){ /* top half of message size */ + bytes_ += data<<8; + mode_++; + }else if( mode_ == MODE_SIZE_CHECKSUM ){ + if( (checksum_%256) == 255) + mode_++; + else + mode_ = MODE_FIRST_FF; /* Abandon the frame if the msg len is wrong */ + }else if( mode_ == MODE_TOPIC_L ){ /* bottom half of topic id */ + topic_ = data; + mode_++; + checksum_ = data; /* first byte included in checksum */ + }else if( mode_ == MODE_TOPIC_H ){ /* top half of topic id */ + topic_ += data<<8; + mode_ = MODE_MESSAGE; + if(bytes_ == 0) + mode_ = MODE_MSG_CHECKSUM; + }else if( mode_ == MODE_MSG_CHECKSUM ){ /* do checksum */ + mode_ = MODE_FIRST_FF; + if( (checksum_%256) == 255){ + if(topic_ == TopicInfo::ID_PUBLISHER){ + requestSyncTime(); + negotiateTopics(); + last_sync_time = c_time; + last_sync_receive_time = c_time; + return -1; + }else if(topic_ == TopicInfo::ID_TIME){ + syncTime(message_in); + }else if (topic_ == TopicInfo::ID_PARAMETER_REQUEST){ + req_param_resp.deserialize(message_in); + param_recieved= true; + }else{ + if(subscribers[topic_-100]) + subscribers[topic_-100]->callback( message_in ); + } + } + } + } + + /* occasionally sync time */ + if( configured_ && ((c_time-last_sync_time) > (SYNC_SECONDS*500) )){ + requestSyncTime(); + last_sync_time = c_time; + } + + return 0; + } + + + /* Are we connected to the PC? */ + virtual bool connected() { + return configured_; + }; + + /******************************************************************** + * Time functions + */ + + void requestSyncTime() + { + std_msgs::Time t; + publish(TopicInfo::ID_TIME, &t); + rt_time = hardware_.time(); + } + + void syncTime( unsigned char * data ) + { + std_msgs::Time t; + unsigned long offset = hardware_.time() - rt_time; + + t.deserialize(data); + t.data.sec += offset/1000; + t.data.nsec += (offset%1000)*1000000UL; + + this->setNow(t.data); + last_sync_receive_time = hardware_.time(); + } + + Time now(){ + unsigned long ms = hardware_.time(); + Time current_time; + current_time.sec = ms/1000 + sec_offset; + current_time.nsec = (ms%1000)*1000000UL + nsec_offset; + normalizeSecNSec(current_time.sec, current_time.nsec); + return current_time; + } + + void setNow( Time & new_now ) + { + unsigned long ms = hardware_.time(); + sec_offset = new_now.sec - ms/1000 - 1; + nsec_offset = new_now.nsec - (ms%1000)*1000000UL + 1000000000UL; + normalizeSecNSec(sec_offset, nsec_offset); + } + + /******************************************************************** + * Topic Management + */ + + /* Register a new publisher */ + bool advertise(Publisher & p) + { + for(int i = 0; i < MAX_PUBLISHERS; i++){ + if(publishers[i] == 0){ // empty slot + publishers[i] = &p; + p.id_ = i+100+MAX_SUBSCRIBERS; + p.nh_ = this; + return true; + } + } + return false; + } + + /* Register a new subscriber */ + template<typename MsgT> + bool subscribe(Subscriber< MsgT> & s){ + for(int i = 0; i < MAX_SUBSCRIBERS; i++){ + if(subscribers[i] == 0){ // empty slot + subscribers[i] = (Subscriber_*) &s; + s.id_ = i+100; + return true; + } + } + return false; + } + + /* Register a new Service Server */ + template<typename MReq, typename MRes> + bool advertiseService(ServiceServer<MReq,MRes>& srv){ + bool v = advertise(srv.pub); + for(int i = 0; i < MAX_SUBSCRIBERS; i++){ + if(subscribers[i] == 0){ // empty slot + subscribers[i] = (Subscriber_*) &srv; + srv.id_ = i+100; + return v; + } + } + return false; + } + + /* Register a new Service Client */ + template<typename MReq, typename MRes> + bool serviceClient(ServiceClient<MReq, MRes>& srv){ + bool v = advertise(srv.pub); + for(int i = 0; i < MAX_SUBSCRIBERS; i++){ + if(subscribers[i] == 0){ // empty slot + subscribers[i] = (Subscriber_*) &srv; + srv.id_ = i+100; + return v; + } + } + return false; + } + + void negotiateTopics() + { + rosserial_msgs::TopicInfo ti; + int i; + for(i = 0; i < MAX_PUBLISHERS; i++) + { + if(publishers[i] != 0) // non-empty slot + { + ti.topic_id = publishers[i]->id_; + ti.topic_name = (char *) publishers[i]->topic_; + ti.message_type = (char *) publishers[i]->msg_->getType(); + ti.md5sum = (char *) publishers[i]->msg_->getMD5(); + ti.buffer_size = OUTPUT_SIZE; + publish( publishers[i]->getEndpointType(), &ti ); + } + } + for(i = 0; i < MAX_SUBSCRIBERS; i++) + { + if(subscribers[i] != 0) // non-empty slot + { + ti.topic_id = subscribers[i]->id_; + ti.topic_name = (char *) subscribers[i]->topic_; + ti.message_type = (char *) subscribers[i]->getMsgType(); + ti.md5sum = (char *) subscribers[i]->getMsgMD5(); + ti.buffer_size = INPUT_SIZE; + publish( subscribers[i]->getEndpointType(), &ti ); + } + } + configured_ = true; + } + + virtual int publish(int id, const Msg * msg) + { + if(id >= 100 && !configured_) + return 0; + + /* serialize message */ + int l = msg->serialize(message_out+7); + + /* setup the header */ + message_out[0] = 0xff; + message_out[1] = PROTOCOL_VER; + message_out[2] = (unsigned char) l&255; + message_out[3] = (unsigned char) l>>8; + message_out[4] = 255 - ((message_out[2] + message_out[3])%256); + message_out[5] = (unsigned char) id&255; + message_out[6] = ((unsigned char) id>>8); + + /* calculate checksum */ + int chk = 0; + for(int i =5; i<l+7; i++) + chk += message_out[i]; + l += 7; + message_out[l++] = 255 - (chk%256); + + if( l <= OUTPUT_SIZE ){ + hardware_.write(message_out, l); + return l; + }else{ + logerror("Message from device dropped: message larger than buffer."); + return -1; + } + } + + /******************************************************************** + * Logging + */ + + private: + void log(char byte, const char * msg){ + rosserial_msgs::Log l; + l.level= byte; + l.msg = (char*)msg; + publish(rosserial_msgs::TopicInfo::ID_LOG, &l); + } + + public: + void logdebug(const char* msg){ + log(rosserial_msgs::Log::ROSDEBUG, msg); + } + void loginfo(const char * msg){ + log(rosserial_msgs::Log::INFO, msg); + } + void logwarn(const char *msg){ + log(rosserial_msgs::Log::WARN, msg); + } + void logerror(const char*msg){ + log(rosserial_msgs::Log::ERROR, msg); + } + void logfatal(const char*msg){ + log(rosserial_msgs::Log::FATAL, msg); + } + + /******************************************************************** + * Parameters + */ + + private: + bool param_recieved; + rosserial_msgs::RequestParamResponse req_param_resp; + + bool requestParam(const char * name, int time_out = 1000){ + param_recieved = false; + rosserial_msgs::RequestParamRequest req; + req.name = (char*)name; + publish(TopicInfo::ID_PARAMETER_REQUEST, &req); + unsigned int end_time = hardware_.time() + time_out; + while(!param_recieved ){ + spinOnce(); + if (hardware_.time() > end_time) return false; + } + return true; + } + + public: + bool getParam(const char* name, int* param, int length =1){ + if (requestParam(name) ){ + if (length == req_param_resp.ints_length){ + //copy it over + for(int i=0; i<length; i++) + param[i] = req_param_resp.ints[i]; + return true; + } + } + return false; + } + bool getParam(const char* name, float* param, int length=1){ + if (requestParam(name) ){ + if (length == req_param_resp.floats_length){ + //copy it over + for(int i=0; i<length; i++) + param[i] = req_param_resp.floats[i]; + return true; + } + } + return false; + } + bool getParam(const char* name, char** param, int length=1){ + if (requestParam(name) ){ + if (length == req_param_resp.strings_length){ + //copy it over + for(int i=0; i<length; i++) + strcpy(param[i],req_param_resp.strings[i]); + return true; + } + } + return false; + } + }; + +} + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/publisher.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,68 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_PUBLISHER_H_ +#define _ROS_PUBLISHER_H_ + +#include "rosserial_msgs/TopicInfo.h" +#include "node_handle.h" + +namespace ros { + + /* Generic Publisher */ + class Publisher + { + public: + Publisher( const char * topic_name, Msg * msg, int endpoint=rosserial_msgs::TopicInfo::ID_PUBLISHER) : + topic_(topic_name), + msg_(msg), + endpoint_(endpoint) {}; + + int publish( const Msg * msg ) { return nh_->publish(id_, msg); }; + int getEndpointType(){ return endpoint_; } + + const char * topic_; + Msg *msg_; + // id_ and no_ are set by NodeHandle when we advertise + int id_; + NodeHandleBase_* nh_; + + private: + int endpoint_; + }; + +} + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/service_client.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,84 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_SERVICE_CLIENT_H_ +#define _ROS_SERVICE_CLIENT_H_ + +#include "rosserial_msgs/TopicInfo.h" + +#include "publisher.h" +#include "subscriber.h" + +namespace ros { + + template<typename MReq , typename MRes> + class ServiceClient : public Subscriber_ { + public: + ServiceClient(const char* topic_name) : + pub(topic_name, &req, rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT + rosserial_msgs::TopicInfo::ID_PUBLISHER) + { + this->topic_ = topic_name; + this->waiting = true; + } + + virtual void call(const MReq & request, MRes & response) + { + if(!pub.nh_->connected()) return; + ret = &response; + waiting = true; + pub.publish(&request); + while(waiting && pub.nh_->connected()) + if(pub.nh_->spinOnce() < 0) break; + } + + // these refer to the subscriber + virtual void callback(unsigned char *data){ + ret->deserialize(data); + waiting = false; + } + virtual const char * getMsgType(){ return this->resp.getType(); } + virtual const char * getMsgMD5(){ return this->resp.getMD5(); } + virtual int getEndpointType(){ return rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT + rosserial_msgs::TopicInfo::ID_SUBSCRIBER; } + + MReq req; + MRes resp; + MRes * ret; + bool waiting; + Publisher pub; + }; + +} + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/service_server.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,77 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _ROS_SERVICE_SERVER_H_ +#define _ROS_SERVICE_SERVER_H_ + +#include "rosserial_msgs/TopicInfo.h" + +#include "publisher.h" +#include "subscriber.h" + +namespace ros { + + template<typename MReq , typename MRes> + class ServiceServer : public Subscriber_ { + public: + typedef void(*CallbackT)(const MReq&, MRes&); + + ServiceServer(const char* topic_name, CallbackT cb) : + pub(topic_name, &resp, rosserial_msgs::TopicInfo::ID_SERVICE_SERVER + rosserial_msgs::TopicInfo::ID_PUBLISHER) + { + this->topic_ = topic_name; + this->cb_ = cb; + } + + // these refer to the subscriber + virtual void callback(unsigned char *data){ + req.deserialize(data); + cb_(req,resp); + pub.publish(&resp); + } + virtual const char * getMsgType(){ return this->req.getType(); } + virtual const char * getMsgMD5(){ return this->req.getMD5(); } + virtual int getEndpointType(){ return rosserial_msgs::TopicInfo::ID_SERVICE_SERVER + rosserial_msgs::TopicInfo::ID_SUBSCRIBER; } + + MReq req; + MRes resp; + Publisher pub; + private: + CallbackT cb_; + }; + +} + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros/subscriber.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,89 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROS_SUBSCRIBER_H_ +#define ROS_SUBSCRIBER_H_ + +#include "rosserial_msgs/TopicInfo.h" + +namespace ros { + + /* Base class for objects subscribers. */ + class Subscriber_ + { + public: + virtual void callback(unsigned char *data)=0; + virtual int getEndpointType()=0; + + // id_ is set by NodeHandle when we advertise + int id_; + + virtual const char * getMsgType()=0; + virtual const char * getMsgMD5()=0; + const char * topic_; + }; + + + /* Actual subscriber, templated on message type. */ + template<typename MsgT> + class Subscriber: public Subscriber_{ + public: + typedef void(*CallbackT)(const MsgT&); + MsgT msg; + + Subscriber(const char * topic_name, CallbackT cb, int endpoint=rosserial_msgs::TopicInfo::ID_SUBSCRIBER) : + cb_(cb), + endpoint_(endpoint) + { + topic_ = topic_name; + }; + + virtual void callback(unsigned char* data){ + msg.deserialize(data); + this->cb_(msg); + } + + virtual const char * getMsgType(){ return this->msg.getType(); } + virtual const char * getMsgMD5(){ return this->msg.getMD5(); } + virtual int getEndpointType(){ return endpoint_; } + + private: + CallbackT cb_; + int endpoint_; + }; + +} + +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/roscpp/Empty.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,63 @@ +#ifndef _ROS_SERVICE_Empty_h +#define _ROS_SERVICE_Empty_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace roscpp +{ + +static const char EMPTY[] = "roscpp/Empty"; + + class EmptyRequest : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return EMPTY; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class EmptyResponse : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return EMPTY; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class Empty { + public: + typedef EmptyRequest Request; + typedef EmptyResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/roscpp/GetLoggers.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,83 @@ +#ifndef _ROS_SERVICE_GetLoggers_h +#define _ROS_SERVICE_GetLoggers_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "roscpp/Logger.h" + +namespace roscpp +{ + +static const char GETLOGGERS[] = "roscpp/GetLoggers"; + + class GetLoggersRequest : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return GETLOGGERS; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class GetLoggersResponse : public ros::Msg + { + public: + uint8_t loggers_length; + roscpp::Logger st_loggers; + roscpp::Logger * loggers; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = loggers_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < loggers_length; i++){ + offset += this->loggers[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t loggers_lengthT = *(inbuffer + offset++); + if(loggers_lengthT > loggers_length) + this->loggers = (roscpp::Logger*)realloc(this->loggers, loggers_lengthT * sizeof(roscpp::Logger)); + offset += 3; + loggers_length = loggers_lengthT; + for( uint8_t i = 0; i < loggers_length; i++){ + offset += this->st_loggers.deserialize(inbuffer + offset); + memcpy( &(this->loggers[i]), &(this->st_loggers), sizeof(roscpp::Logger)); + } + return offset; + } + + const char * getType(){ return GETLOGGERS; }; + const char * getMD5(){ return "32e97e85527d4678a8f9279894bb64b0"; }; + + }; + + class GetLoggers { + public: + typedef GetLoggersRequest Request; + typedef GetLoggersResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/roscpp/Logger.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_roscpp_Logger_h +#define _ROS_roscpp_Logger_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace roscpp +{ + + class Logger : public ros::Msg + { + public: + char * name; + char * level; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen( (const char*) this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_level = strlen( (const char*) this->level); + memcpy(outbuffer + offset, &length_level, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->level, length_level); + offset += length_level; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_level; + memcpy(&length_level, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_level; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_level-1]=0; + this->level = (char *)(inbuffer + offset-1); + offset += length_level; + return offset; + } + + const char * getType(){ return "roscpp/Logger"; }; + const char * getMD5(){ return "a6069a2ff40db7bd32143dd66e1f408e"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/roscpp/SetLoggerLevel.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,93 @@ +#ifndef _ROS_SERVICE_SetLoggerLevel_h +#define _ROS_SERVICE_SetLoggerLevel_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace roscpp +{ + +static const char SETLOGGERLEVEL[] = "roscpp/SetLoggerLevel"; + + class SetLoggerLevelRequest : public ros::Msg + { + public: + char * logger; + char * level; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_logger = strlen( (const char*) this->logger); + memcpy(outbuffer + offset, &length_logger, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->logger, length_logger); + offset += length_logger; + uint32_t length_level = strlen( (const char*) this->level); + memcpy(outbuffer + offset, &length_level, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->level, length_level); + offset += length_level; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_logger; + memcpy(&length_logger, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_logger; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_logger-1]=0; + this->logger = (char *)(inbuffer + offset-1); + offset += length_logger; + uint32_t length_level; + memcpy(&length_level, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_level; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_level-1]=0; + this->level = (char *)(inbuffer + offset-1); + offset += length_level; + return offset; + } + + const char * getType(){ return SETLOGGERLEVEL; }; + const char * getMD5(){ return "51da076440d78ca1684d36c868df61ea"; }; + + }; + + class SetLoggerLevelResponse : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return SETLOGGERLEVEL; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class SetLoggerLevel { + public: + typedef SetLoggerLevelRequest Request; + typedef SetLoggerLevelResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosgraph_msgs/Clock.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,56 @@ +#ifndef _ROS_rosgraph_msgs_Clock_h +#define _ROS_rosgraph_msgs_Clock_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" + +namespace rosgraph_msgs +{ + + class Clock : public ros::Msg + { + public: + ros::Time clock; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->clock.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->clock.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->clock.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->clock.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->clock.sec); + *(outbuffer + offset + 0) = (this->clock.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->clock.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->clock.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->clock.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->clock.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->clock.sec = ((uint32_t) (*(inbuffer + offset))); + this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->clock.sec); + this->clock.nsec = ((uint32_t) (*(inbuffer + offset))); + this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->clock.nsec); + return offset; + } + + const char * getType(){ return "rosgraph_msgs/Clock"; }; + const char * getMD5(){ return "a9c97c1d230cfc112e270351a944ee47"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosgraph_msgs/Log.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,161 @@ +#ifndef _ROS_rosgraph_msgs_Log_h +#define _ROS_rosgraph_msgs_Log_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace rosgraph_msgs +{ + + class Log : public ros::Msg + { + public: + std_msgs::Header header; + int8_t level; + char * name; + char * msg; + char * file; + char * function; + uint32_t line; + uint8_t topics_length; + char* st_topics; + char* * topics; + enum { DEBUG = 1 }; + enum { INFO = 2 }; + enum { WARN = 4 }; + enum { ERROR = 8 }; + enum { FATAL = 16 }; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + int8_t real; + uint8_t base; + } u_level; + u_level.real = this->level; + *(outbuffer + offset + 0) = (u_level.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->level); + uint32_t length_name = strlen( (const char*) this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_msg = strlen( (const char*) this->msg); + memcpy(outbuffer + offset, &length_msg, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->msg, length_msg); + offset += length_msg; + uint32_t length_file = strlen( (const char*) this->file); + memcpy(outbuffer + offset, &length_file, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->file, length_file); + offset += length_file; + uint32_t length_function = strlen( (const char*) this->function); + memcpy(outbuffer + offset, &length_function, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->function, length_function); + offset += length_function; + *(outbuffer + offset + 0) = (this->line >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->line >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->line >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->line >> (8 * 3)) & 0xFF; + offset += sizeof(this->line); + *(outbuffer + offset++) = topics_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < topics_length; i++){ + uint32_t length_topicsi = strlen( (const char*) this->topics[i]); + memcpy(outbuffer + offset, &length_topicsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->topics[i], length_topicsi); + offset += length_topicsi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + int8_t real; + uint8_t base; + } u_level; + u_level.base = 0; + u_level.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->level = u_level.real; + offset += sizeof(this->level); + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_msg; + memcpy(&length_msg, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_msg; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_msg-1]=0; + this->msg = (char *)(inbuffer + offset-1); + offset += length_msg; + uint32_t length_file; + memcpy(&length_file, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_file; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_file-1]=0; + this->file = (char *)(inbuffer + offset-1); + offset += length_file; + uint32_t length_function; + memcpy(&length_function, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_function; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_function-1]=0; + this->function = (char *)(inbuffer + offset-1); + offset += length_function; + this->line = ((uint32_t) (*(inbuffer + offset))); + this->line |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->line |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->line |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->line); + uint8_t topics_lengthT = *(inbuffer + offset++); + if(topics_lengthT > topics_length) + this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*)); + offset += 3; + topics_length = topics_lengthT; + for( uint8_t i = 0; i < topics_length; i++){ + uint32_t length_st_topics; + memcpy(&length_st_topics, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_topics; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_topics-1]=0; + this->st_topics = (char *)(inbuffer + offset-1); + offset += length_st_topics; + memcpy( &(this->topics[i]), &(this->st_topics), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return "rosgraph_msgs/Log"; }; + const char * getMD5(){ return "acffd30cd6b6de30f120938c17c593fb"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/CameraInfo.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,239 @@ +#ifndef _ROS_sensor_msgs_CameraInfo_h +#define _ROS_sensor_msgs_CameraInfo_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "sensor_msgs/RegionOfInterest.h" + +namespace sensor_msgs +{ + + class CameraInfo : public ros::Msg + { + public: + std_msgs::Header header; + uint32_t height; + uint32_t width; + char * distortion_model; + uint8_t D_length; + float st_D; + float * D; + float K[9]; + float R[9]; + float P[12]; + uint32_t binning_x; + uint32_t binning_y; + sensor_msgs::RegionOfInterest roi; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; + offset += sizeof(this->height); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; + offset += sizeof(this->width); + uint32_t length_distortion_model = strlen( (const char*) this->distortion_model); + memcpy(outbuffer + offset, &length_distortion_model, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->distortion_model, length_distortion_model); + offset += length_distortion_model; + *(outbuffer + offset++) = D_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < D_length; i++){ + int32_t * val_Di = (int32_t *) &(this->D[i]); + int32_t exp_Di = (((*val_Di)>>23)&255); + if(exp_Di != 0) + exp_Di += 1023-127; + int32_t sig_Di = *val_Di; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_Di<<5) & 0xff; + *(outbuffer + offset++) = (sig_Di>>3) & 0xff; + *(outbuffer + offset++) = (sig_Di>>11) & 0xff; + *(outbuffer + offset++) = ((exp_Di<<4) & 0xF0) | ((sig_Di>>19)&0x0F); + *(outbuffer + offset++) = (exp_Di>>4) & 0x7F; + if(this->D[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + unsigned char * K_val = (unsigned char *) this->K; + for( uint8_t i = 0; i < 9; i++){ + int32_t * val_Ki = (int32_t *) &(this->K[i]); + int32_t exp_Ki = (((*val_Ki)>>23)&255); + if(exp_Ki != 0) + exp_Ki += 1023-127; + int32_t sig_Ki = *val_Ki; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_Ki<<5) & 0xff; + *(outbuffer + offset++) = (sig_Ki>>3) & 0xff; + *(outbuffer + offset++) = (sig_Ki>>11) & 0xff; + *(outbuffer + offset++) = ((exp_Ki<<4) & 0xF0) | ((sig_Ki>>19)&0x0F); + *(outbuffer + offset++) = (exp_Ki>>4) & 0x7F; + if(this->K[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + unsigned char * R_val = (unsigned char *) this->R; + for( uint8_t i = 0; i < 9; i++){ + int32_t * val_Ri = (int32_t *) &(this->R[i]); + int32_t exp_Ri = (((*val_Ri)>>23)&255); + if(exp_Ri != 0) + exp_Ri += 1023-127; + int32_t sig_Ri = *val_Ri; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_Ri<<5) & 0xff; + *(outbuffer + offset++) = (sig_Ri>>3) & 0xff; + *(outbuffer + offset++) = (sig_Ri>>11) & 0xff; + *(outbuffer + offset++) = ((exp_Ri<<4) & 0xF0) | ((sig_Ri>>19)&0x0F); + *(outbuffer + offset++) = (exp_Ri>>4) & 0x7F; + if(this->R[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + unsigned char * P_val = (unsigned char *) this->P; + for( uint8_t i = 0; i < 12; i++){ + int32_t * val_Pi = (int32_t *) &(this->P[i]); + int32_t exp_Pi = (((*val_Pi)>>23)&255); + if(exp_Pi != 0) + exp_Pi += 1023-127; + int32_t sig_Pi = *val_Pi; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_Pi<<5) & 0xff; + *(outbuffer + offset++) = (sig_Pi>>3) & 0xff; + *(outbuffer + offset++) = (sig_Pi>>11) & 0xff; + *(outbuffer + offset++) = ((exp_Pi<<4) & 0xF0) | ((sig_Pi>>19)&0x0F); + *(outbuffer + offset++) = (exp_Pi>>4) & 0x7F; + if(this->P[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + *(outbuffer + offset + 0) = (this->binning_x >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->binning_x >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->binning_x >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->binning_x >> (8 * 3)) & 0xFF; + offset += sizeof(this->binning_x); + *(outbuffer + offset + 0) = (this->binning_y >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->binning_y >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->binning_y >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->binning_y >> (8 * 3)) & 0xFF; + offset += sizeof(this->binning_y); + offset += this->roi.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + this->height = ((uint32_t) (*(inbuffer + offset))); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->height); + this->width = ((uint32_t) (*(inbuffer + offset))); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->width); + uint32_t length_distortion_model; + memcpy(&length_distortion_model, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_distortion_model; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_distortion_model-1]=0; + this->distortion_model = (char *)(inbuffer + offset-1); + offset += length_distortion_model; + uint8_t D_lengthT = *(inbuffer + offset++); + if(D_lengthT > D_length) + this->D = (float*)realloc(this->D, D_lengthT * sizeof(float)); + offset += 3; + D_length = D_lengthT; + for( uint8_t i = 0; i < D_length; i++){ + uint32_t * val_st_D = (uint32_t*) &(this->st_D); + offset += 3; + *val_st_D = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_st_D |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_st_D |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_st_D |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_st_D = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_st_D |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_st_D !=0) + *val_st_D |= ((exp_st_D)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_D = -this->st_D; + memcpy( &(this->D[i]), &(this->st_D), sizeof(float)); + } + uint8_t * K_val = (uint8_t*) this->K; + for( uint8_t i = 0; i < 9; i++){ + uint32_t * val_Ki = (uint32_t*) &(this->K[i]); + offset += 3; + *val_Ki = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_Ki |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_Ki |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_Ki |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_Ki = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_Ki |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_Ki !=0) + *val_Ki |= ((exp_Ki)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->K[i] = -this->K[i]; + } + uint8_t * R_val = (uint8_t*) this->R; + for( uint8_t i = 0; i < 9; i++){ + uint32_t * val_Ri = (uint32_t*) &(this->R[i]); + offset += 3; + *val_Ri = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_Ri |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_Ri |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_Ri |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_Ri = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_Ri |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_Ri !=0) + *val_Ri |= ((exp_Ri)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->R[i] = -this->R[i]; + } + uint8_t * P_val = (uint8_t*) this->P; + for( uint8_t i = 0; i < 12; i++){ + uint32_t * val_Pi = (uint32_t*) &(this->P[i]); + offset += 3; + *val_Pi = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_Pi |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_Pi |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_Pi |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_Pi = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_Pi |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_Pi !=0) + *val_Pi |= ((exp_Pi)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->P[i] = -this->P[i]; + } + this->binning_x = ((uint32_t) (*(inbuffer + offset))); + this->binning_x |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->binning_x |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->binning_x |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->binning_x); + this->binning_y = ((uint32_t) (*(inbuffer + offset))); + this->binning_y |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->binning_y |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->binning_y |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->binning_y); + offset += this->roi.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return "sensor_msgs/CameraInfo"; }; + const char * getMD5(){ return "c9a58c1b0b154e0e6da7578cb991d214"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/ChannelFloat32.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,87 @@ +#ifndef _ROS_sensor_msgs_ChannelFloat32_h +#define _ROS_sensor_msgs_ChannelFloat32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace sensor_msgs +{ + + class ChannelFloat32 : public ros::Msg + { + public: + char * name; + uint8_t values_length; + float st_values; + float * values; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen( (const char*) this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + *(outbuffer + offset++) = values_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < values_length; i++){ + union { + float real; + uint32_t base; + } u_valuesi; + u_valuesi.real = this->values[i]; + *(outbuffer + offset + 0) = (u_valuesi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_valuesi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_valuesi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_valuesi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->values[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint8_t values_lengthT = *(inbuffer + offset++); + if(values_lengthT > values_length) + this->values = (float*)realloc(this->values, values_lengthT * sizeof(float)); + offset += 3; + values_length = values_lengthT; + for( uint8_t i = 0; i < values_length; i++){ + union { + float real; + uint32_t base; + } u_st_values; + u_st_values.base = 0; + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_values = u_st_values.real; + offset += sizeof(this->st_values); + memcpy( &(this->values[i]), &(this->st_values), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/ChannelFloat32"; }; + const char * getMD5(){ return "3d40139cdd33dfedcb71ffeeeb42ae7f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/CompressedImage.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,74 @@ +#ifndef _ROS_sensor_msgs_CompressedImage_h +#define _ROS_sensor_msgs_CompressedImage_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class CompressedImage : public ros::Msg + { + public: + std_msgs::Header header; + char * format; + uint8_t data_length; + uint8_t st_data; + uint8_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + uint32_t length_format = strlen( (const char*) this->format); + memcpy(outbuffer + offset, &length_format, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->format, length_format); + offset += length_format; + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint32_t length_format; + memcpy(&length_format, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_format; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_format-1]=0; + this->format = (char *)(inbuffer + offset-1); + offset += length_format; + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/CompressedImage"; }; + const char * getMD5(){ return "8f7a12909da2c9d3332d540a0977563f"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/Image.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,112 @@ +#ifndef _ROS_sensor_msgs_Image_h +#define _ROS_sensor_msgs_Image_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class Image : public ros::Msg + { + public: + std_msgs::Header header; + uint32_t height; + uint32_t width; + char * encoding; + uint8_t is_bigendian; + uint32_t step; + uint8_t data_length; + uint8_t st_data; + uint8_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; + offset += sizeof(this->height); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; + offset += sizeof(this->width); + uint32_t length_encoding = strlen( (const char*) this->encoding); + memcpy(outbuffer + offset, &length_encoding, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->encoding, length_encoding); + offset += length_encoding; + *(outbuffer + offset + 0) = (this->is_bigendian >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_bigendian); + *(outbuffer + offset + 0) = (this->step >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->step >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->step >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->step >> (8 * 3)) & 0xFF; + offset += sizeof(this->step); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + this->height = ((uint32_t) (*(inbuffer + offset))); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->height); + this->width = ((uint32_t) (*(inbuffer + offset))); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->width); + uint32_t length_encoding; + memcpy(&length_encoding, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_encoding; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_encoding-1]=0; + this->encoding = (char *)(inbuffer + offset-1); + offset += length_encoding; + this->is_bigendian = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->is_bigendian); + this->step = ((uint32_t) (*(inbuffer + offset))); + this->step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->step); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/Image"; }; + const char * getMD5(){ return "060021388200f6f0f447d0fcd9c64743"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/Imu.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,145 @@ +#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 "std_msgs/Header.h" +#include "geometry_msgs/Quaternion.h" +#include "geometry_msgs/Vector3.h" + +namespace sensor_msgs +{ + + class Imu : public ros::Msg + { + public: + std_msgs::Header header; + geometry_msgs::Quaternion orientation; + float orientation_covariance[9]; + geometry_msgs::Vector3 angular_velocity; + float angular_velocity_covariance[9]; + geometry_msgs::Vector3 linear_acceleration; + float linear_acceleration_covariance[9]; + + 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( uint8_t i = 0; i < 9; i++){ + int32_t * val_orientation_covariancei = (int32_t *) &(this->orientation_covariance[i]); + int32_t exp_orientation_covariancei = (((*val_orientation_covariancei)>>23)&255); + if(exp_orientation_covariancei != 0) + exp_orientation_covariancei += 1023-127; + int32_t sig_orientation_covariancei = *val_orientation_covariancei; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_orientation_covariancei<<5) & 0xff; + *(outbuffer + offset++) = (sig_orientation_covariancei>>3) & 0xff; + *(outbuffer + offset++) = (sig_orientation_covariancei>>11) & 0xff; + *(outbuffer + offset++) = ((exp_orientation_covariancei<<4) & 0xF0) | ((sig_orientation_covariancei>>19)&0x0F); + *(outbuffer + offset++) = (exp_orientation_covariancei>>4) & 0x7F; + if(this->orientation_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + offset += this->angular_velocity.serialize(outbuffer + offset); + unsigned char * angular_velocity_covariance_val = (unsigned char *) this->angular_velocity_covariance; + for( uint8_t i = 0; i < 9; i++){ + int32_t * val_angular_velocity_covariancei = (int32_t *) &(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; + int32_t sig_angular_velocity_covariancei = *val_angular_velocity_covariancei; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_angular_velocity_covariancei<<5) & 0xff; + *(outbuffer + offset++) = (sig_angular_velocity_covariancei>>3) & 0xff; + *(outbuffer + offset++) = (sig_angular_velocity_covariancei>>11) & 0xff; + *(outbuffer + offset++) = ((exp_angular_velocity_covariancei<<4) & 0xF0) | ((sig_angular_velocity_covariancei>>19)&0x0F); + *(outbuffer + offset++) = (exp_angular_velocity_covariancei>>4) & 0x7F; + if(this->angular_velocity_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + offset += this->linear_acceleration.serialize(outbuffer + offset); + unsigned char * linear_acceleration_covariance_val = (unsigned char *) this->linear_acceleration_covariance; + for( uint8_t i = 0; i < 9; i++){ + int32_t * val_linear_acceleration_covariancei = (int32_t *) &(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; + int32_t sig_linear_acceleration_covariancei = *val_linear_acceleration_covariancei; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_linear_acceleration_covariancei<<5) & 0xff; + *(outbuffer + offset++) = (sig_linear_acceleration_covariancei>>3) & 0xff; + *(outbuffer + offset++) = (sig_linear_acceleration_covariancei>>11) & 0xff; + *(outbuffer + offset++) = ((exp_linear_acceleration_covariancei<<4) & 0xF0) | ((sig_linear_acceleration_covariancei>>19)&0x0F); + *(outbuffer + offset++) = (exp_linear_acceleration_covariancei>>4) & 0x7F; + if(this->linear_acceleration_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->orientation.deserialize(inbuffer + offset); + 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 = ((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); + 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 = ((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); + 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 = ((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]; + } + return offset; + } + + const char * getType(){ return "sensor_msgs/Imu"; }; + const char * getMD5(){ return "6a62c6daae103f4ff57a132d6f95cec2"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/JointState.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,195 @@ +#ifndef _ROS_sensor_msgs_JointState_h +#define _ROS_sensor_msgs_JointState_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class JointState : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t name_length; + char* st_name; + char* * name; + uint8_t position_length; + float st_position; + float * position; + uint8_t velocity_length; + float st_velocity; + float * velocity; + uint8_t effort_length; + float st_effort; + float * effort; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = name_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < name_length; i++){ + uint32_t length_namei = strlen( (const char*) this->name[i]); + memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name[i], length_namei); + offset += length_namei; + } + *(outbuffer + offset++) = position_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < position_length; i++){ + int32_t * val_positioni = (int32_t *) &(this->position[i]); + int32_t exp_positioni = (((*val_positioni)>>23)&255); + if(exp_positioni != 0) + exp_positioni += 1023-127; + int32_t sig_positioni = *val_positioni; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_positioni<<5) & 0xff; + *(outbuffer + offset++) = (sig_positioni>>3) & 0xff; + *(outbuffer + offset++) = (sig_positioni>>11) & 0xff; + *(outbuffer + offset++) = ((exp_positioni<<4) & 0xF0) | ((sig_positioni>>19)&0x0F); + *(outbuffer + offset++) = (exp_positioni>>4) & 0x7F; + if(this->position[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + *(outbuffer + offset++) = velocity_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < velocity_length; i++){ + int32_t * val_velocityi = (int32_t *) &(this->velocity[i]); + int32_t exp_velocityi = (((*val_velocityi)>>23)&255); + if(exp_velocityi != 0) + exp_velocityi += 1023-127; + int32_t sig_velocityi = *val_velocityi; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_velocityi<<5) & 0xff; + *(outbuffer + offset++) = (sig_velocityi>>3) & 0xff; + *(outbuffer + offset++) = (sig_velocityi>>11) & 0xff; + *(outbuffer + offset++) = ((exp_velocityi<<4) & 0xF0) | ((sig_velocityi>>19)&0x0F); + *(outbuffer + offset++) = (exp_velocityi>>4) & 0x7F; + if(this->velocity[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + *(outbuffer + offset++) = effort_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < effort_length; i++){ + int32_t * val_efforti = (int32_t *) &(this->effort[i]); + int32_t exp_efforti = (((*val_efforti)>>23)&255); + if(exp_efforti != 0) + exp_efforti += 1023-127; + int32_t sig_efforti = *val_efforti; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_efforti<<5) & 0xff; + *(outbuffer + offset++) = (sig_efforti>>3) & 0xff; + *(outbuffer + offset++) = (sig_efforti>>11) & 0xff; + *(outbuffer + offset++) = ((exp_efforti<<4) & 0xF0) | ((sig_efforti>>19)&0x0F); + *(outbuffer + offset++) = (exp_efforti>>4) & 0x7F; + if(this->effort[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t name_lengthT = *(inbuffer + offset++); + if(name_lengthT > name_length) + this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); + offset += 3; + name_length = name_lengthT; + for( uint8_t i = 0; i < name_length; i++){ + uint32_t length_st_name; + memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_name-1]=0; + this->st_name = (char *)(inbuffer + offset-1); + offset += length_st_name; + memcpy( &(this->name[i]), &(this->st_name), sizeof(char*)); + } + uint8_t position_lengthT = *(inbuffer + offset++); + if(position_lengthT > position_length) + this->position = (float*)realloc(this->position, position_lengthT * sizeof(float)); + offset += 3; + position_length = position_lengthT; + for( uint8_t i = 0; i < position_length; i++){ + uint32_t * val_st_position = (uint32_t*) &(this->st_position); + offset += 3; + *val_st_position = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_st_position |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_st_position |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_st_position |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_st_position = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_st_position |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_st_position !=0) + *val_st_position |= ((exp_st_position)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_position = -this->st_position; + memcpy( &(this->position[i]), &(this->st_position), sizeof(float)); + } + uint8_t velocity_lengthT = *(inbuffer + offset++); + if(velocity_lengthT > velocity_length) + this->velocity = (float*)realloc(this->velocity, velocity_lengthT * sizeof(float)); + offset += 3; + velocity_length = velocity_lengthT; + for( uint8_t i = 0; i < velocity_length; i++){ + uint32_t * val_st_velocity = (uint32_t*) &(this->st_velocity); + offset += 3; + *val_st_velocity = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_st_velocity |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_st_velocity |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_st_velocity |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_st_velocity = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_st_velocity |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_st_velocity !=0) + *val_st_velocity |= ((exp_st_velocity)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_velocity = -this->st_velocity; + memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(float)); + } + uint8_t effort_lengthT = *(inbuffer + offset++); + if(effort_lengthT > effort_length) + this->effort = (float*)realloc(this->effort, effort_lengthT * sizeof(float)); + offset += 3; + effort_length = effort_lengthT; + for( uint8_t i = 0; i < effort_length; i++){ + uint32_t * val_st_effort = (uint32_t*) &(this->st_effort); + offset += 3; + *val_st_effort = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_st_effort |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_st_effort |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_st_effort |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_st_effort = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_st_effort |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_st_effort !=0) + *val_st_effort |= ((exp_st_effort)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_effort = -this->st_effort; + memcpy( &(this->effort[i]), &(this->st_effort), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/JointState"; }; + const char * getMD5(){ return "3066dcd76a6cfaef579bd0f34173e9fd"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/LaserScan.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,268 @@ +#ifndef _ROS_sensor_msgs_LaserScan_h +#define _ROS_sensor_msgs_LaserScan_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class LaserScan : public ros::Msg + { + public: + std_msgs::Header header; + float angle_min; + float angle_max; + float angle_increment; + float time_increment; + float scan_time; + float range_min; + float range_max; + uint8_t ranges_length; + float st_ranges; + float * ranges; + uint8_t intensities_length; + float st_intensities; + float * intensities; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + union { + float real; + uint32_t base; + } u_angle_min; + u_angle_min.real = this->angle_min; + *(outbuffer + offset + 0) = (u_angle_min.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angle_min.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angle_min.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angle_min.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angle_min); + union { + float real; + uint32_t base; + } u_angle_max; + u_angle_max.real = this->angle_max; + *(outbuffer + offset + 0) = (u_angle_max.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angle_max.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angle_max.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angle_max.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angle_max); + union { + float real; + uint32_t base; + } u_angle_increment; + u_angle_increment.real = this->angle_increment; + *(outbuffer + offset + 0) = (u_angle_increment.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_angle_increment.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_angle_increment.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_angle_increment.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->angle_increment); + union { + float real; + uint32_t base; + } u_time_increment; + u_time_increment.real = this->time_increment; + *(outbuffer + offset + 0) = (u_time_increment.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_time_increment.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_time_increment.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_time_increment.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->time_increment); + union { + float real; + uint32_t base; + } u_scan_time; + u_scan_time.real = this->scan_time; + *(outbuffer + offset + 0) = (u_scan_time.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_scan_time.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_scan_time.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_scan_time.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->scan_time); + union { + float real; + uint32_t base; + } u_range_min; + u_range_min.real = this->range_min; + *(outbuffer + offset + 0) = (u_range_min.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_range_min.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_range_min.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_range_min.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->range_min); + union { + float real; + uint32_t base; + } u_range_max; + u_range_max.real = this->range_max; + *(outbuffer + offset + 0) = (u_range_max.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_range_max.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_range_max.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_range_max.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->range_max); + *(outbuffer + offset++) = ranges_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < ranges_length; i++){ + union { + float real; + uint32_t base; + } u_rangesi; + u_rangesi.real = this->ranges[i]; + *(outbuffer + offset + 0) = (u_rangesi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_rangesi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_rangesi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_rangesi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->ranges[i]); + } + *(outbuffer + offset++) = intensities_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < intensities_length; i++){ + union { + float real; + uint32_t base; + } u_intensitiesi; + u_intensitiesi.real = this->intensities[i]; + *(outbuffer + offset + 0) = (u_intensitiesi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_intensitiesi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_intensitiesi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_intensitiesi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->intensities[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + union { + float real; + uint32_t base; + } u_angle_min; + u_angle_min.base = 0; + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angle_min = u_angle_min.real; + offset += sizeof(this->angle_min); + union { + float real; + uint32_t base; + } u_angle_max; + u_angle_max.base = 0; + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angle_max = u_angle_max.real; + offset += sizeof(this->angle_max); + union { + float real; + uint32_t base; + } u_angle_increment; + u_angle_increment.base = 0; + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->angle_increment = u_angle_increment.real; + offset += sizeof(this->angle_increment); + union { + float real; + uint32_t base; + } u_time_increment; + u_time_increment.base = 0; + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->time_increment = u_time_increment.real; + offset += sizeof(this->time_increment); + union { + float real; + uint32_t base; + } u_scan_time; + u_scan_time.base = 0; + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->scan_time = u_scan_time.real; + offset += sizeof(this->scan_time); + union { + float real; + uint32_t base; + } u_range_min; + u_range_min.base = 0; + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->range_min = u_range_min.real; + offset += sizeof(this->range_min); + union { + float real; + uint32_t base; + } u_range_max; + u_range_max.base = 0; + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->range_max = u_range_max.real; + offset += sizeof(this->range_max); + uint8_t ranges_lengthT = *(inbuffer + offset++); + if(ranges_lengthT > ranges_length) + this->ranges = (float*)realloc(this->ranges, ranges_lengthT * sizeof(float)); + offset += 3; + ranges_length = ranges_lengthT; + for( uint8_t i = 0; i < ranges_length; i++){ + union { + float real; + uint32_t base; + } u_st_ranges; + u_st_ranges.base = 0; + u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_ranges = u_st_ranges.real; + offset += sizeof(this->st_ranges); + memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(float)); + } + uint8_t intensities_lengthT = *(inbuffer + offset++); + if(intensities_lengthT > intensities_length) + this->intensities = (float*)realloc(this->intensities, intensities_lengthT * sizeof(float)); + offset += 3; + intensities_length = intensities_lengthT; + for( uint8_t i = 0; i < intensities_length; i++){ + union { + float real; + uint32_t base; + } u_st_intensities; + u_st_intensities.base = 0; + u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_intensities = u_st_intensities.real; + offset += sizeof(this->st_intensities); + memcpy( &(this->intensities[i]), &(this->st_intensities), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/LaserScan"; }; + const char * getMD5(){ return "90c7ef2dc6895d81024acba2ac42f369"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/NavSatFix.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,161 @@ +#ifndef _ROS_sensor_msgs_NavSatFix_h +#define _ROS_sensor_msgs_NavSatFix_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "sensor_msgs/NavSatStatus.h" + +namespace sensor_msgs +{ + + class NavSatFix : public ros::Msg + { + public: + std_msgs::Header header; + sensor_msgs::NavSatStatus status; + float latitude; + float longitude; + float altitude; + float position_covariance[9]; + uint8_t position_covariance_type; + enum { COVARIANCE_TYPE_UNKNOWN = 0 }; + enum { COVARIANCE_TYPE_APPROXIMATED = 1 }; + enum { COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 }; + enum { COVARIANCE_TYPE_KNOWN = 3 }; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + offset += this->status.serialize(outbuffer + offset); + int32_t * val_latitude = (int32_t *) &(this->latitude); + int32_t exp_latitude = (((*val_latitude)>>23)&255); + if(exp_latitude != 0) + exp_latitude += 1023-127; + int32_t sig_latitude = *val_latitude; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_latitude<<5) & 0xff; + *(outbuffer + offset++) = (sig_latitude>>3) & 0xff; + *(outbuffer + offset++) = (sig_latitude>>11) & 0xff; + *(outbuffer + offset++) = ((exp_latitude<<4) & 0xF0) | ((sig_latitude>>19)&0x0F); + *(outbuffer + offset++) = (exp_latitude>>4) & 0x7F; + if(this->latitude < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_longitude = (int32_t *) &(this->longitude); + int32_t exp_longitude = (((*val_longitude)>>23)&255); + if(exp_longitude != 0) + exp_longitude += 1023-127; + int32_t sig_longitude = *val_longitude; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_longitude<<5) & 0xff; + *(outbuffer + offset++) = (sig_longitude>>3) & 0xff; + *(outbuffer + offset++) = (sig_longitude>>11) & 0xff; + *(outbuffer + offset++) = ((exp_longitude<<4) & 0xF0) | ((sig_longitude>>19)&0x0F); + *(outbuffer + offset++) = (exp_longitude>>4) & 0x7F; + if(this->longitude < 0) *(outbuffer + offset -1) |= 0x80; + int32_t * val_altitude = (int32_t *) &(this->altitude); + int32_t exp_altitude = (((*val_altitude)>>23)&255); + if(exp_altitude != 0) + exp_altitude += 1023-127; + int32_t sig_altitude = *val_altitude; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_altitude<<5) & 0xff; + *(outbuffer + offset++) = (sig_altitude>>3) & 0xff; + *(outbuffer + offset++) = (sig_altitude>>11) & 0xff; + *(outbuffer + offset++) = ((exp_altitude<<4) & 0xF0) | ((sig_altitude>>19)&0x0F); + *(outbuffer + offset++) = (exp_altitude>>4) & 0x7F; + if(this->altitude < 0) *(outbuffer + offset -1) |= 0x80; + unsigned char * position_covariance_val = (unsigned char *) this->position_covariance; + for( uint8_t i = 0; i < 9; i++){ + int32_t * val_position_covariancei = (int32_t *) &(this->position_covariance[i]); + int32_t exp_position_covariancei = (((*val_position_covariancei)>>23)&255); + if(exp_position_covariancei != 0) + exp_position_covariancei += 1023-127; + int32_t sig_position_covariancei = *val_position_covariancei; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_position_covariancei<<5) & 0xff; + *(outbuffer + offset++) = (sig_position_covariancei>>3) & 0xff; + *(outbuffer + offset++) = (sig_position_covariancei>>11) & 0xff; + *(outbuffer + offset++) = ((exp_position_covariancei<<4) & 0xF0) | ((sig_position_covariancei>>19)&0x0F); + *(outbuffer + offset++) = (exp_position_covariancei>>4) & 0x7F; + if(this->position_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + *(outbuffer + offset + 0) = (this->position_covariance_type >> (8 * 0)) & 0xFF; + offset += sizeof(this->position_covariance_type); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + offset += this->status.deserialize(inbuffer + offset); + uint32_t * val_latitude = (uint32_t*) &(this->latitude); + offset += 3; + *val_latitude = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_latitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_latitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_latitude |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_latitude = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_latitude |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_latitude !=0) + *val_latitude |= ((exp_latitude)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->latitude = -this->latitude; + uint32_t * val_longitude = (uint32_t*) &(this->longitude); + offset += 3; + *val_longitude = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_longitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_longitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_longitude |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_longitude = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_longitude |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_longitude !=0) + *val_longitude |= ((exp_longitude)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->longitude = -this->longitude; + uint32_t * val_altitude = (uint32_t*) &(this->altitude); + offset += 3; + *val_altitude = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_altitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_altitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_altitude |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_altitude = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_altitude |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_altitude !=0) + *val_altitude |= ((exp_altitude)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->altitude = -this->altitude; + uint8_t * position_covariance_val = (uint8_t*) this->position_covariance; + for( uint8_t i = 0; i < 9; i++){ + uint32_t * val_position_covariancei = (uint32_t*) &(this->position_covariance[i]); + offset += 3; + *val_position_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_position_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_position_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_position_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_position_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_position_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_position_covariancei !=0) + *val_position_covariancei |= ((exp_position_covariancei)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->position_covariance[i] = -this->position_covariance[i]; + } + this->position_covariance_type = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->position_covariance_type); + return offset; + } + + const char * getType(){ return "sensor_msgs/NavSatFix"; }; + const char * getMD5(){ return "2d3a8cd499b9b4a0249fb98fd05cfa48"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/NavSatStatus.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,65 @@ +#ifndef _ROS_sensor_msgs_NavSatStatus_h +#define _ROS_sensor_msgs_NavSatStatus_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace sensor_msgs +{ + + class NavSatStatus : public ros::Msg + { + public: + int8_t status; + uint16_t service; + enum { STATUS_NO_FIX = -1 }; + enum { STATUS_FIX = 0 }; + enum { STATUS_SBAS_FIX = 1 }; + enum { STATUS_GBAS_FIX = 2 }; + enum { SERVICE_GPS = 1 }; + enum { SERVICE_GLONASS = 2 }; + enum { SERVICE_COMPASS = 4 }; + enum { SERVICE_GALILEO = 8 }; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_status; + u_status.real = this->status; + *(outbuffer + offset + 0) = (u_status.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->status); + *(outbuffer + offset + 0) = (this->service >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->service >> (8 * 1)) & 0xFF; + offset += sizeof(this->service); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_status; + u_status.base = 0; + u_status.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->status = u_status.real; + offset += sizeof(this->status); + this->service = ((uint16_t) (*(inbuffer + offset))); + this->service |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + offset += sizeof(this->service); + return offset; + } + + const char * getType(){ return "sensor_msgs/NavSatStatus"; }; + const char * getMD5(){ return "331cdbddfa4bc96ffc3b9ad98900a54c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/PointCloud.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,78 @@ +#ifndef _ROS_sensor_msgs_PointCloud_h +#define _ROS_sensor_msgs_PointCloud_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "geometry_msgs/Point32.h" +#include "sensor_msgs/ChannelFloat32.h" + +namespace sensor_msgs +{ + + class PointCloud : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t points_length; + geometry_msgs::Point32 st_points; + geometry_msgs::Point32 * points; + uint8_t channels_length; + sensor_msgs::ChannelFloat32 st_channels; + sensor_msgs::ChannelFloat32 * channels; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset++) = points_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->points[i].serialize(outbuffer + offset); + } + *(outbuffer + offset++) = channels_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < channels_length; i++){ + offset += this->channels[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + uint8_t points_lengthT = *(inbuffer + offset++); + if(points_lengthT > points_length) + this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32)); + offset += 3; + points_length = points_lengthT; + for( uint8_t i = 0; i < points_length; i++){ + offset += this->st_points.deserialize(inbuffer + offset); + memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32)); + } + uint8_t channels_lengthT = *(inbuffer + offset++); + if(channels_lengthT > channels_length) + this->channels = (sensor_msgs::ChannelFloat32*)realloc(this->channels, channels_lengthT * sizeof(sensor_msgs::ChannelFloat32)); + offset += 3; + channels_length = channels_lengthT; + for( uint8_t i = 0; i < channels_length; i++){ + offset += this->st_channels.deserialize(inbuffer + offset); + memcpy( &(this->channels[i]), &(this->st_channels), sizeof(sensor_msgs::ChannelFloat32)); + } + return offset; + } + + const char * getType(){ return "sensor_msgs/PointCloud"; }; + const char * getMD5(){ return "d8e9c3f5afbdd8a130fd1d2763945fca"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/PointCloud2.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,155 @@ +#ifndef _ROS_sensor_msgs_PointCloud2_h +#define _ROS_sensor_msgs_PointCloud2_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" +#include "sensor_msgs/PointField.h" + +namespace sensor_msgs +{ + + class PointCloud2 : public ros::Msg + { + public: + std_msgs::Header header; + uint32_t height; + uint32_t width; + uint8_t fields_length; + sensor_msgs::PointField st_fields; + sensor_msgs::PointField * fields; + bool is_bigendian; + uint32_t point_step; + uint32_t row_step; + uint8_t data_length; + uint8_t st_data; + uint8_t * data; + bool is_dense; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; + offset += sizeof(this->height); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; + offset += sizeof(this->width); + *(outbuffer + offset++) = fields_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < fields_length; i++){ + offset += this->fields[i].serialize(outbuffer + offset); + } + union { + bool real; + uint8_t base; + } u_is_bigendian; + u_is_bigendian.real = this->is_bigendian; + *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_bigendian); + *(outbuffer + offset + 0) = (this->point_step >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->point_step >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->point_step >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->point_step >> (8 * 3)) & 0xFF; + offset += sizeof(this->point_step); + *(outbuffer + offset + 0) = (this->row_step >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->row_step >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->row_step >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->row_step >> (8 * 3)) & 0xFF; + offset += sizeof(this->row_step); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + union { + bool real; + uint8_t base; + } u_is_dense; + u_is_dense.real = this->is_dense; + *(outbuffer + offset + 0) = (u_is_dense.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->is_dense); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + this->height = ((uint32_t) (*(inbuffer + offset))); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->height); + this->width = ((uint32_t) (*(inbuffer + offset))); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->width); + uint8_t fields_lengthT = *(inbuffer + offset++); + if(fields_lengthT > fields_length) + this->fields = (sensor_msgs::PointField*)realloc(this->fields, fields_lengthT * sizeof(sensor_msgs::PointField)); + offset += 3; + fields_length = fields_lengthT; + for( uint8_t i = 0; i < fields_length; i++){ + offset += this->st_fields.deserialize(inbuffer + offset); + memcpy( &(this->fields[i]), &(this->st_fields), sizeof(sensor_msgs::PointField)); + } + union { + bool real; + uint8_t base; + } u_is_bigendian; + u_is_bigendian.base = 0; + u_is_bigendian.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->is_bigendian = u_is_bigendian.real; + offset += sizeof(this->is_bigendian); + this->point_step = ((uint32_t) (*(inbuffer + offset))); + this->point_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->point_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->point_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->point_step); + this->row_step = ((uint32_t) (*(inbuffer + offset))); + this->row_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->row_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->row_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->row_step); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); + } + union { + bool real; + uint8_t base; + } u_is_dense; + u_is_dense.base = 0; + u_is_dense.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->is_dense = u_is_dense.real; + offset += sizeof(this->is_dense); + return offset; + } + + const char * getType(){ return "sensor_msgs/PointCloud2"; }; + const char * getMD5(){ return "1158d486dd51d683ce2f1be655c3c181"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/PointField.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,84 @@ +#ifndef _ROS_sensor_msgs_PointField_h +#define _ROS_sensor_msgs_PointField_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace sensor_msgs +{ + + class PointField : public ros::Msg + { + public: + char * name; + uint32_t offset; + uint8_t datatype; + uint32_t count; + enum { INT8 = 1 }; + enum { UINT8 = 2 }; + enum { INT16 = 3 }; + enum { UINT16 = 4 }; + enum { INT32 = 5 }; + enum { UINT32 = 6 }; + enum { FLOAT32 = 7 }; + enum { FLOAT64 = 8 }; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen( (const char*) this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + *(outbuffer + offset + 0) = (this->offset >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->offset >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->offset >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->offset >> (8 * 3)) & 0xFF; + offset += sizeof(this->offset); + *(outbuffer + offset + 0) = (this->datatype >> (8 * 0)) & 0xFF; + offset += sizeof(this->datatype); + *(outbuffer + offset + 0) = (this->count >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->count >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->count >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->count >> (8 * 3)) & 0xFF; + offset += sizeof(this->count); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + this->offset = ((uint32_t) (*(inbuffer + offset))); + this->offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->offset); + this->datatype = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->datatype); + this->count = ((uint32_t) (*(inbuffer + offset))); + this->count |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->count |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->count |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->count); + return offset; + } + + const char * getType(){ return "sensor_msgs/PointField"; }; + const char * getMD5(){ return "268eacb2962780ceac86cbd17e328150"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/Range.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,133 @@ +#ifndef _ROS_sensor_msgs_Range_h +#define _ROS_sensor_msgs_Range_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/Header.h" + +namespace sensor_msgs +{ + + class Range : public ros::Msg + { + public: + std_msgs::Header header; + uint8_t radiation_type; + float field_of_view; + float min_range; + float max_range; + float range; + enum { ULTRASOUND = 0 }; + enum { INFRARED = 1 }; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->header.serialize(outbuffer + offset); + *(outbuffer + offset + 0) = (this->radiation_type >> (8 * 0)) & 0xFF; + offset += sizeof(this->radiation_type); + union { + float real; + uint32_t base; + } u_field_of_view; + u_field_of_view.real = this->field_of_view; + *(outbuffer + offset + 0) = (u_field_of_view.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_field_of_view.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_field_of_view.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_field_of_view.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->field_of_view); + union { + float real; + uint32_t base; + } u_min_range; + u_min_range.real = this->min_range; + *(outbuffer + offset + 0) = (u_min_range.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_min_range.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_min_range.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_min_range.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->min_range); + union { + float real; + uint32_t base; + } u_max_range; + u_max_range.real = this->max_range; + *(outbuffer + offset + 0) = (u_max_range.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_max_range.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_max_range.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_max_range.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->max_range); + union { + float real; + uint32_t base; + } u_range; + u_range.real = this->range; + *(outbuffer + offset + 0) = (u_range.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_range.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_range.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_range.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->range); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->header.deserialize(inbuffer + offset); + this->radiation_type = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->radiation_type); + union { + float real; + uint32_t base; + } u_field_of_view; + u_field_of_view.base = 0; + u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->field_of_view = u_field_of_view.real; + offset += sizeof(this->field_of_view); + union { + float real; + uint32_t base; + } u_min_range; + u_min_range.base = 0; + u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->min_range = u_min_range.real; + offset += sizeof(this->min_range); + union { + float real; + uint32_t base; + } u_max_range; + u_max_range.base = 0; + u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->max_range = u_max_range.real; + offset += sizeof(this->max_range); + union { + float real; + uint32_t base; + } u_range; + u_range.base = 0; + u_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->range = u_range.real; + offset += sizeof(this->range); + return offset; + } + + const char * getType(){ return "sensor_msgs/Range"; }; + const char * getMD5(){ return "c005c34273dc426c67a020a87bc24148"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/RegionOfInterest.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,94 @@ +#ifndef _ROS_sensor_msgs_RegionOfInterest_h +#define _ROS_sensor_msgs_RegionOfInterest_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace sensor_msgs +{ + + class RegionOfInterest : public ros::Msg + { + public: + uint32_t x_offset; + uint32_t y_offset; + uint32_t height; + uint32_t width; + bool do_rectify; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->x_offset >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->x_offset >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->x_offset >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->x_offset >> (8 * 3)) & 0xFF; + offset += sizeof(this->x_offset); + *(outbuffer + offset + 0) = (this->y_offset >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->y_offset >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->y_offset >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->y_offset >> (8 * 3)) & 0xFF; + offset += sizeof(this->y_offset); + *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; + offset += sizeof(this->height); + *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; + offset += sizeof(this->width); + union { + bool real; + uint8_t base; + } u_do_rectify; + u_do_rectify.real = this->do_rectify; + *(outbuffer + offset + 0) = (u_do_rectify.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->do_rectify); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->x_offset = ((uint32_t) (*(inbuffer + offset))); + this->x_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->x_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->x_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->x_offset); + this->y_offset = ((uint32_t) (*(inbuffer + offset))); + this->y_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->y_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->y_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->y_offset); + this->height = ((uint32_t) (*(inbuffer + offset))); + this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->height); + this->width = ((uint32_t) (*(inbuffer + offset))); + this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->width); + union { + bool real; + uint8_t base; + } u_do_rectify; + u_do_rectify.base = 0; + u_do_rectify.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->do_rectify = u_do_rectify.real; + offset += sizeof(this->do_rectify); + return offset; + } + + const char * getType(){ return "sensor_msgs/RegionOfInterest"; }; + const char * getMD5(){ return "bdb633039d588fcccb441a4d43ccfe09"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/SetCameraInfo.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,98 @@ +#ifndef _ROS_SERVICE_SetCameraInfo_h +#define _ROS_SERVICE_SetCameraInfo_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "sensor_msgs/CameraInfo.h" + +namespace sensor_msgs +{ + +static const char SETCAMERAINFO[] = "sensor_msgs/SetCameraInfo"; + + class SetCameraInfoRequest : public ros::Msg + { + public: + sensor_msgs::CameraInfo camera_info; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->camera_info.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->camera_info.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return SETCAMERAINFO; }; + const char * getMD5(){ return "ee34be01fdeee563d0d99cd594d5581d"; }; + + }; + + class SetCameraInfoResponse : public ros::Msg + { + public: + bool success; + char * status_message; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_status_message = strlen( (const char*) this->status_message); + memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->status_message, length_status_message); + offset += length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message; + memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + const char * getType(){ return SETCAMERAINFO; }; + const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class SetCameraInfo { + public: + typedef SetCameraInfoRequest Request; + typedef SetCameraInfoResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Bool.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,50 @@ +#ifndef _ROS_std_msgs_Bool_h +#define _ROS_std_msgs_Bool_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Bool : public ros::Msg + { + public: + bool data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Bool"; }; + const char * getMD5(){ return "8b94c1b53db61fb6aed406028ad6332a"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Byte.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,50 @@ +#ifndef _ROS_std_msgs_Byte_h +#define _ROS_std_msgs_Byte_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Byte : public ros::Msg + { + public: + int8_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Byte"; }; + const char * getMD5(){ return "ad736a2e8818154c487bb80fe42ce43b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/ByteMultiArray.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,70 @@ +#ifndef _ROS_std_msgs_ByteMultiArray_h +#define _ROS_std_msgs_ByteMultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class ByteMultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int8_t st_data; + int8_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/ByteMultiArray"; }; + const char * getMD5(){ return "70ea476cbcfd65ac2f68f3cda1e891fe"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Char.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,39 @@ +#ifndef _ROS_std_msgs_Char_h +#define _ROS_std_msgs_Char_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Char : public ros::Msg + { + public: + uint8_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Char"; }; + const char * getMD5(){ return "1bf77f25acecdedba0e224b162199717"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/ColorRGBA.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,122 @@ +#ifndef _ROS_std_msgs_ColorRGBA_h +#define _ROS_std_msgs_ColorRGBA_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class ColorRGBA : public ros::Msg + { + public: + float r; + float g; + float b; + float a; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_r; + u_r.real = this->r; + *(outbuffer + offset + 0) = (u_r.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_r.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_r.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_r.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->r); + union { + float real; + uint32_t base; + } u_g; + u_g.real = this->g; + *(outbuffer + offset + 0) = (u_g.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_g.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_g.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_g.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->g); + union { + float real; + uint32_t base; + } u_b; + u_b.real = this->b; + *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->b); + union { + float real; + uint32_t base; + } u_a; + u_a.real = this->a; + *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->a); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_r; + u_r.base = 0; + u_r.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_r.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_r.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_r.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->r = u_r.real; + offset += sizeof(this->r); + union { + float real; + uint32_t base; + } u_g; + u_g.base = 0; + u_g.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_g.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_g.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_g.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->g = u_g.real; + offset += sizeof(this->g); + union { + float real; + uint32_t base; + } u_b; + u_b.base = 0; + u_b.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->b = u_b.real; + offset += sizeof(this->b); + union { + float real; + uint32_t base; + } u_a; + u_a.base = 0; + u_a.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_a.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_a.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_a.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->a = u_a.real; + offset += sizeof(this->a); + return offset; + } + + const char * getType(){ return "std_msgs/ColorRGBA"; }; + const char * getMD5(){ return "a29a96539573343b1310c73607334b00"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Duration.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,56 @@ +#ifndef _ROS_std_msgs_Duration_h +#define _ROS_std_msgs_Duration_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/duration.h" + +namespace std_msgs +{ + + class Duration : public ros::Msg + { + public: + ros::Duration data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->data.sec); + *(outbuffer + offset + 0) = (this->data.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->data.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data.sec = ((uint32_t) (*(inbuffer + offset))); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data.sec); + this->data.nsec = ((uint32_t) (*(inbuffer + offset))); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data.nsec); + return offset; + } + + const char * getType(){ return "std_msgs/Duration"; }; + const char * getMD5(){ return "3e286caf4241d664e55f3ad380e2ae46"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float32.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,56 @@ +#ifndef _ROS_std_msgs_Float32_h +#define _ROS_std_msgs_Float32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Float32 : public ros::Msg + { + public: + float data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Float32"; }; + const char * getMD5(){ return "73fcbf46b49191e672908e50842a83d4"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float32MultiArray.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,76 @@ +#ifndef _ROS_std_msgs_Float32MultiArray_h +#define _ROS_std_msgs_Float32MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Float32MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + float st_data; + float * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + float real; + uint32_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (float*)realloc(this->data, data_lengthT * sizeof(float)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + float real; + uint32_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Float32MultiArray"; }; + const char * getMD5(){ return "6a40e0ffa6a17a503ac3f8616991b1f6"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float64.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,60 @@ +#ifndef _ROS_std_msgs_Float64_h +#define _ROS_std_msgs_Float64_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Float64 : public ros::Msg + { + public: + float data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + int32_t * val_data = (int32_t *) &(this->data); + int32_t exp_data = (((*val_data)>>23)&255); + if(exp_data != 0) + exp_data += 1023-127; + int32_t sig_data = *val_data; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_data<<5) & 0xff; + *(outbuffer + offset++) = (sig_data>>3) & 0xff; + *(outbuffer + offset++) = (sig_data>>11) & 0xff; + *(outbuffer + offset++) = ((exp_data<<4) & 0xF0) | ((sig_data>>19)&0x0F); + *(outbuffer + offset++) = (exp_data>>4) & 0x7F; + if(this->data < 0) *(outbuffer + offset -1) |= 0x80; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t * val_data = (uint32_t*) &(this->data); + offset += 3; + *val_data = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_data |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_data |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_data |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_data = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_data |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_data !=0) + *val_data |= ((exp_data)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->data = -this->data; + return offset; + } + + const char * getType(){ return "std_msgs/Float64"; }; + const char * getMD5(){ return "fdb28210bfa9d7c91146260178d9a584"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float64MultiArray.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,80 @@ +#ifndef _ROS_std_msgs_Float64MultiArray_h +#define _ROS_std_msgs_Float64MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Float64MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + float st_data; + float * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + int32_t * val_datai = (int32_t *) &(this->data[i]); + int32_t exp_datai = (((*val_datai)>>23)&255); + if(exp_datai != 0) + exp_datai += 1023-127; + int32_t sig_datai = *val_datai; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_datai<<5) & 0xff; + *(outbuffer + offset++) = (sig_datai>>3) & 0xff; + *(outbuffer + offset++) = (sig_datai>>11) & 0xff; + *(outbuffer + offset++) = ((exp_datai<<4) & 0xF0) | ((sig_datai>>19)&0x0F); + *(outbuffer + offset++) = (exp_datai>>4) & 0x7F; + if(this->data[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (float*)realloc(this->data, data_lengthT * sizeof(float)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + uint32_t * val_st_data = (uint32_t*) &(this->st_data); + offset += 3; + *val_st_data = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_st_data |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_st_data |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_st_data |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_st_data = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_st_data |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_st_data !=0) + *val_st_data |= ((exp_st_data)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_data = -this->st_data; + memcpy( &(this->data[i]), &(this->st_data), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Float64MultiArray"; }; + const char * getMD5(){ return "4b7d974086d4060e7db4613a7e6c3ba4"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Header.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,82 @@ +#ifndef _ROS_std_msgs_Header_h +#define _ROS_std_msgs_Header_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" + +namespace std_msgs +{ + + class Header : public ros::Msg + { + public: + uint32_t seq; + ros::Time stamp; + char * frame_id; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->seq >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->seq >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->seq >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->seq >> (8 * 3)) & 0xFF; + offset += sizeof(this->seq); + *(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->stamp.sec); + *(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->stamp.nsec); + uint32_t length_frame_id = strlen( (const char*) this->frame_id); + memcpy(outbuffer + offset, &length_frame_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->frame_id, length_frame_id); + offset += length_frame_id; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->seq = ((uint32_t) (*(inbuffer + offset))); + this->seq |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->seq |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->seq |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->seq); + this->stamp.sec = ((uint32_t) (*(inbuffer + offset))); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stamp.sec); + this->stamp.nsec = ((uint32_t) (*(inbuffer + offset))); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stamp.nsec); + uint32_t length_frame_id; + memcpy(&length_frame_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_frame_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_frame_id-1]=0; + this->frame_id = (char *)(inbuffer + offset-1); + offset += length_frame_id; + return offset; + } + + const char * getType(){ return "std_msgs/Header"; }; + const char * getMD5(){ return "2176decaecbce78abc3b96ef049fabed"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int16.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,52 @@ +#ifndef _ROS_std_msgs_Int16_h +#define _ROS_std_msgs_Int16_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int16 : public ros::Msg + { + public: + int16_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int16_t real; + uint16_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int16_t real; + uint16_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int16"; }; + const char * getMD5(){ return "8524586e34fbd7cb1c08c5f5f1ca0e57"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int16MultiArray.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,72 @@ +#ifndef _ROS_std_msgs_Int16MultiArray_h +#define _ROS_std_msgs_Int16MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int16MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int16_t st_data; + int16_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int16_t real; + uint16_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int16_t*)realloc(this->data, data_lengthT * sizeof(int16_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int16_t real; + uint16_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int16_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int16MultiArray"; }; + const char * getMD5(){ return "d9338d7f523fcb692fae9d0a0e9f067c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int32.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,56 @@ +#ifndef _ROS_std_msgs_Int32_h +#define _ROS_std_msgs_Int32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int32 : public ros::Msg + { + public: + int32_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int32"; }; + const char * getMD5(){ return "da5909fbe378aeaf85e547e830cc1bb7"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int32MultiArray.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,76 @@ +#ifndef _ROS_std_msgs_Int32MultiArray_h +#define _ROS_std_msgs_Int32MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int32MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int32_t st_data; + int32_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int32_t real; + uint32_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int32_t*)realloc(this->data, data_lengthT * sizeof(int32_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int32_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int32MultiArray"; }; + const char * getMD5(){ return "1d99f79f8b325b44fee908053e9c945b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int64.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_std_msgs_Int64_h +#define _ROS_std_msgs_Int64_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int64 : public ros::Msg + { + public: + int64_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_data.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_data.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_data.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_data.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int64"; }; + const char * getMD5(){ return "34add168574510e6e17f5d23ecc077ef"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int64MultiArray.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,84 @@ +#ifndef _ROS_std_msgs_Int64MultiArray_h +#define _ROS_std_msgs_Int64MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int64MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int64_t st_data; + int64_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int64_t real; + uint64_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_datai.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_datai.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_datai.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_datai.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int64_t*)realloc(this->data, data_lengthT * sizeof(int64_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int64_t real; + uint64_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int64_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int64MultiArray"; }; + const char * getMD5(){ return "54865aa6c65be0448113a2afc6a49270"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int8.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,50 @@ +#ifndef _ROS_std_msgs_Int8_h +#define _ROS_std_msgs_Int8_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int8 : public ros::Msg + { + public: + int8_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int8"; }; + const char * getMD5(){ return "27ffa0c9c4b8fb8492252bcad9e5c57b"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int8MultiArray.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,70 @@ +#ifndef _ROS_std_msgs_Int8MultiArray_h +#define _ROS_std_msgs_Int8MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int8MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int8_t st_data; + int8_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int8MultiArray"; }; + const char * getMD5(){ return "d7c1af35a1b4781bbe79e03dd94b7c13"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/MultiArrayDimension.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,71 @@ +#ifndef _ROS_std_msgs_MultiArrayDimension_h +#define _ROS_std_msgs_MultiArrayDimension_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class MultiArrayDimension : public ros::Msg + { + public: + char * label; + uint32_t size; + uint32_t stride; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_label = strlen( (const char*) this->label); + memcpy(outbuffer + offset, &length_label, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->label, length_label); + offset += length_label; + *(outbuffer + offset + 0) = (this->size >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->size >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->size >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->size >> (8 * 3)) & 0xFF; + offset += sizeof(this->size); + *(outbuffer + offset + 0) = (this->stride >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stride >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stride >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stride >> (8 * 3)) & 0xFF; + offset += sizeof(this->stride); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_label; + memcpy(&length_label, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_label; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_label-1]=0; + this->label = (char *)(inbuffer + offset-1); + offset += length_label; + this->size = ((uint32_t) (*(inbuffer + offset))); + this->size |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->size |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->size |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->size); + this->stride = ((uint32_t) (*(inbuffer + offset))); + this->stride |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stride |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stride |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stride); + return offset; + } + + const char * getType(){ return "std_msgs/MultiArrayDimension"; }; + const char * getMD5(){ return "4cd0c83a8683deae40ecdac60e53bfa8"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/MultiArrayLayout.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,65 @@ +#ifndef _ROS_std_msgs_MultiArrayLayout_h +#define _ROS_std_msgs_MultiArrayLayout_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayDimension.h" + +namespace std_msgs +{ + + class MultiArrayLayout : public ros::Msg + { + public: + uint8_t dim_length; + std_msgs::MultiArrayDimension st_dim; + std_msgs::MultiArrayDimension * dim; + uint32_t data_offset; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = dim_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < dim_length; i++){ + offset += this->dim[i].serialize(outbuffer + offset); + } + *(outbuffer + offset + 0) = (this->data_offset >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data_offset >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data_offset >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data_offset >> (8 * 3)) & 0xFF; + offset += sizeof(this->data_offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t dim_lengthT = *(inbuffer + offset++); + if(dim_lengthT > dim_length) + this->dim = (std_msgs::MultiArrayDimension*)realloc(this->dim, dim_lengthT * sizeof(std_msgs::MultiArrayDimension)); + offset += 3; + dim_length = dim_lengthT; + for( uint8_t i = 0; i < dim_length; i++){ + offset += this->st_dim.deserialize(inbuffer + offset); + memcpy( &(this->dim[i]), &(this->st_dim), sizeof(std_msgs::MultiArrayDimension)); + } + this->data_offset = ((uint32_t) (*(inbuffer + offset))); + this->data_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data_offset); + return offset; + } + + const char * getType(){ return "std_msgs/MultiArrayLayout"; }; + const char * getMD5(){ return "0fed2a11c13e11c5571b4e2a995a91a3"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/String.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,49 @@ +#ifndef _ROS_std_msgs_String_h +#define _ROS_std_msgs_String_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class String : public ros::Msg + { + public: + char * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_data = strlen( (const char*) this->data); + memcpy(outbuffer + offset, &length_data, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->data, length_data); + offset += length_data; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_data; + memcpy(&length_data, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_data; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_data-1]=0; + this->data = (char *)(inbuffer + offset-1); + offset += length_data; + return offset; + } + + const char * getType(){ return "std_msgs/String"; }; + const char * getMD5(){ return "992ce8a1687cec8c8bd883ec73ca41d1"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt16.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,41 @@ +#ifndef _ROS_std_msgs_UInt16_h +#define _ROS_std_msgs_UInt16_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class UInt16 : public ros::Msg + { + public: + uint16_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data = ((uint16_t) (*(inbuffer + offset))); + this->data |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/UInt16"; }; + const char * getMD5(){ return "1df79edf208b629fe6b81923a544552d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt16MultiArray.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,61 @@ +#ifndef _ROS_std_msgs_UInt16MultiArray_h +#define _ROS_std_msgs_UInt16MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class UInt16MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + uint16_t st_data; + uint16_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data[i] >> (8 * 1)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint16_t*)realloc(this->data, data_lengthT * sizeof(uint16_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data = ((uint16_t) (*(inbuffer + offset))); + this->st_data |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint16_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/UInt16MultiArray"; }; + const char * getMD5(){ return "52f264f1c973c4b73790d384c6cb4484"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt32.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,45 @@ +#ifndef _ROS_std_msgs_UInt32_h +#define _ROS_std_msgs_UInt32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class UInt32 : public ros::Msg + { + public: + uint32_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data = ((uint32_t) (*(inbuffer + offset))); + this->data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/UInt32"; }; + const char * getMD5(){ return "304a39449588c7f8ce2df6e8001c5fce"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt32MultiArray.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,65 @@ +#ifndef _ROS_std_msgs_UInt32MultiArray_h +#define _ROS_std_msgs_UInt32MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class UInt32MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + uint32_t st_data; + uint32_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data[i] >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data[i] >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data[i] >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint32_t*)realloc(this->data, data_lengthT * sizeof(uint32_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data = ((uint32_t) (*(inbuffer + offset))); + this->st_data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->st_data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->st_data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint32_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/UInt32MultiArray"; }; + const char * getMD5(){ return "4d6a180abc9be191b96a7eda6c8a233d"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt64.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,56 @@ +#ifndef _ROS_std_msgs_UInt64_h +#define _ROS_std_msgs_UInt64_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class UInt64 : public ros::Msg + { + public: + uint64_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + uint64_t real; + uint32_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + uint64_t real; + uint32_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/UInt64"; }; + const char * getMD5(){ return "1b2a79973e8bf53d7b53acb71299cb57"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt64MultiArray.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,76 @@ +#ifndef _ROS_std_msgs_UInt64MultiArray_h +#define _ROS_std_msgs_UInt64MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class UInt64MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + uint64_t st_data; + uint64_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + uint64_t real; + uint32_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint64_t*)realloc(this->data, data_lengthT * sizeof(uint64_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + uint64_t real; + uint32_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint64_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/UInt64MultiArray"; }; + const char * getMD5(){ return "6088f127afb1d6c72927aa1247e945af"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt8.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,39 @@ +#ifndef _ROS_std_msgs_UInt8_h +#define _ROS_std_msgs_UInt8_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class UInt8 : public ros::Msg + { + public: + uint8_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/UInt8"; }; + const char * getMD5(){ return "7c8164229e7d2c17eb95e9231617fdee"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/UInt8MultiArray.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,59 @@ +#ifndef _ROS_std_msgs_UInt8MultiArray_h +#define _ROS_std_msgs_UInt8MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class UInt8MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + uint8_t st_data; + uint8_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + this->st_data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/UInt8MultiArray"; }; + const char * getMD5(){ return "82373f1612381bb6ee473b5cd6f5d89c"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf/FrameGraph.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,78 @@ +#ifndef _ROS_SERVICE_FrameGraph_h +#define _ROS_SERVICE_FrameGraph_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace tf +{ + +static const char FRAMEGRAPH[] = "tf/FrameGraph"; + + class FrameGraphRequest : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return FRAMEGRAPH; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class FrameGraphResponse : public ros::Msg + { + public: + char * dot_graph; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_dot_graph = strlen( (const char*) this->dot_graph); + memcpy(outbuffer + offset, &length_dot_graph, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->dot_graph, length_dot_graph); + offset += length_dot_graph; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_dot_graph; + memcpy(&length_dot_graph, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_dot_graph; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_dot_graph-1]=0; + this->dot_graph = (char *)(inbuffer + offset-1); + offset += length_dot_graph; + return offset; + } + + const char * getType(){ return FRAMEGRAPH; }; + const char * getMD5(){ return "c4af9ac907e58e906eb0b6e3c58478c0"; }; + + }; + + class FrameGraph { + public: + typedef FrameGraphRequest Request; + typedef FrameGraphResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf/tf.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,57 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROS_TF_H_ +#define ROS_TF_H_ + +#include "geometry_msgs/TransformStamped.h" + +namespace tf +{ + + geometry_msgs::Quaternion createQuaternionFromYaw(double yaw) + { + geometry_msgs::Quaternion q; + q.x = 0; + q.y = 0; + q.z = sin(yaw * 0.5); + q.w = cos(yaw * 0.5); + return q; + } + +} + +#endif + +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf/tfMessage.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,54 @@ +#ifndef _ROS_tf_tfMessage_h +#define _ROS_tf_tfMessage_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "geometry_msgs/TransformStamped.h" + +namespace tf +{ + + class tfMessage : public ros::Msg + { + public: + uint8_t transforms_length; + geometry_msgs::TransformStamped st_transforms; + geometry_msgs::TransformStamped * transforms; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = transforms_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < transforms_length; i++){ + offset += this->transforms[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t transforms_lengthT = *(inbuffer + offset++); + if(transforms_lengthT > transforms_length) + this->transforms = (geometry_msgs::TransformStamped*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::TransformStamped)); + offset += 3; + transforms_length = transforms_lengthT; + for( uint8_t i = 0; i < transforms_length; i++){ + offset += this->st_transforms.deserialize(inbuffer + offset); + memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::TransformStamped)); + } + return offset; + } + + const char * getType(){ return "tf/tfMessage"; }; + const char * getMD5(){ return "94810edda583a504dfda3829e70d7eec"; }; + + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/tf/transform_broadcaster.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,69 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote prducts derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROS_TRANSFORM_BROADCASTER_H_ +#define ROS_TRANSFORM_BROADCASTER_H_ + +#include "tfMessage.h" + +namespace tf +{ + + class TransformBroadcaster + { + public: + TransformBroadcaster() : publisher_("tf", &internal_msg) {} + + void init(ros::NodeHandle &nh) + { + nh.advertise(publisher_); + } + + void sendTransform(geometry_msgs::TransformStamped &transform) + { + internal_msg.transforms_length = 1; + internal_msg.transforms = &transform; + publisher_.publish(&internal_msg); + } + + private: + tf::tfMessage internal_msg; + ros::Publisher publisher_; + }; + +} + +#endif + +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/topic_tools/MuxAdd.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,78 @@ +#ifndef _ROS_SERVICE_MuxAdd_h +#define _ROS_SERVICE_MuxAdd_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace topic_tools +{ + +static const char MUXADD[] = "topic_tools/MuxAdd"; + + class MuxAddRequest : public ros::Msg + { + public: + char * topic; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_topic = strlen( (const char*) this->topic); + memcpy(outbuffer + offset, &length_topic, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->topic, length_topic); + offset += length_topic; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_topic; + memcpy(&length_topic, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_topic; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_topic-1]=0; + this->topic = (char *)(inbuffer + offset-1); + offset += length_topic; + return offset; + } + + const char * getType(){ return MUXADD; }; + const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; }; + + }; + + class MuxAddResponse : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return MUXADD; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class MuxAdd { + public: + typedef MuxAddRequest Request; + typedef MuxAddResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/topic_tools/MuxDelete.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,78 @@ +#ifndef _ROS_SERVICE_MuxDelete_h +#define _ROS_SERVICE_MuxDelete_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace topic_tools +{ + +static const char MUXDELETE[] = "topic_tools/MuxDelete"; + + class MuxDeleteRequest : public ros::Msg + { + public: + char * topic; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_topic = strlen( (const char*) this->topic); + memcpy(outbuffer + offset, &length_topic, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->topic, length_topic); + offset += length_topic; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_topic; + memcpy(&length_topic, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_topic; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_topic-1]=0; + this->topic = (char *)(inbuffer + offset-1); + offset += length_topic; + return offset; + } + + const char * getType(){ return MUXDELETE; }; + const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; }; + + }; + + class MuxDeleteResponse : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return MUXDELETE; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class MuxDelete { + public: + typedef MuxDeleteRequest Request; + typedef MuxDeleteResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/topic_tools/MuxList.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,94 @@ +#ifndef _ROS_SERVICE_MuxList_h +#define _ROS_SERVICE_MuxList_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace topic_tools +{ + +static const char MUXLIST[] = "topic_tools/MuxList"; + + class MuxListRequest : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return MUXLIST; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class MuxListResponse : public ros::Msg + { + public: + uint8_t topics_length; + char* st_topics; + char* * topics; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = topics_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < topics_length; i++){ + uint32_t length_topicsi = strlen( (const char*) this->topics[i]); + memcpy(outbuffer + offset, &length_topicsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->topics[i], length_topicsi); + offset += length_topicsi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t topics_lengthT = *(inbuffer + offset++); + if(topics_lengthT > topics_length) + this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*)); + offset += 3; + topics_length = topics_lengthT; + for( uint8_t i = 0; i < topics_length; i++){ + uint32_t length_st_topics; + memcpy(&length_st_topics, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_topics; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_topics-1]=0; + this->st_topics = (char *)(inbuffer + offset-1); + offset += length_st_topics; + memcpy( &(this->topics[i]), &(this->st_topics), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return MUXLIST; }; + const char * getMD5(){ return "b0eef9a05d4e829092fc2f2c3c2aad3d"; }; + + }; + + class MuxList { + public: + typedef MuxListRequest Request; + typedef MuxListResponse Response; + }; + +} +#endif +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/topic_tools/MuxSelect.h Sat Oct 26 15:39:01 2013 +0000 @@ -0,0 +1,93 @@ +#ifndef _ROS_SERVICE_MuxSelect_h +#define _ROS_SERVICE_MuxSelect_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace topic_tools +{ + +static const char MUXSELECT[] = "topic_tools/MuxSelect"; + + class MuxSelectRequest : public ros::Msg + { + public: + char * topic; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_topic = strlen( (const char*) this->topic); + memcpy(outbuffer + offset, &length_topic, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->topic, length_topic); + offset += length_topic; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_topic; + memcpy(&length_topic, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_topic; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_topic-1]=0; + this->topic = (char *)(inbuffer + offset-1); + offset += length_topic; + return offset; + } + + const char * getType(){ return MUXSELECT; }; + const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; }; + + }; + + class MuxSelectResponse : public ros::Msg + { + public: + char * prev_topic; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_prev_topic = strlen( (const char*) this->prev_topic); + memcpy(outbuffer + offset, &length_prev_topic, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->prev_topic, length_prev_topic); + offset += length_prev_topic; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_prev_topic; + memcpy(&length_prev_topic, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_prev_topic; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_prev_topic-1]=0; + this->prev_topic = (char *)(inbuffer + offset-1); + offset += length_prev_topic; + return offset; + } + + const char * getType(){ return MUXSELECT; }; + const char * getMD5(){ return "3db0a473debdbafea387c9e49358c320"; }; + + }; + + class MuxSelect { + public: + typedef MuxSelectRequest Request; + typedef MuxSelectResponse Response; + }; + +} +#endif +