This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial. This program contains an example.
Dependencies: rosserial_mbed_lib mbed Servo
dianostic_msgs/SelfTest.h@3:dff241b66f84, 2011-11-12 (annotated)
- Committer:
- nucho
- Date:
- Sat Nov 12 23:53:04 2011 +0000
- Revision:
- 3:dff241b66f84
- Parent:
- 0:06fc856e99ca
This program supported the revision of 167 of rosserial.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
nucho | 3:dff241b66f84 | 1 | #ifndef _ROS_SERVICE_SelfTest_h |
nucho | 3:dff241b66f84 | 2 | #define _ROS_SERVICE_SelfTest_h |
nucho | 0:06fc856e99ca | 3 | #include <stdint.h> |
nucho | 0:06fc856e99ca | 4 | #include <string.h> |
nucho | 0:06fc856e99ca | 5 | #include <stdlib.h> |
nucho | 3:dff241b66f84 | 6 | #include "ros/msg.h" |
nucho | 0:06fc856e99ca | 7 | #include "diagnostic_msgs/DiagnosticStatus.h" |
nucho | 3:dff241b66f84 | 8 | #include "diagnostic_msgs/byte.h" |
nucho | 0:06fc856e99ca | 9 | |
nucho | 0:06fc856e99ca | 10 | namespace diagnostic_msgs |
nucho | 0:06fc856e99ca | 11 | { |
nucho | 0:06fc856e99ca | 12 | |
nucho | 0:06fc856e99ca | 13 | static const char SELFTEST[] = "diagnostic_msgs/SelfTest"; |
nucho | 0:06fc856e99ca | 14 | |
nucho | 0:06fc856e99ca | 15 | class SelfTestRequest : public ros::Msg |
nucho | 0:06fc856e99ca | 16 | { |
nucho | 0:06fc856e99ca | 17 | public: |
nucho | 0:06fc856e99ca | 18 | |
nucho | 3:dff241b66f84 | 19 | virtual int serialize(unsigned char *outbuffer) const |
nucho | 0:06fc856e99ca | 20 | { |
nucho | 0:06fc856e99ca | 21 | int offset = 0; |
nucho | 0:06fc856e99ca | 22 | return offset; |
nucho | 0:06fc856e99ca | 23 | } |
nucho | 0:06fc856e99ca | 24 | |
nucho | 0:06fc856e99ca | 25 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:06fc856e99ca | 26 | { |
nucho | 0:06fc856e99ca | 27 | int offset = 0; |
nucho | 0:06fc856e99ca | 28 | return offset; |
nucho | 0:06fc856e99ca | 29 | } |
nucho | 0:06fc856e99ca | 30 | |
nucho | 3:dff241b66f84 | 31 | virtual const char * getType(){ return SELFTEST; }; |
nucho | 3:dff241b66f84 | 32 | virtual const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; |
nucho | 0:06fc856e99ca | 33 | |
nucho | 0:06fc856e99ca | 34 | }; |
nucho | 0:06fc856e99ca | 35 | |
nucho | 0:06fc856e99ca | 36 | class SelfTestResponse : public ros::Msg |
nucho | 0:06fc856e99ca | 37 | { |
nucho | 0:06fc856e99ca | 38 | public: |
nucho | 0:06fc856e99ca | 39 | char * id; |
nucho | 3:dff241b66f84 | 40 | diagnostic_msgs::byte passed; |
nucho | 3:dff241b66f84 | 41 | uint8_t status_length; |
nucho | 0:06fc856e99ca | 42 | diagnostic_msgs::DiagnosticStatus st_status; |
nucho | 0:06fc856e99ca | 43 | diagnostic_msgs::DiagnosticStatus * status; |
nucho | 0:06fc856e99ca | 44 | |
nucho | 3:dff241b66f84 | 45 | virtual int serialize(unsigned char *outbuffer) const |
nucho | 0:06fc856e99ca | 46 | { |
nucho | 0:06fc856e99ca | 47 | int offset = 0; |
nucho | 3:dff241b66f84 | 48 | uint32_t * length_id = (uint32_t *)(outbuffer + offset); |
nucho | 0:06fc856e99ca | 49 | *length_id = strlen( (const char*) this->id); |
nucho | 0:06fc856e99ca | 50 | offset += 4; |
nucho | 0:06fc856e99ca | 51 | memcpy(outbuffer + offset, this->id, *length_id); |
nucho | 0:06fc856e99ca | 52 | offset += *length_id; |
nucho | 3:dff241b66f84 | 53 | offset += this->passed.serialize(outbuffer + offset); |
nucho | 0:06fc856e99ca | 54 | *(outbuffer + offset++) = status_length; |
nucho | 0:06fc856e99ca | 55 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 56 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 57 | *(outbuffer + offset++) = 0; |
nucho | 3:dff241b66f84 | 58 | for( uint8_t i = 0; i < status_length; i++){ |
nucho | 0:06fc856e99ca | 59 | offset += this->status[i].serialize(outbuffer + offset); |
nucho | 0:06fc856e99ca | 60 | } |
nucho | 0:06fc856e99ca | 61 | return offset; |
nucho | 0:06fc856e99ca | 62 | } |
nucho | 0:06fc856e99ca | 63 | |
nucho | 0:06fc856e99ca | 64 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:06fc856e99ca | 65 | { |
nucho | 0:06fc856e99ca | 66 | int offset = 0; |
nucho | 0:06fc856e99ca | 67 | uint32_t length_id = *(uint32_t *)(inbuffer + offset); |
nucho | 0:06fc856e99ca | 68 | offset += 4; |
nucho | 0:06fc856e99ca | 69 | for(unsigned int k= offset; k< offset+length_id; ++k){ |
nucho | 0:06fc856e99ca | 70 | inbuffer[k-1]=inbuffer[k]; |
nucho | 3:dff241b66f84 | 71 | } |
nucho | 0:06fc856e99ca | 72 | inbuffer[offset+length_id-1]=0; |
nucho | 0:06fc856e99ca | 73 | this->id = (char *)(inbuffer + offset-1); |
nucho | 0:06fc856e99ca | 74 | offset += length_id; |
nucho | 3:dff241b66f84 | 75 | offset += this->passed.deserialize(inbuffer + offset); |
nucho | 3:dff241b66f84 | 76 | uint8_t status_lengthT = *(inbuffer + offset++); |
nucho | 0:06fc856e99ca | 77 | if(status_lengthT > status_length) |
nucho | 0:06fc856e99ca | 78 | this->status = (diagnostic_msgs::DiagnosticStatus*)realloc(this->status, status_lengthT * sizeof(diagnostic_msgs::DiagnosticStatus)); |
nucho | 0:06fc856e99ca | 79 | offset += 3; |
nucho | 0:06fc856e99ca | 80 | status_length = status_lengthT; |
nucho | 3:dff241b66f84 | 81 | for( uint8_t i = 0; i < status_length; i++){ |
nucho | 0:06fc856e99ca | 82 | offset += this->st_status.deserialize(inbuffer + offset); |
nucho | 0:06fc856e99ca | 83 | memcpy( &(this->status[i]), &(this->st_status), sizeof(diagnostic_msgs::DiagnosticStatus)); |
nucho | 0:06fc856e99ca | 84 | } |
nucho | 0:06fc856e99ca | 85 | return offset; |
nucho | 0:06fc856e99ca | 86 | } |
nucho | 0:06fc856e99ca | 87 | |
nucho | 0:06fc856e99ca | 88 | virtual const char * getType(){ return SELFTEST; }; |
nucho | 3:dff241b66f84 | 89 | virtual const char * getMD5(){ return "74c9372c870a76da4fc2b3973978b898"; }; |
nucho | 0:06fc856e99ca | 90 | |
nucho | 0:06fc856e99ca | 91 | }; |
nucho | 0:06fc856e99ca | 92 | |
nucho | 3:dff241b66f84 | 93 | class SelfTest { |
nucho | 3:dff241b66f84 | 94 | public: |
nucho | 3:dff241b66f84 | 95 | typedef SelfTestRequest Request; |
nucho | 3:dff241b66f84 | 96 | typedef SelfTestResponse Response; |
nucho | 3:dff241b66f84 | 97 | }; |
nucho | 3:dff241b66f84 | 98 | |
nucho | 0:06fc856e99ca | 99 | } |
nucho | 0:06fc856e99ca | 100 | #endif |