This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial.
Dependents: rosserial_mbed robot_S2
Diff: dianostic_msgs/DiagnosticStatus.h
- Revision:
- 3:1cf99502f396
- Parent:
- 1:ff0ec969dad1
- Child:
- 4:684f39d0c346
diff -r bb6bb835fde4 -r 1cf99502f396 dianostic_msgs/DiagnosticStatus.h --- a/dianostic_msgs/DiagnosticStatus.h Sun Oct 16 09:35:11 2011 +0000 +++ b/dianostic_msgs/DiagnosticStatus.h Sat Nov 12 23:54:45 2011 +0000 @@ -1,112 +1,103 @@ -#ifndef ros_diagnostic_msgs_DiagnosticStatus_h -#define ros_diagnostic_msgs_DiagnosticStatus_h +#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 "ros/msg.h" +#include "diagnostic_msgs/byte.h" #include "diagnostic_msgs/KeyValue.h" -namespace diagnostic_msgs { +namespace diagnostic_msgs +{ -class DiagnosticStatus : public ros::Msg { -public: - unsigned char level; - char * name; - char * message; - char * hardware_id; - unsigned char values_length; - diagnostic_msgs::KeyValue st_values; - diagnostic_msgs::KeyValue * values; - enum { OK = 0 }; - enum { WARN = 1 }; - enum { ERROR = 2 }; + class DiagnosticStatus : public ros::Msg + { + public: + diagnostic_msgs::byte 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) { - int offset = 0; - union { - unsigned char real; - unsigned char base; - } u_level; - u_level.real = this->level; - *(outbuffer + offset + 0) = (u_level.base >> (8 * 0)) & 0xFF; - offset += sizeof(this->level); - long * length_name = (long *)(outbuffer + offset); - *length_name = strlen( (const char*) this->name); - offset += 4; - memcpy(outbuffer + offset, this->name, *length_name); - offset += *length_name; - long * length_message = (long *)(outbuffer + offset); - *length_message = strlen( (const char*) this->message); - offset += 4; - memcpy(outbuffer + offset, this->message, *length_message); - offset += *length_message; - long * length_hardware_id = (long *)(outbuffer + offset); - *length_hardware_id = strlen( (const char*) this->hardware_id); - 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 ( unsigned char i = 0; i < values_length; i++) { - offset += this->values[i].serialize(outbuffer + offset); - } - return offset; + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->level.serialize(outbuffer + offset); + uint32_t * length_name = (uint32_t *)(outbuffer + offset); + *length_name = strlen( (const char*) this->name); + offset += 4; + memcpy(outbuffer + offset, this->name, *length_name); + offset += *length_name; + uint32_t * length_message = (uint32_t *)(outbuffer + offset); + *length_message = strlen( (const char*) this->message); + offset += 4; + memcpy(outbuffer + offset, this->message, *length_message); + offset += *length_message; + uint32_t * length_hardware_id = (uint32_t *)(outbuffer + offset); + *length_hardware_id = strlen( (const char*) this->hardware_id); + 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 { - unsigned char real; - unsigned char base; - } u_level; - u_level.base = 0; - u_level.base |= ((typeof(u_level.base)) (*(inbuffer + offset + 0))) << (8 * 0); - this->level = u_level.real; - offset += sizeof(this->level); - uint32_t length_name = *(uint32_t *)(inbuffer + offset); - 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 = *(uint32_t *)(inbuffer + offset); - 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 = *(uint32_t *)(inbuffer + offset); - 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; - unsigned char 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 ( unsigned char 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; + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->level.deserialize(inbuffer + offset); + uint32_t length_name = *(uint32_t *)(inbuffer + offset); + 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 = *(uint32_t *)(inbuffer + offset); + 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 = *(uint32_t *)(inbuffer + offset); + 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; } - virtual const char * getType() { - return "diagnostic_msgs/DiagnosticStatus"; - }; + virtual const char * getType(){ return "diagnostic_msgs/DiagnosticStatus"; }; + virtual const char * getMD5(){ return "67d15a62edb26e9d52b0f0efa3ef9da7"; }; -}; + }; } #endif \ No newline at end of file