ROS Serial library for Mbed platforms for ROS Melodic Morenia. Check http://wiki.ros.org/rosserial_mbed/ for more information.

Dependencies:   BufferedSerial

Committer:
krogedal
Date:
Thu May 27 19:25:46 2021 +0000
Revision:
2:fa426560b283
Parent:
0:04ac6be8229a
no change

Who changed what in which revision?

UserRevisionLine numberNew contents of line
Gary Servin 0:04ac6be8229a 1 #ifndef _ROS_control_msgs_JointJog_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_control_msgs_JointJog_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 control_msgs
Gary Servin 0:04ac6be8229a 11 {
Gary Servin 0:04ac6be8229a 12
Gary Servin 0:04ac6be8229a 13 class JointJog : 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 joint_names_length;
Gary Servin 0:04ac6be8229a 19 typedef char* _joint_names_type;
Gary Servin 0:04ac6be8229a 20 _joint_names_type st_joint_names;
Gary Servin 0:04ac6be8229a 21 _joint_names_type * joint_names;
Gary Servin 0:04ac6be8229a 22 uint32_t displacements_length;
Gary Servin 0:04ac6be8229a 23 typedef double _displacements_type;
Gary Servin 0:04ac6be8229a 24 _displacements_type st_displacements;
Gary Servin 0:04ac6be8229a 25 _displacements_type * displacements;
Gary Servin 0:04ac6be8229a 26 uint32_t velocities_length;
Gary Servin 0:04ac6be8229a 27 typedef double _velocities_type;
Gary Servin 0:04ac6be8229a 28 _velocities_type st_velocities;
Gary Servin 0:04ac6be8229a 29 _velocities_type * velocities;
Gary Servin 0:04ac6be8229a 30 typedef double _duration_type;
Gary Servin 0:04ac6be8229a 31 _duration_type duration;
Gary Servin 0:04ac6be8229a 32
Gary Servin 0:04ac6be8229a 33 JointJog():
Gary Servin 0:04ac6be8229a 34 header(),
Gary Servin 0:04ac6be8229a 35 joint_names_length(0), joint_names(NULL),
Gary Servin 0:04ac6be8229a 36 displacements_length(0), displacements(NULL),
Gary Servin 0:04ac6be8229a 37 velocities_length(0), velocities(NULL),
Gary Servin 0:04ac6be8229a 38 duration(0)
Gary Servin 0:04ac6be8229a 39 {
Gary Servin 0:04ac6be8229a 40 }
Gary Servin 0:04ac6be8229a 41
Gary Servin 0:04ac6be8229a 42 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 43 {
Gary Servin 0:04ac6be8229a 44 int offset = 0;
Gary Servin 0:04ac6be8229a 45 offset += this->header.serialize(outbuffer + offset);
Gary Servin 0:04ac6be8229a 46 *(outbuffer + offset + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 47 *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 48 *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 49 *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 50 offset += sizeof(this->joint_names_length);
Gary Servin 0:04ac6be8229a 51 for( uint32_t i = 0; i < joint_names_length; i++){
Gary Servin 0:04ac6be8229a 52 uint32_t length_joint_namesi = strlen(this->joint_names[i]);
Gary Servin 0:04ac6be8229a 53 varToArr(outbuffer + offset, length_joint_namesi);
Gary Servin 0:04ac6be8229a 54 offset += 4;
Gary Servin 0:04ac6be8229a 55 memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
Gary Servin 0:04ac6be8229a 56 offset += length_joint_namesi;
Gary Servin 0:04ac6be8229a 57 }
Gary Servin 0:04ac6be8229a 58 *(outbuffer + offset + 0) = (this->displacements_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 59 *(outbuffer + offset + 1) = (this->displacements_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 60 *(outbuffer + offset + 2) = (this->displacements_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 61 *(outbuffer + offset + 3) = (this->displacements_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 62 offset += sizeof(this->displacements_length);
Gary Servin 0:04ac6be8229a 63 for( uint32_t i = 0; i < displacements_length; i++){
Gary Servin 0:04ac6be8229a 64 union {
Gary Servin 0:04ac6be8229a 65 double real;
Gary Servin 0:04ac6be8229a 66 uint64_t base;
Gary Servin 0:04ac6be8229a 67 } u_displacementsi;
Gary Servin 0:04ac6be8229a 68 u_displacementsi.real = this->displacements[i];
Gary Servin 0:04ac6be8229a 69 *(outbuffer + offset + 0) = (u_displacementsi.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 70 *(outbuffer + offset + 1) = (u_displacementsi.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 71 *(outbuffer + offset + 2) = (u_displacementsi.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 72 *(outbuffer + offset + 3) = (u_displacementsi.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 73 *(outbuffer + offset + 4) = (u_displacementsi.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 74 *(outbuffer + offset + 5) = (u_displacementsi.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 75 *(outbuffer + offset + 6) = (u_displacementsi.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 76 *(outbuffer + offset + 7) = (u_displacementsi.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 77 offset += sizeof(this->displacements[i]);
Gary Servin 0:04ac6be8229a 78 }
Gary Servin 0:04ac6be8229a 79 *(outbuffer + offset + 0) = (this->velocities_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 80 *(outbuffer + offset + 1) = (this->velocities_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 81 *(outbuffer + offset + 2) = (this->velocities_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 82 *(outbuffer + offset + 3) = (this->velocities_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 83 offset += sizeof(this->velocities_length);
Gary Servin 0:04ac6be8229a 84 for( uint32_t i = 0; i < velocities_length; i++){
Gary Servin 0:04ac6be8229a 85 union {
Gary Servin 0:04ac6be8229a 86 double real;
Gary Servin 0:04ac6be8229a 87 uint64_t base;
Gary Servin 0:04ac6be8229a 88 } u_velocitiesi;
Gary Servin 0:04ac6be8229a 89 u_velocitiesi.real = this->velocities[i];
Gary Servin 0:04ac6be8229a 90 *(outbuffer + offset + 0) = (u_velocitiesi.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 91 *(outbuffer + offset + 1) = (u_velocitiesi.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 92 *(outbuffer + offset + 2) = (u_velocitiesi.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 93 *(outbuffer + offset + 3) = (u_velocitiesi.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 94 *(outbuffer + offset + 4) = (u_velocitiesi.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 95 *(outbuffer + offset + 5) = (u_velocitiesi.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 96 *(outbuffer + offset + 6) = (u_velocitiesi.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 97 *(outbuffer + offset + 7) = (u_velocitiesi.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 98 offset += sizeof(this->velocities[i]);
Gary Servin 0:04ac6be8229a 99 }
Gary Servin 0:04ac6be8229a 100 union {
Gary Servin 0:04ac6be8229a 101 double real;
Gary Servin 0:04ac6be8229a 102 uint64_t base;
Gary Servin 0:04ac6be8229a 103 } u_duration;
Gary Servin 0:04ac6be8229a 104 u_duration.real = this->duration;
Gary Servin 0:04ac6be8229a 105 *(outbuffer + offset + 0) = (u_duration.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 106 *(outbuffer + offset + 1) = (u_duration.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 107 *(outbuffer + offset + 2) = (u_duration.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 108 *(outbuffer + offset + 3) = (u_duration.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 109 *(outbuffer + offset + 4) = (u_duration.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 110 *(outbuffer + offset + 5) = (u_duration.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 111 *(outbuffer + offset + 6) = (u_duration.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 112 *(outbuffer + offset + 7) = (u_duration.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 113 offset += sizeof(this->duration);
Gary Servin 0:04ac6be8229a 114 return offset;
Gary Servin 0:04ac6be8229a 115 }
Gary Servin 0:04ac6be8229a 116
Gary Servin 0:04ac6be8229a 117 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 118 {
Gary Servin 0:04ac6be8229a 119 int offset = 0;
Gary Servin 0:04ac6be8229a 120 offset += this->header.deserialize(inbuffer + offset);
Gary Servin 0:04ac6be8229a 121 uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 122 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 123 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 124 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 125 offset += sizeof(this->joint_names_length);
Gary Servin 0:04ac6be8229a 126 if(joint_names_lengthT > joint_names_length)
Gary Servin 0:04ac6be8229a 127 this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
Gary Servin 0:04ac6be8229a 128 joint_names_length = joint_names_lengthT;
Gary Servin 0:04ac6be8229a 129 for( uint32_t i = 0; i < joint_names_length; i++){
Gary Servin 0:04ac6be8229a 130 uint32_t length_st_joint_names;
Gary Servin 0:04ac6be8229a 131 arrToVar(length_st_joint_names, (inbuffer + offset));
Gary Servin 0:04ac6be8229a 132 offset += 4;
Gary Servin 0:04ac6be8229a 133 for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
Gary Servin 0:04ac6be8229a 134 inbuffer[k-1]=inbuffer[k];
Gary Servin 0:04ac6be8229a 135 }
Gary Servin 0:04ac6be8229a 136 inbuffer[offset+length_st_joint_names-1]=0;
Gary Servin 0:04ac6be8229a 137 this->st_joint_names = (char *)(inbuffer + offset-1);
Gary Servin 0:04ac6be8229a 138 offset += length_st_joint_names;
Gary Servin 0:04ac6be8229a 139 memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
Gary Servin 0:04ac6be8229a 140 }
Gary Servin 0:04ac6be8229a 141 uint32_t displacements_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 142 displacements_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 143 displacements_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 144 displacements_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 145 offset += sizeof(this->displacements_length);
Gary Servin 0:04ac6be8229a 146 if(displacements_lengthT > displacements_length)
Gary Servin 0:04ac6be8229a 147 this->displacements = (double*)realloc(this->displacements, displacements_lengthT * sizeof(double));
Gary Servin 0:04ac6be8229a 148 displacements_length = displacements_lengthT;
Gary Servin 0:04ac6be8229a 149 for( uint32_t i = 0; i < displacements_length; i++){
Gary Servin 0:04ac6be8229a 150 union {
Gary Servin 0:04ac6be8229a 151 double real;
Gary Servin 0:04ac6be8229a 152 uint64_t base;
Gary Servin 0:04ac6be8229a 153 } u_st_displacements;
Gary Servin 0:04ac6be8229a 154 u_st_displacements.base = 0;
Gary Servin 0:04ac6be8229a 155 u_st_displacements.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 156 u_st_displacements.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 157 u_st_displacements.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 158 u_st_displacements.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 159 u_st_displacements.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 160 u_st_displacements.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 161 u_st_displacements.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 162 u_st_displacements.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 163 this->st_displacements = u_st_displacements.real;
Gary Servin 0:04ac6be8229a 164 offset += sizeof(this->st_displacements);
Gary Servin 0:04ac6be8229a 165 memcpy( &(this->displacements[i]), &(this->st_displacements), sizeof(double));
Gary Servin 0:04ac6be8229a 166 }
Gary Servin 0:04ac6be8229a 167 uint32_t velocities_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 168 velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 169 velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 170 velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 171 offset += sizeof(this->velocities_length);
Gary Servin 0:04ac6be8229a 172 if(velocities_lengthT > velocities_length)
Gary Servin 0:04ac6be8229a 173 this->velocities = (double*)realloc(this->velocities, velocities_lengthT * sizeof(double));
Gary Servin 0:04ac6be8229a 174 velocities_length = velocities_lengthT;
Gary Servin 0:04ac6be8229a 175 for( uint32_t i = 0; i < velocities_length; i++){
Gary Servin 0:04ac6be8229a 176 union {
Gary Servin 0:04ac6be8229a 177 double real;
Gary Servin 0:04ac6be8229a 178 uint64_t base;
Gary Servin 0:04ac6be8229a 179 } u_st_velocities;
Gary Servin 0:04ac6be8229a 180 u_st_velocities.base = 0;
Gary Servin 0:04ac6be8229a 181 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 182 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 183 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 184 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 185 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 186 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 187 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 188 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 189 this->st_velocities = u_st_velocities.real;
Gary Servin 0:04ac6be8229a 190 offset += sizeof(this->st_velocities);
Gary Servin 0:04ac6be8229a 191 memcpy( &(this->velocities[i]), &(this->st_velocities), sizeof(double));
Gary Servin 0:04ac6be8229a 192 }
Gary Servin 0:04ac6be8229a 193 union {
Gary Servin 0:04ac6be8229a 194 double real;
Gary Servin 0:04ac6be8229a 195 uint64_t base;
Gary Servin 0:04ac6be8229a 196 } u_duration;
Gary Servin 0:04ac6be8229a 197 u_duration.base = 0;
Gary Servin 0:04ac6be8229a 198 u_duration.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 199 u_duration.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 200 u_duration.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 201 u_duration.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 202 u_duration.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 203 u_duration.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 204 u_duration.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 205 u_duration.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 206 this->duration = u_duration.real;
Gary Servin 0:04ac6be8229a 207 offset += sizeof(this->duration);
Gary Servin 0:04ac6be8229a 208 return offset;
Gary Servin 0:04ac6be8229a 209 }
Gary Servin 0:04ac6be8229a 210
Gary Servin 0:04ac6be8229a 211 const char * getType(){ return "control_msgs/JointJog"; };
Gary Servin 0:04ac6be8229a 212 const char * getMD5(){ return "1685da700c8c2e1254afc92a5fb89c96"; };
Gary Servin 0:04ac6be8229a 213
Gary Servin 0:04ac6be8229a 214 };
Gary Servin 0:04ac6be8229a 215
Gary Servin 0:04ac6be8229a 216 }
Gary Servin 0:04ac6be8229a 217 #endif