This is a fork from the original, including a small change in the buffer size of the hardware interface (increased to 2048) and decreasing the number of publishers and subscribers to 5. Besides, the library about the message Adc.h was modified so as to increase the number of available Adc channels to be read ( from 6 to 7 ) For this modification, a change in checksum was required

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Committer:
garyservin
Date:
Sat Dec 31 00:48:34 2016 +0000
Revision:
0:9e9b7db60fd5
Initial commit, generated based on a clean kinetic-desktop-full

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 #ifndef _ROS_SERVICE_RequestMessageInfo_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_SERVICE_RequestMessageInfo_h
garyservin 0:9e9b7db60fd5 3 #include <stdint.h>
garyservin 0:9e9b7db60fd5 4 #include <string.h>
garyservin 0:9e9b7db60fd5 5 #include <stdlib.h>
garyservin 0:9e9b7db60fd5 6 #include "ros/msg.h"
garyservin 0:9e9b7db60fd5 7
garyservin 0:9e9b7db60fd5 8 namespace rosserial_msgs
garyservin 0:9e9b7db60fd5 9 {
garyservin 0:9e9b7db60fd5 10
garyservin 0:9e9b7db60fd5 11 static const char REQUESTMESSAGEINFO[] = "rosserial_msgs/RequestMessageInfo";
garyservin 0:9e9b7db60fd5 12
garyservin 0:9e9b7db60fd5 13 class RequestMessageInfoRequest : public ros::Msg
garyservin 0:9e9b7db60fd5 14 {
garyservin 0:9e9b7db60fd5 15 public:
garyservin 0:9e9b7db60fd5 16 typedef const char* _type_type;
garyservin 0:9e9b7db60fd5 17 _type_type type;
garyservin 0:9e9b7db60fd5 18
garyservin 0:9e9b7db60fd5 19 RequestMessageInfoRequest():
garyservin 0:9e9b7db60fd5 20 type("")
garyservin 0:9e9b7db60fd5 21 {
garyservin 0:9e9b7db60fd5 22 }
garyservin 0:9e9b7db60fd5 23
garyservin 0:9e9b7db60fd5 24 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 25 {
garyservin 0:9e9b7db60fd5 26 int offset = 0;
garyservin 0:9e9b7db60fd5 27 uint32_t length_type = strlen(this->type);
garyservin 0:9e9b7db60fd5 28 varToArr(outbuffer + offset, length_type);
garyservin 0:9e9b7db60fd5 29 offset += 4;
garyservin 0:9e9b7db60fd5 30 memcpy(outbuffer + offset, this->type, length_type);
garyservin 0:9e9b7db60fd5 31 offset += length_type;
garyservin 0:9e9b7db60fd5 32 return offset;
garyservin 0:9e9b7db60fd5 33 }
garyservin 0:9e9b7db60fd5 34
garyservin 0:9e9b7db60fd5 35 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 36 {
garyservin 0:9e9b7db60fd5 37 int offset = 0;
garyservin 0:9e9b7db60fd5 38 uint32_t length_type;
garyservin 0:9e9b7db60fd5 39 arrToVar(length_type, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 40 offset += 4;
garyservin 0:9e9b7db60fd5 41 for(unsigned int k= offset; k< offset+length_type; ++k){
garyservin 0:9e9b7db60fd5 42 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 43 }
garyservin 0:9e9b7db60fd5 44 inbuffer[offset+length_type-1]=0;
garyservin 0:9e9b7db60fd5 45 this->type = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 46 offset += length_type;
garyservin 0:9e9b7db60fd5 47 return offset;
garyservin 0:9e9b7db60fd5 48 }
garyservin 0:9e9b7db60fd5 49
garyservin 0:9e9b7db60fd5 50 const char * getType(){ return REQUESTMESSAGEINFO; };
garyservin 0:9e9b7db60fd5 51 const char * getMD5(){ return "dc67331de85cf97091b7d45e5c64ab75"; };
garyservin 0:9e9b7db60fd5 52
garyservin 0:9e9b7db60fd5 53 };
garyservin 0:9e9b7db60fd5 54
garyservin 0:9e9b7db60fd5 55 class RequestMessageInfoResponse : public ros::Msg
garyservin 0:9e9b7db60fd5 56 {
garyservin 0:9e9b7db60fd5 57 public:
garyservin 0:9e9b7db60fd5 58 typedef const char* _md5_type;
garyservin 0:9e9b7db60fd5 59 _md5_type md5;
garyservin 0:9e9b7db60fd5 60 typedef const char* _definition_type;
garyservin 0:9e9b7db60fd5 61 _definition_type definition;
garyservin 0:9e9b7db60fd5 62
garyservin 0:9e9b7db60fd5 63 RequestMessageInfoResponse():
garyservin 0:9e9b7db60fd5 64 md5(""),
garyservin 0:9e9b7db60fd5 65 definition("")
garyservin 0:9e9b7db60fd5 66 {
garyservin 0:9e9b7db60fd5 67 }
garyservin 0:9e9b7db60fd5 68
garyservin 0:9e9b7db60fd5 69 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 70 {
garyservin 0:9e9b7db60fd5 71 int offset = 0;
garyservin 0:9e9b7db60fd5 72 uint32_t length_md5 = strlen(this->md5);
garyservin 0:9e9b7db60fd5 73 varToArr(outbuffer + offset, length_md5);
garyservin 0:9e9b7db60fd5 74 offset += 4;
garyservin 0:9e9b7db60fd5 75 memcpy(outbuffer + offset, this->md5, length_md5);
garyservin 0:9e9b7db60fd5 76 offset += length_md5;
garyservin 0:9e9b7db60fd5 77 uint32_t length_definition = strlen(this->definition);
garyservin 0:9e9b7db60fd5 78 varToArr(outbuffer + offset, length_definition);
garyservin 0:9e9b7db60fd5 79 offset += 4;
garyservin 0:9e9b7db60fd5 80 memcpy(outbuffer + offset, this->definition, length_definition);
garyservin 0:9e9b7db60fd5 81 offset += length_definition;
garyservin 0:9e9b7db60fd5 82 return offset;
garyservin 0:9e9b7db60fd5 83 }
garyservin 0:9e9b7db60fd5 84
garyservin 0:9e9b7db60fd5 85 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 86 {
garyservin 0:9e9b7db60fd5 87 int offset = 0;
garyservin 0:9e9b7db60fd5 88 uint32_t length_md5;
garyservin 0:9e9b7db60fd5 89 arrToVar(length_md5, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 90 offset += 4;
garyservin 0:9e9b7db60fd5 91 for(unsigned int k= offset; k< offset+length_md5; ++k){
garyservin 0:9e9b7db60fd5 92 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 93 }
garyservin 0:9e9b7db60fd5 94 inbuffer[offset+length_md5-1]=0;
garyservin 0:9e9b7db60fd5 95 this->md5 = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 96 offset += length_md5;
garyservin 0:9e9b7db60fd5 97 uint32_t length_definition;
garyservin 0:9e9b7db60fd5 98 arrToVar(length_definition, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 99 offset += 4;
garyservin 0:9e9b7db60fd5 100 for(unsigned int k= offset; k< offset+length_definition; ++k){
garyservin 0:9e9b7db60fd5 101 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 102 }
garyservin 0:9e9b7db60fd5 103 inbuffer[offset+length_definition-1]=0;
garyservin 0:9e9b7db60fd5 104 this->definition = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 105 offset += length_definition;
garyservin 0:9e9b7db60fd5 106 return offset;
garyservin 0:9e9b7db60fd5 107 }
garyservin 0:9e9b7db60fd5 108
garyservin 0:9e9b7db60fd5 109 const char * getType(){ return REQUESTMESSAGEINFO; };
garyservin 0:9e9b7db60fd5 110 const char * getMD5(){ return "fe452186a069bed40f09b8628fe5eac8"; };
garyservin 0:9e9b7db60fd5 111
garyservin 0:9e9b7db60fd5 112 };
garyservin 0:9e9b7db60fd5 113
garyservin 0:9e9b7db60fd5 114 class RequestMessageInfo {
garyservin 0:9e9b7db60fd5 115 public:
garyservin 0:9e9b7db60fd5 116 typedef RequestMessageInfoRequest Request;
garyservin 0:9e9b7db60fd5 117 typedef RequestMessageInfoResponse Response;
garyservin 0:9e9b7db60fd5 118 };
garyservin 0:9e9b7db60fd5 119
garyservin 0:9e9b7db60fd5 120 }
garyservin 0:9e9b7db60fd5 121 #endif