make changes on buffer serial

Dependencies:   BufferedSerial

Dependents:  

Committer:
howanglam3
Date:
Wed May 19 09:50:43 2021 +0000
Revision:
2:3f1139cf73be
Parent:
0:04ac6be8229a
updated buffer serial

Who changed what in which revision?

UserRevisionLine numberNew contents of line
Gary Servin 0:04ac6be8229a 1 #ifndef _ROS_sensor_msgs_JointState_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_sensor_msgs_JointState_h
Gary Servin 0:04ac6be8229a 3
Gary Servin 0:04ac6be8229a 4 #include <stdint.h>
Gary Servin 0:04ac6be8229a 5 #include <string.h>
Gary Servin 0:04ac6be8229a 6 #include <stdlib.h>
Gary Servin 0:04ac6be8229a 7 #include "ros/msg.h"
Gary Servin 0:04ac6be8229a 8 #include "std_msgs/Header.h"
Gary Servin 0:04ac6be8229a 9
Gary Servin 0:04ac6be8229a 10 namespace sensor_msgs
Gary Servin 0:04ac6be8229a 11 {
Gary Servin 0:04ac6be8229a 12
Gary Servin 0:04ac6be8229a 13 class JointState : public ros::Msg
Gary Servin 0:04ac6be8229a 14 {
Gary Servin 0:04ac6be8229a 15 public:
Gary Servin 0:04ac6be8229a 16 typedef std_msgs::Header _header_type;
Gary Servin 0:04ac6be8229a 17 _header_type header;
Gary Servin 0:04ac6be8229a 18 uint32_t name_length;
Gary Servin 0:04ac6be8229a 19 typedef char* _name_type;
Gary Servin 0:04ac6be8229a 20 _name_type st_name;
Gary Servin 0:04ac6be8229a 21 _name_type * name;
Gary Servin 0:04ac6be8229a 22 uint32_t position_length;
Gary Servin 0:04ac6be8229a 23 typedef double _position_type;
Gary Servin 0:04ac6be8229a 24 _position_type st_position;
Gary Servin 0:04ac6be8229a 25 _position_type * position;
Gary Servin 0:04ac6be8229a 26 uint32_t velocity_length;
Gary Servin 0:04ac6be8229a 27 typedef double _velocity_type;
Gary Servin 0:04ac6be8229a 28 _velocity_type st_velocity;
Gary Servin 0:04ac6be8229a 29 _velocity_type * velocity;
Gary Servin 0:04ac6be8229a 30 uint32_t effort_length;
Gary Servin 0:04ac6be8229a 31 typedef double _effort_type;
Gary Servin 0:04ac6be8229a 32 _effort_type st_effort;
Gary Servin 0:04ac6be8229a 33 _effort_type * effort;
Gary Servin 0:04ac6be8229a 34
Gary Servin 0:04ac6be8229a 35 JointState():
Gary Servin 0:04ac6be8229a 36 header(),
Gary Servin 0:04ac6be8229a 37 name_length(0), name(NULL),
Gary Servin 0:04ac6be8229a 38 position_length(0), position(NULL),
Gary Servin 0:04ac6be8229a 39 velocity_length(0), velocity(NULL),
Gary Servin 0:04ac6be8229a 40 effort_length(0), effort(NULL)
Gary Servin 0:04ac6be8229a 41 {
Gary Servin 0:04ac6be8229a 42 }
Gary Servin 0:04ac6be8229a 43
Gary Servin 0:04ac6be8229a 44 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 45 {
Gary Servin 0:04ac6be8229a 46 int offset = 0;
Gary Servin 0:04ac6be8229a 47 offset += this->header.serialize(outbuffer + offset);
Gary Servin 0:04ac6be8229a 48 *(outbuffer + offset + 0) = (this->name_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 49 *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 50 *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 51 *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 52 offset += sizeof(this->name_length);
Gary Servin 0:04ac6be8229a 53 for( uint32_t i = 0; i < name_length; i++){
Gary Servin 0:04ac6be8229a 54 uint32_t length_namei = strlen(this->name[i]);
Gary Servin 0:04ac6be8229a 55 varToArr(outbuffer + offset, length_namei);
Gary Servin 0:04ac6be8229a 56 offset += 4;
Gary Servin 0:04ac6be8229a 57 memcpy(outbuffer + offset, this->name[i], length_namei);
Gary Servin 0:04ac6be8229a 58 offset += length_namei;
Gary Servin 0:04ac6be8229a 59 }
Gary Servin 0:04ac6be8229a 60 *(outbuffer + offset + 0) = (this->position_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 61 *(outbuffer + offset + 1) = (this->position_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 62 *(outbuffer + offset + 2) = (this->position_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 63 *(outbuffer + offset + 3) = (this->position_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 64 offset += sizeof(this->position_length);
Gary Servin 0:04ac6be8229a 65 for( uint32_t i = 0; i < position_length; i++){
Gary Servin 0:04ac6be8229a 66 union {
Gary Servin 0:04ac6be8229a 67 double real;
Gary Servin 0:04ac6be8229a 68 uint64_t base;
Gary Servin 0:04ac6be8229a 69 } u_positioni;
Gary Servin 0:04ac6be8229a 70 u_positioni.real = this->position[i];
Gary Servin 0:04ac6be8229a 71 *(outbuffer + offset + 0) = (u_positioni.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 72 *(outbuffer + offset + 1) = (u_positioni.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 73 *(outbuffer + offset + 2) = (u_positioni.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 74 *(outbuffer + offset + 3) = (u_positioni.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 75 *(outbuffer + offset + 4) = (u_positioni.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 76 *(outbuffer + offset + 5) = (u_positioni.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 77 *(outbuffer + offset + 6) = (u_positioni.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 78 *(outbuffer + offset + 7) = (u_positioni.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 79 offset += sizeof(this->position[i]);
Gary Servin 0:04ac6be8229a 80 }
Gary Servin 0:04ac6be8229a 81 *(outbuffer + offset + 0) = (this->velocity_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 82 *(outbuffer + offset + 1) = (this->velocity_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 83 *(outbuffer + offset + 2) = (this->velocity_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 84 *(outbuffer + offset + 3) = (this->velocity_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 85 offset += sizeof(this->velocity_length);
Gary Servin 0:04ac6be8229a 86 for( uint32_t i = 0; i < velocity_length; i++){
Gary Servin 0:04ac6be8229a 87 union {
Gary Servin 0:04ac6be8229a 88 double real;
Gary Servin 0:04ac6be8229a 89 uint64_t base;
Gary Servin 0:04ac6be8229a 90 } u_velocityi;
Gary Servin 0:04ac6be8229a 91 u_velocityi.real = this->velocity[i];
Gary Servin 0:04ac6be8229a 92 *(outbuffer + offset + 0) = (u_velocityi.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 93 *(outbuffer + offset + 1) = (u_velocityi.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 94 *(outbuffer + offset + 2) = (u_velocityi.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 95 *(outbuffer + offset + 3) = (u_velocityi.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 96 *(outbuffer + offset + 4) = (u_velocityi.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 97 *(outbuffer + offset + 5) = (u_velocityi.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 98 *(outbuffer + offset + 6) = (u_velocityi.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 99 *(outbuffer + offset + 7) = (u_velocityi.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 100 offset += sizeof(this->velocity[i]);
Gary Servin 0:04ac6be8229a 101 }
Gary Servin 0:04ac6be8229a 102 *(outbuffer + offset + 0) = (this->effort_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 103 *(outbuffer + offset + 1) = (this->effort_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 104 *(outbuffer + offset + 2) = (this->effort_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 105 *(outbuffer + offset + 3) = (this->effort_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 106 offset += sizeof(this->effort_length);
Gary Servin 0:04ac6be8229a 107 for( uint32_t i = 0; i < effort_length; i++){
Gary Servin 0:04ac6be8229a 108 union {
Gary Servin 0:04ac6be8229a 109 double real;
Gary Servin 0:04ac6be8229a 110 uint64_t base;
Gary Servin 0:04ac6be8229a 111 } u_efforti;
Gary Servin 0:04ac6be8229a 112 u_efforti.real = this->effort[i];
Gary Servin 0:04ac6be8229a 113 *(outbuffer + offset + 0) = (u_efforti.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 114 *(outbuffer + offset + 1) = (u_efforti.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 115 *(outbuffer + offset + 2) = (u_efforti.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 116 *(outbuffer + offset + 3) = (u_efforti.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 117 *(outbuffer + offset + 4) = (u_efforti.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 118 *(outbuffer + offset + 5) = (u_efforti.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 119 *(outbuffer + offset + 6) = (u_efforti.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 120 *(outbuffer + offset + 7) = (u_efforti.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 121 offset += sizeof(this->effort[i]);
Gary Servin 0:04ac6be8229a 122 }
Gary Servin 0:04ac6be8229a 123 return offset;
Gary Servin 0:04ac6be8229a 124 }
Gary Servin 0:04ac6be8229a 125
Gary Servin 0:04ac6be8229a 126 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 127 {
Gary Servin 0:04ac6be8229a 128 int offset = 0;
Gary Servin 0:04ac6be8229a 129 offset += this->header.deserialize(inbuffer + offset);
Gary Servin 0:04ac6be8229a 130 uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 131 name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 132 name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 133 name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 134 offset += sizeof(this->name_length);
Gary Servin 0:04ac6be8229a 135 if(name_lengthT > name_length)
Gary Servin 0:04ac6be8229a 136 this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
Gary Servin 0:04ac6be8229a 137 name_length = name_lengthT;
Gary Servin 0:04ac6be8229a 138 for( uint32_t i = 0; i < name_length; i++){
Gary Servin 0:04ac6be8229a 139 uint32_t length_st_name;
Gary Servin 0:04ac6be8229a 140 arrToVar(length_st_name, (inbuffer + offset));
Gary Servin 0:04ac6be8229a 141 offset += 4;
Gary Servin 0:04ac6be8229a 142 for(unsigned int k= offset; k< offset+length_st_name; ++k){
Gary Servin 0:04ac6be8229a 143 inbuffer[k-1]=inbuffer[k];
Gary Servin 0:04ac6be8229a 144 }
Gary Servin 0:04ac6be8229a 145 inbuffer[offset+length_st_name-1]=0;
Gary Servin 0:04ac6be8229a 146 this->st_name = (char *)(inbuffer + offset-1);
Gary Servin 0:04ac6be8229a 147 offset += length_st_name;
Gary Servin 0:04ac6be8229a 148 memcpy( &(this->name[i]), &(this->st_name), sizeof(char*));
Gary Servin 0:04ac6be8229a 149 }
Gary Servin 0:04ac6be8229a 150 uint32_t position_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 151 position_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 152 position_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 153 position_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 154 offset += sizeof(this->position_length);
Gary Servin 0:04ac6be8229a 155 if(position_lengthT > position_length)
Gary Servin 0:04ac6be8229a 156 this->position = (double*)realloc(this->position, position_lengthT * sizeof(double));
Gary Servin 0:04ac6be8229a 157 position_length = position_lengthT;
Gary Servin 0:04ac6be8229a 158 for( uint32_t i = 0; i < position_length; i++){
Gary Servin 0:04ac6be8229a 159 union {
Gary Servin 0:04ac6be8229a 160 double real;
Gary Servin 0:04ac6be8229a 161 uint64_t base;
Gary Servin 0:04ac6be8229a 162 } u_st_position;
Gary Servin 0:04ac6be8229a 163 u_st_position.base = 0;
Gary Servin 0:04ac6be8229a 164 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 165 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 166 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 167 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 168 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 169 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 170 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 171 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 172 this->st_position = u_st_position.real;
Gary Servin 0:04ac6be8229a 173 offset += sizeof(this->st_position);
Gary Servin 0:04ac6be8229a 174 memcpy( &(this->position[i]), &(this->st_position), sizeof(double));
Gary Servin 0:04ac6be8229a 175 }
Gary Servin 0:04ac6be8229a 176 uint32_t velocity_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 177 velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 178 velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 179 velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 180 offset += sizeof(this->velocity_length);
Gary Servin 0:04ac6be8229a 181 if(velocity_lengthT > velocity_length)
Gary Servin 0:04ac6be8229a 182 this->velocity = (double*)realloc(this->velocity, velocity_lengthT * sizeof(double));
Gary Servin 0:04ac6be8229a 183 velocity_length = velocity_lengthT;
Gary Servin 0:04ac6be8229a 184 for( uint32_t i = 0; i < velocity_length; i++){
Gary Servin 0:04ac6be8229a 185 union {
Gary Servin 0:04ac6be8229a 186 double real;
Gary Servin 0:04ac6be8229a 187 uint64_t base;
Gary Servin 0:04ac6be8229a 188 } u_st_velocity;
Gary Servin 0:04ac6be8229a 189 u_st_velocity.base = 0;
Gary Servin 0:04ac6be8229a 190 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 191 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 192 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 193 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 194 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 195 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 196 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 197 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 198 this->st_velocity = u_st_velocity.real;
Gary Servin 0:04ac6be8229a 199 offset += sizeof(this->st_velocity);
Gary Servin 0:04ac6be8229a 200 memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(double));
Gary Servin 0:04ac6be8229a 201 }
Gary Servin 0:04ac6be8229a 202 uint32_t effort_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 203 effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 204 effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 205 effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 206 offset += sizeof(this->effort_length);
Gary Servin 0:04ac6be8229a 207 if(effort_lengthT > effort_length)
Gary Servin 0:04ac6be8229a 208 this->effort = (double*)realloc(this->effort, effort_lengthT * sizeof(double));
Gary Servin 0:04ac6be8229a 209 effort_length = effort_lengthT;
Gary Servin 0:04ac6be8229a 210 for( uint32_t i = 0; i < effort_length; i++){
Gary Servin 0:04ac6be8229a 211 union {
Gary Servin 0:04ac6be8229a 212 double real;
Gary Servin 0:04ac6be8229a 213 uint64_t base;
Gary Servin 0:04ac6be8229a 214 } u_st_effort;
Gary Servin 0:04ac6be8229a 215 u_st_effort.base = 0;
Gary Servin 0:04ac6be8229a 216 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 217 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 218 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 219 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 220 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 221 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 222 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 223 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 224 this->st_effort = u_st_effort.real;
Gary Servin 0:04ac6be8229a 225 offset += sizeof(this->st_effort);
Gary Servin 0:04ac6be8229a 226 memcpy( &(this->effort[i]), &(this->st_effort), sizeof(double));
Gary Servin 0:04ac6be8229a 227 }
Gary Servin 0:04ac6be8229a 228 return offset;
Gary Servin 0:04ac6be8229a 229 }
Gary Servin 0:04ac6be8229a 230
Gary Servin 0:04ac6be8229a 231 const char * getType(){ return "sensor_msgs/JointState"; };
Gary Servin 0:04ac6be8229a 232 const char * getMD5(){ return "3066dcd76a6cfaef579bd0f34173e9fd"; };
Gary Servin 0:04ac6be8229a 233
Gary Servin 0:04ac6be8229a 234 };
Gary Servin 0:04ac6be8229a 235
Gary Servin 0:04ac6be8229a 236 }
Gary Servin 0:04ac6be8229a 237 #endif