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_gazebo_msgs_ContactState_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_gazebo_msgs_ContactState_h
garyservin 0:9e9b7db60fd5 3
garyservin 0:9e9b7db60fd5 4 #include <stdint.h>
garyservin 0:9e9b7db60fd5 5 #include <string.h>
garyservin 0:9e9b7db60fd5 6 #include <stdlib.h>
garyservin 0:9e9b7db60fd5 7 #include "ros/msg.h"
garyservin 0:9e9b7db60fd5 8 #include "geometry_msgs/Wrench.h"
garyservin 0:9e9b7db60fd5 9 #include "geometry_msgs/Vector3.h"
garyservin 0:9e9b7db60fd5 10
garyservin 0:9e9b7db60fd5 11 namespace gazebo_msgs
garyservin 0:9e9b7db60fd5 12 {
garyservin 0:9e9b7db60fd5 13
garyservin 0:9e9b7db60fd5 14 class ContactState : public ros::Msg
garyservin 0:9e9b7db60fd5 15 {
garyservin 0:9e9b7db60fd5 16 public:
garyservin 0:9e9b7db60fd5 17 typedef const char* _info_type;
garyservin 0:9e9b7db60fd5 18 _info_type info;
garyservin 0:9e9b7db60fd5 19 typedef const char* _collision1_name_type;
garyservin 0:9e9b7db60fd5 20 _collision1_name_type collision1_name;
garyservin 0:9e9b7db60fd5 21 typedef const char* _collision2_name_type;
garyservin 0:9e9b7db60fd5 22 _collision2_name_type collision2_name;
garyservin 0:9e9b7db60fd5 23 uint32_t wrenches_length;
garyservin 0:9e9b7db60fd5 24 typedef geometry_msgs::Wrench _wrenches_type;
garyservin 0:9e9b7db60fd5 25 _wrenches_type st_wrenches;
garyservin 0:9e9b7db60fd5 26 _wrenches_type * wrenches;
garyservin 0:9e9b7db60fd5 27 typedef geometry_msgs::Wrench _total_wrench_type;
garyservin 0:9e9b7db60fd5 28 _total_wrench_type total_wrench;
garyservin 0:9e9b7db60fd5 29 uint32_t contact_positions_length;
garyservin 0:9e9b7db60fd5 30 typedef geometry_msgs::Vector3 _contact_positions_type;
garyservin 0:9e9b7db60fd5 31 _contact_positions_type st_contact_positions;
garyservin 0:9e9b7db60fd5 32 _contact_positions_type * contact_positions;
garyservin 0:9e9b7db60fd5 33 uint32_t contact_normals_length;
garyservin 0:9e9b7db60fd5 34 typedef geometry_msgs::Vector3 _contact_normals_type;
garyservin 0:9e9b7db60fd5 35 _contact_normals_type st_contact_normals;
garyservin 0:9e9b7db60fd5 36 _contact_normals_type * contact_normals;
garyservin 0:9e9b7db60fd5 37 uint32_t depths_length;
garyservin 0:9e9b7db60fd5 38 typedef double _depths_type;
garyservin 0:9e9b7db60fd5 39 _depths_type st_depths;
garyservin 0:9e9b7db60fd5 40 _depths_type * depths;
garyservin 0:9e9b7db60fd5 41
garyservin 0:9e9b7db60fd5 42 ContactState():
garyservin 0:9e9b7db60fd5 43 info(""),
garyservin 0:9e9b7db60fd5 44 collision1_name(""),
garyservin 0:9e9b7db60fd5 45 collision2_name(""),
garyservin 0:9e9b7db60fd5 46 wrenches_length(0), wrenches(NULL),
garyservin 0:9e9b7db60fd5 47 total_wrench(),
garyservin 0:9e9b7db60fd5 48 contact_positions_length(0), contact_positions(NULL),
garyservin 0:9e9b7db60fd5 49 contact_normals_length(0), contact_normals(NULL),
garyservin 0:9e9b7db60fd5 50 depths_length(0), depths(NULL)
garyservin 0:9e9b7db60fd5 51 {
garyservin 0:9e9b7db60fd5 52 }
garyservin 0:9e9b7db60fd5 53
garyservin 0:9e9b7db60fd5 54 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 55 {
garyservin 0:9e9b7db60fd5 56 int offset = 0;
garyservin 0:9e9b7db60fd5 57 uint32_t length_info = strlen(this->info);
garyservin 0:9e9b7db60fd5 58 varToArr(outbuffer + offset, length_info);
garyservin 0:9e9b7db60fd5 59 offset += 4;
garyservin 0:9e9b7db60fd5 60 memcpy(outbuffer + offset, this->info, length_info);
garyservin 0:9e9b7db60fd5 61 offset += length_info;
garyservin 0:9e9b7db60fd5 62 uint32_t length_collision1_name = strlen(this->collision1_name);
garyservin 0:9e9b7db60fd5 63 varToArr(outbuffer + offset, length_collision1_name);
garyservin 0:9e9b7db60fd5 64 offset += 4;
garyservin 0:9e9b7db60fd5 65 memcpy(outbuffer + offset, this->collision1_name, length_collision1_name);
garyservin 0:9e9b7db60fd5 66 offset += length_collision1_name;
garyservin 0:9e9b7db60fd5 67 uint32_t length_collision2_name = strlen(this->collision2_name);
garyservin 0:9e9b7db60fd5 68 varToArr(outbuffer + offset, length_collision2_name);
garyservin 0:9e9b7db60fd5 69 offset += 4;
garyservin 0:9e9b7db60fd5 70 memcpy(outbuffer + offset, this->collision2_name, length_collision2_name);
garyservin 0:9e9b7db60fd5 71 offset += length_collision2_name;
garyservin 0:9e9b7db60fd5 72 *(outbuffer + offset + 0) = (this->wrenches_length >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 73 *(outbuffer + offset + 1) = (this->wrenches_length >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 74 *(outbuffer + offset + 2) = (this->wrenches_length >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 75 *(outbuffer + offset + 3) = (this->wrenches_length >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 76 offset += sizeof(this->wrenches_length);
garyservin 0:9e9b7db60fd5 77 for( uint32_t i = 0; i < wrenches_length; i++){
garyservin 0:9e9b7db60fd5 78 offset += this->wrenches[i].serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 79 }
garyservin 0:9e9b7db60fd5 80 offset += this->total_wrench.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 81 *(outbuffer + offset + 0) = (this->contact_positions_length >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 82 *(outbuffer + offset + 1) = (this->contact_positions_length >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 83 *(outbuffer + offset + 2) = (this->contact_positions_length >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 84 *(outbuffer + offset + 3) = (this->contact_positions_length >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 85 offset += sizeof(this->contact_positions_length);
garyservin 0:9e9b7db60fd5 86 for( uint32_t i = 0; i < contact_positions_length; i++){
garyservin 0:9e9b7db60fd5 87 offset += this->contact_positions[i].serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 88 }
garyservin 0:9e9b7db60fd5 89 *(outbuffer + offset + 0) = (this->contact_normals_length >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 90 *(outbuffer + offset + 1) = (this->contact_normals_length >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 91 *(outbuffer + offset + 2) = (this->contact_normals_length >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 92 *(outbuffer + offset + 3) = (this->contact_normals_length >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 93 offset += sizeof(this->contact_normals_length);
garyservin 0:9e9b7db60fd5 94 for( uint32_t i = 0; i < contact_normals_length; i++){
garyservin 0:9e9b7db60fd5 95 offset += this->contact_normals[i].serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 96 }
garyservin 0:9e9b7db60fd5 97 *(outbuffer + offset + 0) = (this->depths_length >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 98 *(outbuffer + offset + 1) = (this->depths_length >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 99 *(outbuffer + offset + 2) = (this->depths_length >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 100 *(outbuffer + offset + 3) = (this->depths_length >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 101 offset += sizeof(this->depths_length);
garyservin 0:9e9b7db60fd5 102 for( uint32_t i = 0; i < depths_length; i++){
garyservin 0:9e9b7db60fd5 103 union {
garyservin 0:9e9b7db60fd5 104 double real;
garyservin 0:9e9b7db60fd5 105 uint64_t base;
garyservin 0:9e9b7db60fd5 106 } u_depthsi;
garyservin 0:9e9b7db60fd5 107 u_depthsi.real = this->depths[i];
garyservin 0:9e9b7db60fd5 108 *(outbuffer + offset + 0) = (u_depthsi.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 109 *(outbuffer + offset + 1) = (u_depthsi.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 110 *(outbuffer + offset + 2) = (u_depthsi.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 111 *(outbuffer + offset + 3) = (u_depthsi.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 112 *(outbuffer + offset + 4) = (u_depthsi.base >> (8 * 4)) & 0xFF;
garyservin 0:9e9b7db60fd5 113 *(outbuffer + offset + 5) = (u_depthsi.base >> (8 * 5)) & 0xFF;
garyservin 0:9e9b7db60fd5 114 *(outbuffer + offset + 6) = (u_depthsi.base >> (8 * 6)) & 0xFF;
garyservin 0:9e9b7db60fd5 115 *(outbuffer + offset + 7) = (u_depthsi.base >> (8 * 7)) & 0xFF;
garyservin 0:9e9b7db60fd5 116 offset += sizeof(this->depths[i]);
garyservin 0:9e9b7db60fd5 117 }
garyservin 0:9e9b7db60fd5 118 return offset;
garyservin 0:9e9b7db60fd5 119 }
garyservin 0:9e9b7db60fd5 120
garyservin 0:9e9b7db60fd5 121 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 122 {
garyservin 0:9e9b7db60fd5 123 int offset = 0;
garyservin 0:9e9b7db60fd5 124 uint32_t length_info;
garyservin 0:9e9b7db60fd5 125 arrToVar(length_info, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 126 offset += 4;
garyservin 0:9e9b7db60fd5 127 for(unsigned int k= offset; k< offset+length_info; ++k){
garyservin 0:9e9b7db60fd5 128 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 129 }
garyservin 0:9e9b7db60fd5 130 inbuffer[offset+length_info-1]=0;
garyservin 0:9e9b7db60fd5 131 this->info = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 132 offset += length_info;
garyservin 0:9e9b7db60fd5 133 uint32_t length_collision1_name;
garyservin 0:9e9b7db60fd5 134 arrToVar(length_collision1_name, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 135 offset += 4;
garyservin 0:9e9b7db60fd5 136 for(unsigned int k= offset; k< offset+length_collision1_name; ++k){
garyservin 0:9e9b7db60fd5 137 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 138 }
garyservin 0:9e9b7db60fd5 139 inbuffer[offset+length_collision1_name-1]=0;
garyservin 0:9e9b7db60fd5 140 this->collision1_name = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 141 offset += length_collision1_name;
garyservin 0:9e9b7db60fd5 142 uint32_t length_collision2_name;
garyservin 0:9e9b7db60fd5 143 arrToVar(length_collision2_name, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 144 offset += 4;
garyservin 0:9e9b7db60fd5 145 for(unsigned int k= offset; k< offset+length_collision2_name; ++k){
garyservin 0:9e9b7db60fd5 146 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 147 }
garyservin 0:9e9b7db60fd5 148 inbuffer[offset+length_collision2_name-1]=0;
garyservin 0:9e9b7db60fd5 149 this->collision2_name = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 150 offset += length_collision2_name;
garyservin 0:9e9b7db60fd5 151 uint32_t wrenches_lengthT = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 152 wrenches_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 153 wrenches_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 154 wrenches_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 155 offset += sizeof(this->wrenches_length);
garyservin 0:9e9b7db60fd5 156 if(wrenches_lengthT > wrenches_length)
garyservin 0:9e9b7db60fd5 157 this->wrenches = (geometry_msgs::Wrench*)realloc(this->wrenches, wrenches_lengthT * sizeof(geometry_msgs::Wrench));
garyservin 0:9e9b7db60fd5 158 wrenches_length = wrenches_lengthT;
garyservin 0:9e9b7db60fd5 159 for( uint32_t i = 0; i < wrenches_length; i++){
garyservin 0:9e9b7db60fd5 160 offset += this->st_wrenches.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 161 memcpy( &(this->wrenches[i]), &(this->st_wrenches), sizeof(geometry_msgs::Wrench));
garyservin 0:9e9b7db60fd5 162 }
garyservin 0:9e9b7db60fd5 163 offset += this->total_wrench.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 164 uint32_t contact_positions_lengthT = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 165 contact_positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 166 contact_positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 167 contact_positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 168 offset += sizeof(this->contact_positions_length);
garyservin 0:9e9b7db60fd5 169 if(contact_positions_lengthT > contact_positions_length)
garyservin 0:9e9b7db60fd5 170 this->contact_positions = (geometry_msgs::Vector3*)realloc(this->contact_positions, contact_positions_lengthT * sizeof(geometry_msgs::Vector3));
garyservin 0:9e9b7db60fd5 171 contact_positions_length = contact_positions_lengthT;
garyservin 0:9e9b7db60fd5 172 for( uint32_t i = 0; i < contact_positions_length; i++){
garyservin 0:9e9b7db60fd5 173 offset += this->st_contact_positions.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 174 memcpy( &(this->contact_positions[i]), &(this->st_contact_positions), sizeof(geometry_msgs::Vector3));
garyservin 0:9e9b7db60fd5 175 }
garyservin 0:9e9b7db60fd5 176 uint32_t contact_normals_lengthT = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 177 contact_normals_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 178 contact_normals_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 179 contact_normals_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 180 offset += sizeof(this->contact_normals_length);
garyservin 0:9e9b7db60fd5 181 if(contact_normals_lengthT > contact_normals_length)
garyservin 0:9e9b7db60fd5 182 this->contact_normals = (geometry_msgs::Vector3*)realloc(this->contact_normals, contact_normals_lengthT * sizeof(geometry_msgs::Vector3));
garyservin 0:9e9b7db60fd5 183 contact_normals_length = contact_normals_lengthT;
garyservin 0:9e9b7db60fd5 184 for( uint32_t i = 0; i < contact_normals_length; i++){
garyservin 0:9e9b7db60fd5 185 offset += this->st_contact_normals.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 186 memcpy( &(this->contact_normals[i]), &(this->st_contact_normals), sizeof(geometry_msgs::Vector3));
garyservin 0:9e9b7db60fd5 187 }
garyservin 0:9e9b7db60fd5 188 uint32_t depths_lengthT = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 189 depths_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 190 depths_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 191 depths_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 192 offset += sizeof(this->depths_length);
garyservin 0:9e9b7db60fd5 193 if(depths_lengthT > depths_length)
garyservin 0:9e9b7db60fd5 194 this->depths = (double*)realloc(this->depths, depths_lengthT * sizeof(double));
garyservin 0:9e9b7db60fd5 195 depths_length = depths_lengthT;
garyservin 0:9e9b7db60fd5 196 for( uint32_t i = 0; i < depths_length; i++){
garyservin 0:9e9b7db60fd5 197 union {
garyservin 0:9e9b7db60fd5 198 double real;
garyservin 0:9e9b7db60fd5 199 uint64_t base;
garyservin 0:9e9b7db60fd5 200 } u_st_depths;
garyservin 0:9e9b7db60fd5 201 u_st_depths.base = 0;
garyservin 0:9e9b7db60fd5 202 u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 203 u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 204 u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 205 u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 206 u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:9e9b7db60fd5 207 u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:9e9b7db60fd5 208 u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:9e9b7db60fd5 209 u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:9e9b7db60fd5 210 this->st_depths = u_st_depths.real;
garyservin 0:9e9b7db60fd5 211 offset += sizeof(this->st_depths);
garyservin 0:9e9b7db60fd5 212 memcpy( &(this->depths[i]), &(this->st_depths), sizeof(double));
garyservin 0:9e9b7db60fd5 213 }
garyservin 0:9e9b7db60fd5 214 return offset;
garyservin 0:9e9b7db60fd5 215 }
garyservin 0:9e9b7db60fd5 216
garyservin 0:9e9b7db60fd5 217 const char * getType(){ return "gazebo_msgs/ContactState"; };
garyservin 0:9e9b7db60fd5 218 const char * getMD5(){ return "48c0ffb054b8c444f870cecea1ee50d9"; };
garyservin 0:9e9b7db60fd5 219
garyservin 0:9e9b7db60fd5 220 };
garyservin 0:9e9b7db60fd5 221
garyservin 0:9e9b7db60fd5 222 }
garyservin 0:9e9b7db60fd5 223 #endif