rosserial library for mbed Inspired by nucho's rosserial library This library is still under development
Dependents: mbed_roshydro_test
Library still under development!
control_msgs/QueryTrajectoryState.h@0:30537dec6e0b, 2015-02-15 (annotated)
- Committer:
- akashvibhute
- Date:
- Sun Feb 15 10:53:43 2015 +0000
- Revision:
- 0:30537dec6e0b
First commit; Library still need to be debugged, compilation issues with new mbed and modserial updates.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
akashvibhute | 0:30537dec6e0b | 1 | #ifndef _ROS_SERVICE_QueryTrajectoryState_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_SERVICE_QueryTrajectoryState_h |
akashvibhute | 0:30537dec6e0b | 3 | #include <stdint.h> |
akashvibhute | 0:30537dec6e0b | 4 | #include <string.h> |
akashvibhute | 0:30537dec6e0b | 5 | #include <stdlib.h> |
akashvibhute | 0:30537dec6e0b | 6 | #include "ros/msg.h" |
akashvibhute | 0:30537dec6e0b | 7 | #include "ros/time.h" |
akashvibhute | 0:30537dec6e0b | 8 | |
akashvibhute | 0:30537dec6e0b | 9 | namespace control_msgs |
akashvibhute | 0:30537dec6e0b | 10 | { |
akashvibhute | 0:30537dec6e0b | 11 | |
akashvibhute | 0:30537dec6e0b | 12 | static const char QUERYTRAJECTORYSTATE[] = "control_msgs/QueryTrajectoryState"; |
akashvibhute | 0:30537dec6e0b | 13 | |
akashvibhute | 0:30537dec6e0b | 14 | class QueryTrajectoryStateRequest : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 15 | { |
akashvibhute | 0:30537dec6e0b | 16 | public: |
akashvibhute | 0:30537dec6e0b | 17 | ros::Time time; |
akashvibhute | 0:30537dec6e0b | 18 | |
akashvibhute | 0:30537dec6e0b | 19 | QueryTrajectoryStateRequest(): |
akashvibhute | 0:30537dec6e0b | 20 | time() |
akashvibhute | 0:30537dec6e0b | 21 | { |
akashvibhute | 0:30537dec6e0b | 22 | } |
akashvibhute | 0:30537dec6e0b | 23 | |
akashvibhute | 0:30537dec6e0b | 24 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 25 | { |
akashvibhute | 0:30537dec6e0b | 26 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 27 | *(outbuffer + offset + 0) = (this->time.sec >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 28 | *(outbuffer + offset + 1) = (this->time.sec >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 29 | *(outbuffer + offset + 2) = (this->time.sec >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 30 | *(outbuffer + offset + 3) = (this->time.sec >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 31 | offset += sizeof(this->time.sec); |
akashvibhute | 0:30537dec6e0b | 32 | *(outbuffer + offset + 0) = (this->time.nsec >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 33 | *(outbuffer + offset + 1) = (this->time.nsec >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 34 | *(outbuffer + offset + 2) = (this->time.nsec >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 35 | *(outbuffer + offset + 3) = (this->time.nsec >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 36 | offset += sizeof(this->time.nsec); |
akashvibhute | 0:30537dec6e0b | 37 | return offset; |
akashvibhute | 0:30537dec6e0b | 38 | } |
akashvibhute | 0:30537dec6e0b | 39 | |
akashvibhute | 0:30537dec6e0b | 40 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 41 | { |
akashvibhute | 0:30537dec6e0b | 42 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 43 | this->time.sec = ((uint32_t) (*(inbuffer + offset))); |
akashvibhute | 0:30537dec6e0b | 44 | this->time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 45 | this->time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 46 | this->time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 47 | offset += sizeof(this->time.sec); |
akashvibhute | 0:30537dec6e0b | 48 | this->time.nsec = ((uint32_t) (*(inbuffer + offset))); |
akashvibhute | 0:30537dec6e0b | 49 | this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 50 | this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 51 | this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 52 | offset += sizeof(this->time.nsec); |
akashvibhute | 0:30537dec6e0b | 53 | return offset; |
akashvibhute | 0:30537dec6e0b | 54 | } |
akashvibhute | 0:30537dec6e0b | 55 | |
akashvibhute | 0:30537dec6e0b | 56 | const char * getType(){ return QUERYTRAJECTORYSTATE; }; |
akashvibhute | 0:30537dec6e0b | 57 | const char * getMD5(){ return "556a4fb76023a469987922359d08a844"; }; |
akashvibhute | 0:30537dec6e0b | 58 | |
akashvibhute | 0:30537dec6e0b | 59 | }; |
akashvibhute | 0:30537dec6e0b | 60 | |
akashvibhute | 0:30537dec6e0b | 61 | class QueryTrajectoryStateResponse : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 62 | { |
akashvibhute | 0:30537dec6e0b | 63 | public: |
akashvibhute | 0:30537dec6e0b | 64 | uint8_t name_length; |
akashvibhute | 0:30537dec6e0b | 65 | char* st_name; |
akashvibhute | 0:30537dec6e0b | 66 | char* * name; |
akashvibhute | 0:30537dec6e0b | 67 | uint8_t position_length; |
akashvibhute | 0:30537dec6e0b | 68 | float st_position; |
akashvibhute | 0:30537dec6e0b | 69 | float * position; |
akashvibhute | 0:30537dec6e0b | 70 | uint8_t velocity_length; |
akashvibhute | 0:30537dec6e0b | 71 | float st_velocity; |
akashvibhute | 0:30537dec6e0b | 72 | float * velocity; |
akashvibhute | 0:30537dec6e0b | 73 | uint8_t acceleration_length; |
akashvibhute | 0:30537dec6e0b | 74 | float st_acceleration; |
akashvibhute | 0:30537dec6e0b | 75 | float * acceleration; |
akashvibhute | 0:30537dec6e0b | 76 | |
akashvibhute | 0:30537dec6e0b | 77 | QueryTrajectoryStateResponse(): |
akashvibhute | 0:30537dec6e0b | 78 | name_length(0), name(NULL), |
akashvibhute | 0:30537dec6e0b | 79 | position_length(0), position(NULL), |
akashvibhute | 0:30537dec6e0b | 80 | velocity_length(0), velocity(NULL), |
akashvibhute | 0:30537dec6e0b | 81 | acceleration_length(0), acceleration(NULL) |
akashvibhute | 0:30537dec6e0b | 82 | { |
akashvibhute | 0:30537dec6e0b | 83 | } |
akashvibhute | 0:30537dec6e0b | 84 | |
akashvibhute | 0:30537dec6e0b | 85 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 86 | { |
akashvibhute | 0:30537dec6e0b | 87 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 88 | *(outbuffer + offset++) = name_length; |
akashvibhute | 0:30537dec6e0b | 89 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 90 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 91 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 92 | for( uint8_t i = 0; i < name_length; i++){ |
akashvibhute | 0:30537dec6e0b | 93 | uint32_t length_namei = strlen(this->name[i]); |
akashvibhute | 0:30537dec6e0b | 94 | memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 95 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 96 | memcpy(outbuffer + offset, this->name[i], length_namei); |
akashvibhute | 0:30537dec6e0b | 97 | offset += length_namei; |
akashvibhute | 0:30537dec6e0b | 98 | } |
akashvibhute | 0:30537dec6e0b | 99 | *(outbuffer + offset++) = position_length; |
akashvibhute | 0:30537dec6e0b | 100 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 101 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 102 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 103 | for( uint8_t i = 0; i < position_length; i++){ |
akashvibhute | 0:30537dec6e0b | 104 | offset += serializeAvrFloat64(outbuffer + offset, this->position[i]); |
akashvibhute | 0:30537dec6e0b | 105 | } |
akashvibhute | 0:30537dec6e0b | 106 | *(outbuffer + offset++) = velocity_length; |
akashvibhute | 0:30537dec6e0b | 107 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 108 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 109 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 110 | for( uint8_t i = 0; i < velocity_length; i++){ |
akashvibhute | 0:30537dec6e0b | 111 | offset += serializeAvrFloat64(outbuffer + offset, this->velocity[i]); |
akashvibhute | 0:30537dec6e0b | 112 | } |
akashvibhute | 0:30537dec6e0b | 113 | *(outbuffer + offset++) = acceleration_length; |
akashvibhute | 0:30537dec6e0b | 114 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 115 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 116 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 117 | for( uint8_t i = 0; i < acceleration_length; i++){ |
akashvibhute | 0:30537dec6e0b | 118 | offset += serializeAvrFloat64(outbuffer + offset, this->acceleration[i]); |
akashvibhute | 0:30537dec6e0b | 119 | } |
akashvibhute | 0:30537dec6e0b | 120 | return offset; |
akashvibhute | 0:30537dec6e0b | 121 | } |
akashvibhute | 0:30537dec6e0b | 122 | |
akashvibhute | 0:30537dec6e0b | 123 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 124 | { |
akashvibhute | 0:30537dec6e0b | 125 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 126 | uint8_t name_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 127 | if(name_lengthT > name_length) |
akashvibhute | 0:30537dec6e0b | 128 | this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); |
akashvibhute | 0:30537dec6e0b | 129 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 130 | name_length = name_lengthT; |
akashvibhute | 0:30537dec6e0b | 131 | for( uint8_t i = 0; i < name_length; i++){ |
akashvibhute | 0:30537dec6e0b | 132 | uint32_t length_st_name; |
akashvibhute | 0:30537dec6e0b | 133 | memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 134 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 135 | for(unsigned int k= offset; k< offset+length_st_name; ++k){ |
akashvibhute | 0:30537dec6e0b | 136 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 137 | } |
akashvibhute | 0:30537dec6e0b | 138 | inbuffer[offset+length_st_name-1]=0; |
akashvibhute | 0:30537dec6e0b | 139 | this->st_name = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 140 | offset += length_st_name; |
akashvibhute | 0:30537dec6e0b | 141 | memcpy( &(this->name[i]), &(this->st_name), sizeof(char*)); |
akashvibhute | 0:30537dec6e0b | 142 | } |
akashvibhute | 0:30537dec6e0b | 143 | uint8_t position_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 144 | if(position_lengthT > position_length) |
akashvibhute | 0:30537dec6e0b | 145 | this->position = (float*)realloc(this->position, position_lengthT * sizeof(float)); |
akashvibhute | 0:30537dec6e0b | 146 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 147 | position_length = position_lengthT; |
akashvibhute | 0:30537dec6e0b | 148 | for( uint8_t i = 0; i < position_length; i++){ |
akashvibhute | 0:30537dec6e0b | 149 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_position)); |
akashvibhute | 0:30537dec6e0b | 150 | memcpy( &(this->position[i]), &(this->st_position), sizeof(float)); |
akashvibhute | 0:30537dec6e0b | 151 | } |
akashvibhute | 0:30537dec6e0b | 152 | uint8_t velocity_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 153 | if(velocity_lengthT > velocity_length) |
akashvibhute | 0:30537dec6e0b | 154 | this->velocity = (float*)realloc(this->velocity, velocity_lengthT * sizeof(float)); |
akashvibhute | 0:30537dec6e0b | 155 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 156 | velocity_length = velocity_lengthT; |
akashvibhute | 0:30537dec6e0b | 157 | for( uint8_t i = 0; i < velocity_length; i++){ |
akashvibhute | 0:30537dec6e0b | 158 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_velocity)); |
akashvibhute | 0:30537dec6e0b | 159 | memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(float)); |
akashvibhute | 0:30537dec6e0b | 160 | } |
akashvibhute | 0:30537dec6e0b | 161 | uint8_t acceleration_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 162 | if(acceleration_lengthT > acceleration_length) |
akashvibhute | 0:30537dec6e0b | 163 | this->acceleration = (float*)realloc(this->acceleration, acceleration_lengthT * sizeof(float)); |
akashvibhute | 0:30537dec6e0b | 164 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 165 | acceleration_length = acceleration_lengthT; |
akashvibhute | 0:30537dec6e0b | 166 | for( uint8_t i = 0; i < acceleration_length; i++){ |
akashvibhute | 0:30537dec6e0b | 167 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_acceleration)); |
akashvibhute | 0:30537dec6e0b | 168 | memcpy( &(this->acceleration[i]), &(this->st_acceleration), sizeof(float)); |
akashvibhute | 0:30537dec6e0b | 169 | } |
akashvibhute | 0:30537dec6e0b | 170 | return offset; |
akashvibhute | 0:30537dec6e0b | 171 | } |
akashvibhute | 0:30537dec6e0b | 172 | |
akashvibhute | 0:30537dec6e0b | 173 | const char * getType(){ return QUERYTRAJECTORYSTATE; }; |
akashvibhute | 0:30537dec6e0b | 174 | const char * getMD5(){ return "1f1a6554ad060f44d013e71868403c1a"; }; |
akashvibhute | 0:30537dec6e0b | 175 | |
akashvibhute | 0:30537dec6e0b | 176 | }; |
akashvibhute | 0:30537dec6e0b | 177 | |
akashvibhute | 0:30537dec6e0b | 178 | class QueryTrajectoryState { |
akashvibhute | 0:30537dec6e0b | 179 | public: |
akashvibhute | 0:30537dec6e0b | 180 | typedef QueryTrajectoryStateRequest Request; |
akashvibhute | 0:30537dec6e0b | 181 | typedef QueryTrajectoryStateResponse Response; |
akashvibhute | 0:30537dec6e0b | 182 | }; |
akashvibhute | 0:30537dec6e0b | 183 | |
akashvibhute | 0:30537dec6e0b | 184 | } |
akashvibhute | 0:30537dec6e0b | 185 | #endif |
akashvibhute | 0:30537dec6e0b | 186 |