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:
jacobepfl1692
Date:
Tue Oct 17 18:49:03 2017 +0000
Revision:
2:9114cc24ddcf
Parent:
0:9e9b7db60fd5
I increased the channels of the ADC to 6 (hence change in checksum) because my application needed it (STM32f407V6)

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 #ifndef _ROS_SERVICE_GetModelState_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_SERVICE_GetModelState_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 #include "geometry_msgs/Pose.h"
garyservin 0:9e9b7db60fd5 8 #include "geometry_msgs/Twist.h"
garyservin 0:9e9b7db60fd5 9 #include "std_msgs/Header.h"
garyservin 0:9e9b7db60fd5 10
garyservin 0:9e9b7db60fd5 11 namespace gazebo_msgs
garyservin 0:9e9b7db60fd5 12 {
garyservin 0:9e9b7db60fd5 13
garyservin 0:9e9b7db60fd5 14 static const char GETMODELSTATE[] = "gazebo_msgs/GetModelState";
garyservin 0:9e9b7db60fd5 15
garyservin 0:9e9b7db60fd5 16 class GetModelStateRequest : public ros::Msg
garyservin 0:9e9b7db60fd5 17 {
garyservin 0:9e9b7db60fd5 18 public:
garyservin 0:9e9b7db60fd5 19 typedef const char* _model_name_type;
garyservin 0:9e9b7db60fd5 20 _model_name_type model_name;
garyservin 0:9e9b7db60fd5 21 typedef const char* _relative_entity_name_type;
garyservin 0:9e9b7db60fd5 22 _relative_entity_name_type relative_entity_name;
garyservin 0:9e9b7db60fd5 23
garyservin 0:9e9b7db60fd5 24 GetModelStateRequest():
garyservin 0:9e9b7db60fd5 25 model_name(""),
garyservin 0:9e9b7db60fd5 26 relative_entity_name("")
garyservin 0:9e9b7db60fd5 27 {
garyservin 0:9e9b7db60fd5 28 }
garyservin 0:9e9b7db60fd5 29
garyservin 0:9e9b7db60fd5 30 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 31 {
garyservin 0:9e9b7db60fd5 32 int offset = 0;
garyservin 0:9e9b7db60fd5 33 uint32_t length_model_name = strlen(this->model_name);
garyservin 0:9e9b7db60fd5 34 varToArr(outbuffer + offset, length_model_name);
garyservin 0:9e9b7db60fd5 35 offset += 4;
garyservin 0:9e9b7db60fd5 36 memcpy(outbuffer + offset, this->model_name, length_model_name);
garyservin 0:9e9b7db60fd5 37 offset += length_model_name;
garyservin 0:9e9b7db60fd5 38 uint32_t length_relative_entity_name = strlen(this->relative_entity_name);
garyservin 0:9e9b7db60fd5 39 varToArr(outbuffer + offset, length_relative_entity_name);
garyservin 0:9e9b7db60fd5 40 offset += 4;
garyservin 0:9e9b7db60fd5 41 memcpy(outbuffer + offset, this->relative_entity_name, length_relative_entity_name);
garyservin 0:9e9b7db60fd5 42 offset += length_relative_entity_name;
garyservin 0:9e9b7db60fd5 43 return offset;
garyservin 0:9e9b7db60fd5 44 }
garyservin 0:9e9b7db60fd5 45
garyservin 0:9e9b7db60fd5 46 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 47 {
garyservin 0:9e9b7db60fd5 48 int offset = 0;
garyservin 0:9e9b7db60fd5 49 uint32_t length_model_name;
garyservin 0:9e9b7db60fd5 50 arrToVar(length_model_name, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 51 offset += 4;
garyservin 0:9e9b7db60fd5 52 for(unsigned int k= offset; k< offset+length_model_name; ++k){
garyservin 0:9e9b7db60fd5 53 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 54 }
garyservin 0:9e9b7db60fd5 55 inbuffer[offset+length_model_name-1]=0;
garyservin 0:9e9b7db60fd5 56 this->model_name = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 57 offset += length_model_name;
garyservin 0:9e9b7db60fd5 58 uint32_t length_relative_entity_name;
garyservin 0:9e9b7db60fd5 59 arrToVar(length_relative_entity_name, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 60 offset += 4;
garyservin 0:9e9b7db60fd5 61 for(unsigned int k= offset; k< offset+length_relative_entity_name; ++k){
garyservin 0:9e9b7db60fd5 62 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 63 }
garyservin 0:9e9b7db60fd5 64 inbuffer[offset+length_relative_entity_name-1]=0;
garyservin 0:9e9b7db60fd5 65 this->relative_entity_name = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 66 offset += length_relative_entity_name;
garyservin 0:9e9b7db60fd5 67 return offset;
garyservin 0:9e9b7db60fd5 68 }
garyservin 0:9e9b7db60fd5 69
garyservin 0:9e9b7db60fd5 70 const char * getType(){ return GETMODELSTATE; };
garyservin 0:9e9b7db60fd5 71 const char * getMD5(){ return "19d412713cefe4a67437e17a951e759e"; };
garyservin 0:9e9b7db60fd5 72
garyservin 0:9e9b7db60fd5 73 };
garyservin 0:9e9b7db60fd5 74
garyservin 0:9e9b7db60fd5 75 class GetModelStateResponse : public ros::Msg
garyservin 0:9e9b7db60fd5 76 {
garyservin 0:9e9b7db60fd5 77 public:
garyservin 0:9e9b7db60fd5 78 typedef std_msgs::Header _header_type;
garyservin 0:9e9b7db60fd5 79 _header_type header;
garyservin 0:9e9b7db60fd5 80 typedef geometry_msgs::Pose _pose_type;
garyservin 0:9e9b7db60fd5 81 _pose_type pose;
garyservin 0:9e9b7db60fd5 82 typedef geometry_msgs::Twist _twist_type;
garyservin 0:9e9b7db60fd5 83 _twist_type twist;
garyservin 0:9e9b7db60fd5 84 typedef bool _success_type;
garyservin 0:9e9b7db60fd5 85 _success_type success;
garyservin 0:9e9b7db60fd5 86 typedef const char* _status_message_type;
garyservin 0:9e9b7db60fd5 87 _status_message_type status_message;
garyservin 0:9e9b7db60fd5 88
garyservin 0:9e9b7db60fd5 89 GetModelStateResponse():
garyservin 0:9e9b7db60fd5 90 header(),
garyservin 0:9e9b7db60fd5 91 pose(),
garyservin 0:9e9b7db60fd5 92 twist(),
garyservin 0:9e9b7db60fd5 93 success(0),
garyservin 0:9e9b7db60fd5 94 status_message("")
garyservin 0:9e9b7db60fd5 95 {
garyservin 0:9e9b7db60fd5 96 }
garyservin 0:9e9b7db60fd5 97
garyservin 0:9e9b7db60fd5 98 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 99 {
garyservin 0:9e9b7db60fd5 100 int offset = 0;
garyservin 0:9e9b7db60fd5 101 offset += this->header.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 102 offset += this->pose.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 103 offset += this->twist.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 104 union {
garyservin 0:9e9b7db60fd5 105 bool real;
garyservin 0:9e9b7db60fd5 106 uint8_t base;
garyservin 0:9e9b7db60fd5 107 } u_success;
garyservin 0:9e9b7db60fd5 108 u_success.real = this->success;
garyservin 0:9e9b7db60fd5 109 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 110 offset += sizeof(this->success);
garyservin 0:9e9b7db60fd5 111 uint32_t length_status_message = strlen(this->status_message);
garyservin 0:9e9b7db60fd5 112 varToArr(outbuffer + offset, length_status_message);
garyservin 0:9e9b7db60fd5 113 offset += 4;
garyservin 0:9e9b7db60fd5 114 memcpy(outbuffer + offset, this->status_message, length_status_message);
garyservin 0:9e9b7db60fd5 115 offset += length_status_message;
garyservin 0:9e9b7db60fd5 116 return offset;
garyservin 0:9e9b7db60fd5 117 }
garyservin 0:9e9b7db60fd5 118
garyservin 0:9e9b7db60fd5 119 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 120 {
garyservin 0:9e9b7db60fd5 121 int offset = 0;
garyservin 0:9e9b7db60fd5 122 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 123 offset += this->pose.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 124 offset += this->twist.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 125 union {
garyservin 0:9e9b7db60fd5 126 bool real;
garyservin 0:9e9b7db60fd5 127 uint8_t base;
garyservin 0:9e9b7db60fd5 128 } u_success;
garyservin 0:9e9b7db60fd5 129 u_success.base = 0;
garyservin 0:9e9b7db60fd5 130 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 131 this->success = u_success.real;
garyservin 0:9e9b7db60fd5 132 offset += sizeof(this->success);
garyservin 0:9e9b7db60fd5 133 uint32_t length_status_message;
garyservin 0:9e9b7db60fd5 134 arrToVar(length_status_message, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 135 offset += 4;
garyservin 0:9e9b7db60fd5 136 for(unsigned int k= offset; k< offset+length_status_message; ++k){
garyservin 0:9e9b7db60fd5 137 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 138 }
garyservin 0:9e9b7db60fd5 139 inbuffer[offset+length_status_message-1]=0;
garyservin 0:9e9b7db60fd5 140 this->status_message = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 141 offset += length_status_message;
garyservin 0:9e9b7db60fd5 142 return offset;
garyservin 0:9e9b7db60fd5 143 }
garyservin 0:9e9b7db60fd5 144
garyservin 0:9e9b7db60fd5 145 const char * getType(){ return GETMODELSTATE; };
garyservin 0:9e9b7db60fd5 146 const char * getMD5(){ return "ccd51739bb00f0141629e87b792e92b9"; };
garyservin 0:9e9b7db60fd5 147
garyservin 0:9e9b7db60fd5 148 };
garyservin 0:9e9b7db60fd5 149
garyservin 0:9e9b7db60fd5 150 class GetModelState {
garyservin 0:9e9b7db60fd5 151 public:
garyservin 0:9e9b7db60fd5 152 typedef GetModelStateRequest Request;
garyservin 0:9e9b7db60fd5 153 typedef GetModelStateResponse Response;
garyservin 0:9e9b7db60fd5 154 };
garyservin 0:9e9b7db60fd5 155
garyservin 0:9e9b7db60fd5 156 }
garyservin 0:9e9b7db60fd5 157 #endif