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
Fork of ros_lib_kinetic by
control_msgs/QueryTrajectoryState.h@2:9114cc24ddcf, 2017-10-17 (annotated)
- 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?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:9e9b7db60fd5 | 1 | #ifndef _ROS_SERVICE_QueryTrajectoryState_h |
garyservin | 0:9e9b7db60fd5 | 2 | #define _ROS_SERVICE_QueryTrajectoryState_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 "ros/time.h" |
garyservin | 0:9e9b7db60fd5 | 8 | |
garyservin | 0:9e9b7db60fd5 | 9 | namespace control_msgs |
garyservin | 0:9e9b7db60fd5 | 10 | { |
garyservin | 0:9e9b7db60fd5 | 11 | |
garyservin | 0:9e9b7db60fd5 | 12 | static const char QUERYTRAJECTORYSTATE[] = "control_msgs/QueryTrajectoryState"; |
garyservin | 0:9e9b7db60fd5 | 13 | |
garyservin | 0:9e9b7db60fd5 | 14 | class QueryTrajectoryStateRequest : public ros::Msg |
garyservin | 0:9e9b7db60fd5 | 15 | { |
garyservin | 0:9e9b7db60fd5 | 16 | public: |
garyservin | 0:9e9b7db60fd5 | 17 | typedef ros::Time _time_type; |
garyservin | 0:9e9b7db60fd5 | 18 | _time_type time; |
garyservin | 0:9e9b7db60fd5 | 19 | |
garyservin | 0:9e9b7db60fd5 | 20 | QueryTrajectoryStateRequest(): |
garyservin | 0:9e9b7db60fd5 | 21 | time() |
garyservin | 0:9e9b7db60fd5 | 22 | { |
garyservin | 0:9e9b7db60fd5 | 23 | } |
garyservin | 0:9e9b7db60fd5 | 24 | |
garyservin | 0:9e9b7db60fd5 | 25 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:9e9b7db60fd5 | 26 | { |
garyservin | 0:9e9b7db60fd5 | 27 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 28 | *(outbuffer + offset + 0) = (this->time.sec >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 29 | *(outbuffer + offset + 1) = (this->time.sec >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 30 | *(outbuffer + offset + 2) = (this->time.sec >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 31 | *(outbuffer + offset + 3) = (this->time.sec >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 32 | offset += sizeof(this->time.sec); |
garyservin | 0:9e9b7db60fd5 | 33 | *(outbuffer + offset + 0) = (this->time.nsec >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 34 | *(outbuffer + offset + 1) = (this->time.nsec >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 35 | *(outbuffer + offset + 2) = (this->time.nsec >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 36 | *(outbuffer + offset + 3) = (this->time.nsec >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 37 | offset += sizeof(this->time.nsec); |
garyservin | 0:9e9b7db60fd5 | 38 | return offset; |
garyservin | 0:9e9b7db60fd5 | 39 | } |
garyservin | 0:9e9b7db60fd5 | 40 | |
garyservin | 0:9e9b7db60fd5 | 41 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:9e9b7db60fd5 | 42 | { |
garyservin | 0:9e9b7db60fd5 | 43 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 44 | this->time.sec = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 45 | this->time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 46 | this->time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 47 | this->time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 48 | offset += sizeof(this->time.sec); |
garyservin | 0:9e9b7db60fd5 | 49 | this->time.nsec = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 50 | this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 51 | this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 52 | this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 53 | offset += sizeof(this->time.nsec); |
garyservin | 0:9e9b7db60fd5 | 54 | return offset; |
garyservin | 0:9e9b7db60fd5 | 55 | } |
garyservin | 0:9e9b7db60fd5 | 56 | |
garyservin | 0:9e9b7db60fd5 | 57 | const char * getType(){ return QUERYTRAJECTORYSTATE; }; |
garyservin | 0:9e9b7db60fd5 | 58 | const char * getMD5(){ return "556a4fb76023a469987922359d08a844"; }; |
garyservin | 0:9e9b7db60fd5 | 59 | |
garyservin | 0:9e9b7db60fd5 | 60 | }; |
garyservin | 0:9e9b7db60fd5 | 61 | |
garyservin | 0:9e9b7db60fd5 | 62 | class QueryTrajectoryStateResponse : public ros::Msg |
garyservin | 0:9e9b7db60fd5 | 63 | { |
garyservin | 0:9e9b7db60fd5 | 64 | public: |
garyservin | 0:9e9b7db60fd5 | 65 | uint32_t name_length; |
garyservin | 0:9e9b7db60fd5 | 66 | typedef char* _name_type; |
garyservin | 0:9e9b7db60fd5 | 67 | _name_type st_name; |
garyservin | 0:9e9b7db60fd5 | 68 | _name_type * name; |
garyservin | 0:9e9b7db60fd5 | 69 | uint32_t position_length; |
garyservin | 0:9e9b7db60fd5 | 70 | typedef double _position_type; |
garyservin | 0:9e9b7db60fd5 | 71 | _position_type st_position; |
garyservin | 0:9e9b7db60fd5 | 72 | _position_type * position; |
garyservin | 0:9e9b7db60fd5 | 73 | uint32_t velocity_length; |
garyservin | 0:9e9b7db60fd5 | 74 | typedef double _velocity_type; |
garyservin | 0:9e9b7db60fd5 | 75 | _velocity_type st_velocity; |
garyservin | 0:9e9b7db60fd5 | 76 | _velocity_type * velocity; |
garyservin | 0:9e9b7db60fd5 | 77 | uint32_t acceleration_length; |
garyservin | 0:9e9b7db60fd5 | 78 | typedef double _acceleration_type; |
garyservin | 0:9e9b7db60fd5 | 79 | _acceleration_type st_acceleration; |
garyservin | 0:9e9b7db60fd5 | 80 | _acceleration_type * acceleration; |
garyservin | 0:9e9b7db60fd5 | 81 | |
garyservin | 0:9e9b7db60fd5 | 82 | QueryTrajectoryStateResponse(): |
garyservin | 0:9e9b7db60fd5 | 83 | name_length(0), name(NULL), |
garyservin | 0:9e9b7db60fd5 | 84 | position_length(0), position(NULL), |
garyservin | 0:9e9b7db60fd5 | 85 | velocity_length(0), velocity(NULL), |
garyservin | 0:9e9b7db60fd5 | 86 | acceleration_length(0), acceleration(NULL) |
garyservin | 0:9e9b7db60fd5 | 87 | { |
garyservin | 0:9e9b7db60fd5 | 88 | } |
garyservin | 0:9e9b7db60fd5 | 89 | |
garyservin | 0:9e9b7db60fd5 | 90 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:9e9b7db60fd5 | 91 | { |
garyservin | 0:9e9b7db60fd5 | 92 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 93 | *(outbuffer + offset + 0) = (this->name_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 94 | *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 95 | *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 96 | *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 97 | offset += sizeof(this->name_length); |
garyservin | 0:9e9b7db60fd5 | 98 | for( uint32_t i = 0; i < name_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 99 | uint32_t length_namei = strlen(this->name[i]); |
garyservin | 0:9e9b7db60fd5 | 100 | varToArr(outbuffer + offset, length_namei); |
garyservin | 0:9e9b7db60fd5 | 101 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 102 | memcpy(outbuffer + offset, this->name[i], length_namei); |
garyservin | 0:9e9b7db60fd5 | 103 | offset += length_namei; |
garyservin | 0:9e9b7db60fd5 | 104 | } |
garyservin | 0:9e9b7db60fd5 | 105 | *(outbuffer + offset + 0) = (this->position_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 106 | *(outbuffer + offset + 1) = (this->position_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 107 | *(outbuffer + offset + 2) = (this->position_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 108 | *(outbuffer + offset + 3) = (this->position_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 109 | offset += sizeof(this->position_length); |
garyservin | 0:9e9b7db60fd5 | 110 | for( uint32_t i = 0; i < position_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 111 | union { |
garyservin | 0:9e9b7db60fd5 | 112 | double real; |
garyservin | 0:9e9b7db60fd5 | 113 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 114 | } u_positioni; |
garyservin | 0:9e9b7db60fd5 | 115 | u_positioni.real = this->position[i]; |
garyservin | 0:9e9b7db60fd5 | 116 | *(outbuffer + offset + 0) = (u_positioni.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 117 | *(outbuffer + offset + 1) = (u_positioni.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 118 | *(outbuffer + offset + 2) = (u_positioni.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 119 | *(outbuffer + offset + 3) = (u_positioni.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 120 | *(outbuffer + offset + 4) = (u_positioni.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 121 | *(outbuffer + offset + 5) = (u_positioni.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 122 | *(outbuffer + offset + 6) = (u_positioni.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 123 | *(outbuffer + offset + 7) = (u_positioni.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 124 | offset += sizeof(this->position[i]); |
garyservin | 0:9e9b7db60fd5 | 125 | } |
garyservin | 0:9e9b7db60fd5 | 126 | *(outbuffer + offset + 0) = (this->velocity_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 127 | *(outbuffer + offset + 1) = (this->velocity_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 128 | *(outbuffer + offset + 2) = (this->velocity_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 129 | *(outbuffer + offset + 3) = (this->velocity_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 130 | offset += sizeof(this->velocity_length); |
garyservin | 0:9e9b7db60fd5 | 131 | for( uint32_t i = 0; i < velocity_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 132 | union { |
garyservin | 0:9e9b7db60fd5 | 133 | double real; |
garyservin | 0:9e9b7db60fd5 | 134 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 135 | } u_velocityi; |
garyservin | 0:9e9b7db60fd5 | 136 | u_velocityi.real = this->velocity[i]; |
garyservin | 0:9e9b7db60fd5 | 137 | *(outbuffer + offset + 0) = (u_velocityi.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 138 | *(outbuffer + offset + 1) = (u_velocityi.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 139 | *(outbuffer + offset + 2) = (u_velocityi.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 140 | *(outbuffer + offset + 3) = (u_velocityi.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 141 | *(outbuffer + offset + 4) = (u_velocityi.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 142 | *(outbuffer + offset + 5) = (u_velocityi.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 143 | *(outbuffer + offset + 6) = (u_velocityi.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 144 | *(outbuffer + offset + 7) = (u_velocityi.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 145 | offset += sizeof(this->velocity[i]); |
garyservin | 0:9e9b7db60fd5 | 146 | } |
garyservin | 0:9e9b7db60fd5 | 147 | *(outbuffer + offset + 0) = (this->acceleration_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 148 | *(outbuffer + offset + 1) = (this->acceleration_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 149 | *(outbuffer + offset + 2) = (this->acceleration_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 150 | *(outbuffer + offset + 3) = (this->acceleration_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 151 | offset += sizeof(this->acceleration_length); |
garyservin | 0:9e9b7db60fd5 | 152 | for( uint32_t i = 0; i < acceleration_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 153 | union { |
garyservin | 0:9e9b7db60fd5 | 154 | double real; |
garyservin | 0:9e9b7db60fd5 | 155 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 156 | } u_accelerationi; |
garyservin | 0:9e9b7db60fd5 | 157 | u_accelerationi.real = this->acceleration[i]; |
garyservin | 0:9e9b7db60fd5 | 158 | *(outbuffer + offset + 0) = (u_accelerationi.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 159 | *(outbuffer + offset + 1) = (u_accelerationi.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 160 | *(outbuffer + offset + 2) = (u_accelerationi.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 161 | *(outbuffer + offset + 3) = (u_accelerationi.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 162 | *(outbuffer + offset + 4) = (u_accelerationi.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 163 | *(outbuffer + offset + 5) = (u_accelerationi.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 164 | *(outbuffer + offset + 6) = (u_accelerationi.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 165 | *(outbuffer + offset + 7) = (u_accelerationi.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 166 | offset += sizeof(this->acceleration[i]); |
garyservin | 0:9e9b7db60fd5 | 167 | } |
garyservin | 0:9e9b7db60fd5 | 168 | return offset; |
garyservin | 0:9e9b7db60fd5 | 169 | } |
garyservin | 0:9e9b7db60fd5 | 170 | |
garyservin | 0:9e9b7db60fd5 | 171 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:9e9b7db60fd5 | 172 | { |
garyservin | 0:9e9b7db60fd5 | 173 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 174 | uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 175 | name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 176 | name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 177 | name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 178 | offset += sizeof(this->name_length); |
garyservin | 0:9e9b7db60fd5 | 179 | if(name_lengthT > name_length) |
garyservin | 0:9e9b7db60fd5 | 180 | this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 181 | name_length = name_lengthT; |
garyservin | 0:9e9b7db60fd5 | 182 | for( uint32_t i = 0; i < name_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 183 | uint32_t length_st_name; |
garyservin | 0:9e9b7db60fd5 | 184 | arrToVar(length_st_name, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 185 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 186 | for(unsigned int k= offset; k< offset+length_st_name; ++k){ |
garyservin | 0:9e9b7db60fd5 | 187 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 188 | } |
garyservin | 0:9e9b7db60fd5 | 189 | inbuffer[offset+length_st_name-1]=0; |
garyservin | 0:9e9b7db60fd5 | 190 | this->st_name = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 191 | offset += length_st_name; |
garyservin | 0:9e9b7db60fd5 | 192 | memcpy( &(this->name[i]), &(this->st_name), sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 193 | } |
garyservin | 0:9e9b7db60fd5 | 194 | uint32_t position_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 195 | position_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 196 | position_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 197 | position_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 198 | offset += sizeof(this->position_length); |
garyservin | 0:9e9b7db60fd5 | 199 | if(position_lengthT > position_length) |
garyservin | 0:9e9b7db60fd5 | 200 | this->position = (double*)realloc(this->position, position_lengthT * sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 201 | position_length = position_lengthT; |
garyservin | 0:9e9b7db60fd5 | 202 | for( uint32_t i = 0; i < position_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 203 | union { |
garyservin | 0:9e9b7db60fd5 | 204 | double real; |
garyservin | 0:9e9b7db60fd5 | 205 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 206 | } u_st_position; |
garyservin | 0:9e9b7db60fd5 | 207 | u_st_position.base = 0; |
garyservin | 0:9e9b7db60fd5 | 208 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 209 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 210 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 211 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 212 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 213 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 214 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 215 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 216 | this->st_position = u_st_position.real; |
garyservin | 0:9e9b7db60fd5 | 217 | offset += sizeof(this->st_position); |
garyservin | 0:9e9b7db60fd5 | 218 | memcpy( &(this->position[i]), &(this->st_position), sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 219 | } |
garyservin | 0:9e9b7db60fd5 | 220 | uint32_t velocity_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 221 | velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 222 | velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 223 | velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 224 | offset += sizeof(this->velocity_length); |
garyservin | 0:9e9b7db60fd5 | 225 | if(velocity_lengthT > velocity_length) |
garyservin | 0:9e9b7db60fd5 | 226 | this->velocity = (double*)realloc(this->velocity, velocity_lengthT * sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 227 | velocity_length = velocity_lengthT; |
garyservin | 0:9e9b7db60fd5 | 228 | for( uint32_t i = 0; i < velocity_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 229 | union { |
garyservin | 0:9e9b7db60fd5 | 230 | double real; |
garyservin | 0:9e9b7db60fd5 | 231 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 232 | } u_st_velocity; |
garyservin | 0:9e9b7db60fd5 | 233 | u_st_velocity.base = 0; |
garyservin | 0:9e9b7db60fd5 | 234 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 235 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 236 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 237 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 238 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 239 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 240 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 241 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 242 | this->st_velocity = u_st_velocity.real; |
garyservin | 0:9e9b7db60fd5 | 243 | offset += sizeof(this->st_velocity); |
garyservin | 0:9e9b7db60fd5 | 244 | memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 245 | } |
garyservin | 0:9e9b7db60fd5 | 246 | uint32_t acceleration_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 247 | acceleration_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 248 | acceleration_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 249 | acceleration_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 250 | offset += sizeof(this->acceleration_length); |
garyservin | 0:9e9b7db60fd5 | 251 | if(acceleration_lengthT > acceleration_length) |
garyservin | 0:9e9b7db60fd5 | 252 | this->acceleration = (double*)realloc(this->acceleration, acceleration_lengthT * sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 253 | acceleration_length = acceleration_lengthT; |
garyservin | 0:9e9b7db60fd5 | 254 | for( uint32_t i = 0; i < acceleration_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 255 | union { |
garyservin | 0:9e9b7db60fd5 | 256 | double real; |
garyservin | 0:9e9b7db60fd5 | 257 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 258 | } u_st_acceleration; |
garyservin | 0:9e9b7db60fd5 | 259 | u_st_acceleration.base = 0; |
garyservin | 0:9e9b7db60fd5 | 260 | u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 261 | u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 262 | u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 263 | u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 264 | u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 265 | u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 266 | u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 267 | u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 268 | this->st_acceleration = u_st_acceleration.real; |
garyservin | 0:9e9b7db60fd5 | 269 | offset += sizeof(this->st_acceleration); |
garyservin | 0:9e9b7db60fd5 | 270 | memcpy( &(this->acceleration[i]), &(this->st_acceleration), sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 271 | } |
garyservin | 0:9e9b7db60fd5 | 272 | return offset; |
garyservin | 0:9e9b7db60fd5 | 273 | } |
garyservin | 0:9e9b7db60fd5 | 274 | |
garyservin | 0:9e9b7db60fd5 | 275 | const char * getType(){ return QUERYTRAJECTORYSTATE; }; |
garyservin | 0:9e9b7db60fd5 | 276 | const char * getMD5(){ return "1f1a6554ad060f44d013e71868403c1a"; }; |
garyservin | 0:9e9b7db60fd5 | 277 | |
garyservin | 0:9e9b7db60fd5 | 278 | }; |
garyservin | 0:9e9b7db60fd5 | 279 | |
garyservin | 0:9e9b7db60fd5 | 280 | class QueryTrajectoryState { |
garyservin | 0:9e9b7db60fd5 | 281 | public: |
garyservin | 0:9e9b7db60fd5 | 282 | typedef QueryTrajectoryStateRequest Request; |
garyservin | 0:9e9b7db60fd5 | 283 | typedef QueryTrajectoryStateResponse Response; |
garyservin | 0:9e9b7db60fd5 | 284 | }; |
garyservin | 0:9e9b7db60fd5 | 285 | |
garyservin | 0:9e9b7db60fd5 | 286 | } |
garyservin | 0:9e9b7db60fd5 | 287 | #endif |