Personal fork
Fork of rosserial_mbed_lib by
rosgraph_msgs/Log.h@5:19c5437ed9fe, 2014-05-01 (annotated)
- Committer:
- garyservin
- Date:
- Thu May 01 06:01:31 2014 +0000
- Revision:
- 5:19c5437ed9fe
- Parent:
- 3:1cf99502f396
Updated to hydro
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
nucho | 3:1cf99502f396 | 1 | #ifndef _ROS_rosgraph_msgs_Log_h |
nucho | 3:1cf99502f396 | 2 | #define _ROS_rosgraph_msgs_Log_h |
nucho | 3:1cf99502f396 | 3 | |
nucho | 3:1cf99502f396 | 4 | #include <stdint.h> |
nucho | 3:1cf99502f396 | 5 | #include <string.h> |
nucho | 3:1cf99502f396 | 6 | #include <stdlib.h> |
nucho | 3:1cf99502f396 | 7 | #include "ros/msg.h" |
nucho | 3:1cf99502f396 | 8 | #include "std_msgs/Header.h" |
nucho | 3:1cf99502f396 | 9 | #include "rosgraph_msgs/byte.h" |
nucho | 3:1cf99502f396 | 10 | |
nucho | 3:1cf99502f396 | 11 | namespace rosgraph_msgs |
nucho | 3:1cf99502f396 | 12 | { |
nucho | 3:1cf99502f396 | 13 | |
nucho | 3:1cf99502f396 | 14 | class Log : public ros::Msg |
nucho | 3:1cf99502f396 | 15 | { |
nucho | 3:1cf99502f396 | 16 | public: |
nucho | 3:1cf99502f396 | 17 | std_msgs::Header header; |
nucho | 3:1cf99502f396 | 18 | rosgraph_msgs::byte level; |
nucho | 3:1cf99502f396 | 19 | char * name; |
nucho | 3:1cf99502f396 | 20 | char * msg; |
nucho | 3:1cf99502f396 | 21 | char * file; |
nucho | 3:1cf99502f396 | 22 | char * function; |
nucho | 3:1cf99502f396 | 23 | uint32_t line; |
nucho | 3:1cf99502f396 | 24 | uint8_t topics_length; |
nucho | 3:1cf99502f396 | 25 | char* st_topics; |
nucho | 3:1cf99502f396 | 26 | char* * topics; |
nucho | 3:1cf99502f396 | 27 | enum { DEBUG = 1 }; |
nucho | 3:1cf99502f396 | 28 | enum { INFO = 2 }; |
nucho | 3:1cf99502f396 | 29 | enum { WARN = 4 }; |
nucho | 3:1cf99502f396 | 30 | enum { ERROR = 8 }; |
nucho | 3:1cf99502f396 | 31 | enum { FATAL = 16 }; |
nucho | 3:1cf99502f396 | 32 | |
nucho | 3:1cf99502f396 | 33 | virtual int serialize(unsigned char *outbuffer) const |
nucho | 3:1cf99502f396 | 34 | { |
nucho | 3:1cf99502f396 | 35 | int offset = 0; |
nucho | 3:1cf99502f396 | 36 | offset += this->header.serialize(outbuffer + offset); |
nucho | 3:1cf99502f396 | 37 | offset += this->level.serialize(outbuffer + offset); |
nucho | 3:1cf99502f396 | 38 | uint32_t * length_name = (uint32_t *)(outbuffer + offset); |
nucho | 3:1cf99502f396 | 39 | *length_name = strlen( (const char*) this->name); |
nucho | 3:1cf99502f396 | 40 | offset += 4; |
nucho | 3:1cf99502f396 | 41 | memcpy(outbuffer + offset, this->name, *length_name); |
nucho | 3:1cf99502f396 | 42 | offset += *length_name; |
nucho | 3:1cf99502f396 | 43 | uint32_t * length_msg = (uint32_t *)(outbuffer + offset); |
nucho | 3:1cf99502f396 | 44 | *length_msg = strlen( (const char*) this->msg); |
nucho | 3:1cf99502f396 | 45 | offset += 4; |
nucho | 3:1cf99502f396 | 46 | memcpy(outbuffer + offset, this->msg, *length_msg); |
nucho | 3:1cf99502f396 | 47 | offset += *length_msg; |
nucho | 3:1cf99502f396 | 48 | uint32_t * length_file = (uint32_t *)(outbuffer + offset); |
nucho | 3:1cf99502f396 | 49 | *length_file = strlen( (const char*) this->file); |
nucho | 3:1cf99502f396 | 50 | offset += 4; |
nucho | 3:1cf99502f396 | 51 | memcpy(outbuffer + offset, this->file, *length_file); |
nucho | 3:1cf99502f396 | 52 | offset += *length_file; |
nucho | 3:1cf99502f396 | 53 | uint32_t * length_function = (uint32_t *)(outbuffer + offset); |
nucho | 3:1cf99502f396 | 54 | *length_function = strlen( (const char*) this->function); |
nucho | 3:1cf99502f396 | 55 | offset += 4; |
nucho | 3:1cf99502f396 | 56 | memcpy(outbuffer + offset, this->function, *length_function); |
nucho | 3:1cf99502f396 | 57 | offset += *length_function; |
nucho | 3:1cf99502f396 | 58 | *(outbuffer + offset + 0) = (this->line >> (8 * 0)) & 0xFF; |
nucho | 3:1cf99502f396 | 59 | *(outbuffer + offset + 1) = (this->line >> (8 * 1)) & 0xFF; |
nucho | 3:1cf99502f396 | 60 | *(outbuffer + offset + 2) = (this->line >> (8 * 2)) & 0xFF; |
nucho | 3:1cf99502f396 | 61 | *(outbuffer + offset + 3) = (this->line >> (8 * 3)) & 0xFF; |
nucho | 3:1cf99502f396 | 62 | offset += sizeof(this->line); |
nucho | 3:1cf99502f396 | 63 | *(outbuffer + offset++) = topics_length; |
nucho | 3:1cf99502f396 | 64 | *(outbuffer + offset++) = 0; |
nucho | 3:1cf99502f396 | 65 | *(outbuffer + offset++) = 0; |
nucho | 3:1cf99502f396 | 66 | *(outbuffer + offset++) = 0; |
nucho | 3:1cf99502f396 | 67 | for( uint8_t i = 0; i < topics_length; i++){ |
nucho | 3:1cf99502f396 | 68 | uint32_t * length_topicsi = (uint32_t *)(outbuffer + offset); |
nucho | 3:1cf99502f396 | 69 | *length_topicsi = strlen( (const char*) this->topics[i]); |
nucho | 3:1cf99502f396 | 70 | offset += 4; |
nucho | 3:1cf99502f396 | 71 | memcpy(outbuffer + offset, this->topics[i], *length_topicsi); |
nucho | 3:1cf99502f396 | 72 | offset += *length_topicsi; |
nucho | 3:1cf99502f396 | 73 | } |
nucho | 3:1cf99502f396 | 74 | return offset; |
nucho | 3:1cf99502f396 | 75 | } |
nucho | 3:1cf99502f396 | 76 | |
nucho | 3:1cf99502f396 | 77 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 3:1cf99502f396 | 78 | { |
nucho | 3:1cf99502f396 | 79 | int offset = 0; |
nucho | 3:1cf99502f396 | 80 | offset += this->header.deserialize(inbuffer + offset); |
nucho | 3:1cf99502f396 | 81 | offset += this->level.deserialize(inbuffer + offset); |
nucho | 3:1cf99502f396 | 82 | uint32_t length_name = *(uint32_t *)(inbuffer + offset); |
nucho | 3:1cf99502f396 | 83 | offset += 4; |
nucho | 3:1cf99502f396 | 84 | for(unsigned int k= offset; k< offset+length_name; ++k){ |
nucho | 3:1cf99502f396 | 85 | inbuffer[k-1]=inbuffer[k]; |
nucho | 3:1cf99502f396 | 86 | } |
nucho | 3:1cf99502f396 | 87 | inbuffer[offset+length_name-1]=0; |
nucho | 3:1cf99502f396 | 88 | this->name = (char *)(inbuffer + offset-1); |
nucho | 3:1cf99502f396 | 89 | offset += length_name; |
nucho | 3:1cf99502f396 | 90 | uint32_t length_msg = *(uint32_t *)(inbuffer + offset); |
nucho | 3:1cf99502f396 | 91 | offset += 4; |
nucho | 3:1cf99502f396 | 92 | for(unsigned int k= offset; k< offset+length_msg; ++k){ |
nucho | 3:1cf99502f396 | 93 | inbuffer[k-1]=inbuffer[k]; |
nucho | 3:1cf99502f396 | 94 | } |
nucho | 3:1cf99502f396 | 95 | inbuffer[offset+length_msg-1]=0; |
nucho | 3:1cf99502f396 | 96 | this->msg = (char *)(inbuffer + offset-1); |
nucho | 3:1cf99502f396 | 97 | offset += length_msg; |
nucho | 3:1cf99502f396 | 98 | uint32_t length_file = *(uint32_t *)(inbuffer + offset); |
nucho | 3:1cf99502f396 | 99 | offset += 4; |
nucho | 3:1cf99502f396 | 100 | for(unsigned int k= offset; k< offset+length_file; ++k){ |
nucho | 3:1cf99502f396 | 101 | inbuffer[k-1]=inbuffer[k]; |
nucho | 3:1cf99502f396 | 102 | } |
nucho | 3:1cf99502f396 | 103 | inbuffer[offset+length_file-1]=0; |
nucho | 3:1cf99502f396 | 104 | this->file = (char *)(inbuffer + offset-1); |
nucho | 3:1cf99502f396 | 105 | offset += length_file; |
nucho | 3:1cf99502f396 | 106 | uint32_t length_function = *(uint32_t *)(inbuffer + offset); |
nucho | 3:1cf99502f396 | 107 | offset += 4; |
nucho | 3:1cf99502f396 | 108 | for(unsigned int k= offset; k< offset+length_function; ++k){ |
nucho | 3:1cf99502f396 | 109 | inbuffer[k-1]=inbuffer[k]; |
nucho | 3:1cf99502f396 | 110 | } |
nucho | 3:1cf99502f396 | 111 | inbuffer[offset+length_function-1]=0; |
nucho | 3:1cf99502f396 | 112 | this->function = (char *)(inbuffer + offset-1); |
nucho | 3:1cf99502f396 | 113 | offset += length_function; |
nucho | 3:1cf99502f396 | 114 | this->line |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 3:1cf99502f396 | 115 | this->line |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 3:1cf99502f396 | 116 | this->line |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 3:1cf99502f396 | 117 | this->line |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 3:1cf99502f396 | 118 | offset += sizeof(this->line); |
nucho | 3:1cf99502f396 | 119 | uint8_t topics_lengthT = *(inbuffer + offset++); |
nucho | 3:1cf99502f396 | 120 | if(topics_lengthT > topics_length) |
nucho | 3:1cf99502f396 | 121 | this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*)); |
nucho | 3:1cf99502f396 | 122 | offset += 3; |
nucho | 3:1cf99502f396 | 123 | topics_length = topics_lengthT; |
nucho | 3:1cf99502f396 | 124 | for( uint8_t i = 0; i < topics_length; i++){ |
nucho | 3:1cf99502f396 | 125 | uint32_t length_st_topics = *(uint32_t *)(inbuffer + offset); |
nucho | 3:1cf99502f396 | 126 | offset += 4; |
nucho | 3:1cf99502f396 | 127 | for(unsigned int k= offset; k< offset+length_st_topics; ++k){ |
nucho | 3:1cf99502f396 | 128 | inbuffer[k-1]=inbuffer[k]; |
nucho | 3:1cf99502f396 | 129 | } |
nucho | 3:1cf99502f396 | 130 | inbuffer[offset+length_st_topics-1]=0; |
nucho | 3:1cf99502f396 | 131 | this->st_topics = (char *)(inbuffer + offset-1); |
nucho | 3:1cf99502f396 | 132 | offset += length_st_topics; |
nucho | 3:1cf99502f396 | 133 | memcpy( &(this->topics[i]), &(this->st_topics), sizeof(char*)); |
nucho | 3:1cf99502f396 | 134 | } |
nucho | 3:1cf99502f396 | 135 | return offset; |
nucho | 3:1cf99502f396 | 136 | } |
nucho | 3:1cf99502f396 | 137 | |
nucho | 3:1cf99502f396 | 138 | virtual const char * getType(){ return "rosgraph_msgs/Log"; }; |
nucho | 3:1cf99502f396 | 139 | virtual const char * getMD5(){ return "acffd30cd6b6de30f120938c17c593fb"; }; |
nucho | 3:1cf99502f396 | 140 | |
nucho | 3:1cf99502f396 | 141 | }; |
nucho | 3:1cf99502f396 | 142 | |
nucho | 3:1cf99502f396 | 143 | } |
nucho | 3:1cf99502f396 | 144 | #endif |