added 1 custom message
Fork of ros_lib_kinetic by
gazebo_msgs/GetModelProperties.h@2:af816ffd33df, 2017-05-19 (annotated)
- Committer:
- randalthor
- Date:
- Fri May 19 08:59:12 2017 +0000
- Revision:
- 2:af816ffd33df
- Parent:
- 0:9e9b7db60fd5
custom message mobile robot added for ITU cyber physical lab
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:9e9b7db60fd5 | 1 | #ifndef _ROS_SERVICE_GetModelProperties_h |
garyservin | 0:9e9b7db60fd5 | 2 | #define _ROS_SERVICE_GetModelProperties_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 | |
garyservin | 0:9e9b7db60fd5 | 8 | namespace gazebo_msgs |
garyservin | 0:9e9b7db60fd5 | 9 | { |
garyservin | 0:9e9b7db60fd5 | 10 | |
garyservin | 0:9e9b7db60fd5 | 11 | static const char GETMODELPROPERTIES[] = "gazebo_msgs/GetModelProperties"; |
garyservin | 0:9e9b7db60fd5 | 12 | |
garyservin | 0:9e9b7db60fd5 | 13 | class GetModelPropertiesRequest : public ros::Msg |
garyservin | 0:9e9b7db60fd5 | 14 | { |
garyservin | 0:9e9b7db60fd5 | 15 | public: |
garyservin | 0:9e9b7db60fd5 | 16 | typedef const char* _model_name_type; |
garyservin | 0:9e9b7db60fd5 | 17 | _model_name_type model_name; |
garyservin | 0:9e9b7db60fd5 | 18 | |
garyservin | 0:9e9b7db60fd5 | 19 | GetModelPropertiesRequest(): |
garyservin | 0:9e9b7db60fd5 | 20 | model_name("") |
garyservin | 0:9e9b7db60fd5 | 21 | { |
garyservin | 0:9e9b7db60fd5 | 22 | } |
garyservin | 0:9e9b7db60fd5 | 23 | |
garyservin | 0:9e9b7db60fd5 | 24 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:9e9b7db60fd5 | 25 | { |
garyservin | 0:9e9b7db60fd5 | 26 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 27 | uint32_t length_model_name = strlen(this->model_name); |
garyservin | 0:9e9b7db60fd5 | 28 | varToArr(outbuffer + offset, length_model_name); |
garyservin | 0:9e9b7db60fd5 | 29 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 30 | memcpy(outbuffer + offset, this->model_name, length_model_name); |
garyservin | 0:9e9b7db60fd5 | 31 | offset += length_model_name; |
garyservin | 0:9e9b7db60fd5 | 32 | return offset; |
garyservin | 0:9e9b7db60fd5 | 33 | } |
garyservin | 0:9e9b7db60fd5 | 34 | |
garyservin | 0:9e9b7db60fd5 | 35 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:9e9b7db60fd5 | 36 | { |
garyservin | 0:9e9b7db60fd5 | 37 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 38 | uint32_t length_model_name; |
garyservin | 0:9e9b7db60fd5 | 39 | arrToVar(length_model_name, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 40 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 41 | for(unsigned int k= offset; k< offset+length_model_name; ++k){ |
garyservin | 0:9e9b7db60fd5 | 42 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 43 | } |
garyservin | 0:9e9b7db60fd5 | 44 | inbuffer[offset+length_model_name-1]=0; |
garyservin | 0:9e9b7db60fd5 | 45 | this->model_name = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 46 | offset += length_model_name; |
garyservin | 0:9e9b7db60fd5 | 47 | return offset; |
garyservin | 0:9e9b7db60fd5 | 48 | } |
garyservin | 0:9e9b7db60fd5 | 49 | |
garyservin | 0:9e9b7db60fd5 | 50 | const char * getType(){ return GETMODELPROPERTIES; }; |
garyservin | 0:9e9b7db60fd5 | 51 | const char * getMD5(){ return "ea31c8eab6fc401383cf528a7c0984ba"; }; |
garyservin | 0:9e9b7db60fd5 | 52 | |
garyservin | 0:9e9b7db60fd5 | 53 | }; |
garyservin | 0:9e9b7db60fd5 | 54 | |
garyservin | 0:9e9b7db60fd5 | 55 | class GetModelPropertiesResponse : public ros::Msg |
garyservin | 0:9e9b7db60fd5 | 56 | { |
garyservin | 0:9e9b7db60fd5 | 57 | public: |
garyservin | 0:9e9b7db60fd5 | 58 | typedef const char* _parent_model_name_type; |
garyservin | 0:9e9b7db60fd5 | 59 | _parent_model_name_type parent_model_name; |
garyservin | 0:9e9b7db60fd5 | 60 | typedef const char* _canonical_body_name_type; |
garyservin | 0:9e9b7db60fd5 | 61 | _canonical_body_name_type canonical_body_name; |
garyservin | 0:9e9b7db60fd5 | 62 | uint32_t body_names_length; |
garyservin | 0:9e9b7db60fd5 | 63 | typedef char* _body_names_type; |
garyservin | 0:9e9b7db60fd5 | 64 | _body_names_type st_body_names; |
garyservin | 0:9e9b7db60fd5 | 65 | _body_names_type * body_names; |
garyservin | 0:9e9b7db60fd5 | 66 | uint32_t geom_names_length; |
garyservin | 0:9e9b7db60fd5 | 67 | typedef char* _geom_names_type; |
garyservin | 0:9e9b7db60fd5 | 68 | _geom_names_type st_geom_names; |
garyservin | 0:9e9b7db60fd5 | 69 | _geom_names_type * geom_names; |
garyservin | 0:9e9b7db60fd5 | 70 | uint32_t joint_names_length; |
garyservin | 0:9e9b7db60fd5 | 71 | typedef char* _joint_names_type; |
garyservin | 0:9e9b7db60fd5 | 72 | _joint_names_type st_joint_names; |
garyservin | 0:9e9b7db60fd5 | 73 | _joint_names_type * joint_names; |
garyservin | 0:9e9b7db60fd5 | 74 | uint32_t child_model_names_length; |
garyservin | 0:9e9b7db60fd5 | 75 | typedef char* _child_model_names_type; |
garyservin | 0:9e9b7db60fd5 | 76 | _child_model_names_type st_child_model_names; |
garyservin | 0:9e9b7db60fd5 | 77 | _child_model_names_type * child_model_names; |
garyservin | 0:9e9b7db60fd5 | 78 | typedef bool _is_static_type; |
garyservin | 0:9e9b7db60fd5 | 79 | _is_static_type is_static; |
garyservin | 0:9e9b7db60fd5 | 80 | typedef bool _success_type; |
garyservin | 0:9e9b7db60fd5 | 81 | _success_type success; |
garyservin | 0:9e9b7db60fd5 | 82 | typedef const char* _status_message_type; |
garyservin | 0:9e9b7db60fd5 | 83 | _status_message_type status_message; |
garyservin | 0:9e9b7db60fd5 | 84 | |
garyservin | 0:9e9b7db60fd5 | 85 | GetModelPropertiesResponse(): |
garyservin | 0:9e9b7db60fd5 | 86 | parent_model_name(""), |
garyservin | 0:9e9b7db60fd5 | 87 | canonical_body_name(""), |
garyservin | 0:9e9b7db60fd5 | 88 | body_names_length(0), body_names(NULL), |
garyservin | 0:9e9b7db60fd5 | 89 | geom_names_length(0), geom_names(NULL), |
garyservin | 0:9e9b7db60fd5 | 90 | joint_names_length(0), joint_names(NULL), |
garyservin | 0:9e9b7db60fd5 | 91 | child_model_names_length(0), child_model_names(NULL), |
garyservin | 0:9e9b7db60fd5 | 92 | is_static(0), |
garyservin | 0:9e9b7db60fd5 | 93 | success(0), |
garyservin | 0:9e9b7db60fd5 | 94 | status_message("") |
garyservin | 0:9e9b7db60fd5 | 95 | { |
garyservin | 0:9e9b7db60fd5 | 96 | } |
garyservin | 0:9e9b7db60fd5 | 97 | |
garyservin | 0:9e9b7db60fd5 | 98 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:9e9b7db60fd5 | 99 | { |
garyservin | 0:9e9b7db60fd5 | 100 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 101 | uint32_t length_parent_model_name = strlen(this->parent_model_name); |
garyservin | 0:9e9b7db60fd5 | 102 | varToArr(outbuffer + offset, length_parent_model_name); |
garyservin | 0:9e9b7db60fd5 | 103 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 104 | memcpy(outbuffer + offset, this->parent_model_name, length_parent_model_name); |
garyservin | 0:9e9b7db60fd5 | 105 | offset += length_parent_model_name; |
garyservin | 0:9e9b7db60fd5 | 106 | uint32_t length_canonical_body_name = strlen(this->canonical_body_name); |
garyservin | 0:9e9b7db60fd5 | 107 | varToArr(outbuffer + offset, length_canonical_body_name); |
garyservin | 0:9e9b7db60fd5 | 108 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 109 | memcpy(outbuffer + offset, this->canonical_body_name, length_canonical_body_name); |
garyservin | 0:9e9b7db60fd5 | 110 | offset += length_canonical_body_name; |
garyservin | 0:9e9b7db60fd5 | 111 | *(outbuffer + offset + 0) = (this->body_names_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 112 | *(outbuffer + offset + 1) = (this->body_names_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 113 | *(outbuffer + offset + 2) = (this->body_names_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 114 | *(outbuffer + offset + 3) = (this->body_names_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 115 | offset += sizeof(this->body_names_length); |
garyservin | 0:9e9b7db60fd5 | 116 | for( uint32_t i = 0; i < body_names_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 117 | uint32_t length_body_namesi = strlen(this->body_names[i]); |
garyservin | 0:9e9b7db60fd5 | 118 | varToArr(outbuffer + offset, length_body_namesi); |
garyservin | 0:9e9b7db60fd5 | 119 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 120 | memcpy(outbuffer + offset, this->body_names[i], length_body_namesi); |
garyservin | 0:9e9b7db60fd5 | 121 | offset += length_body_namesi; |
garyservin | 0:9e9b7db60fd5 | 122 | } |
garyservin | 0:9e9b7db60fd5 | 123 | *(outbuffer + offset + 0) = (this->geom_names_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 124 | *(outbuffer + offset + 1) = (this->geom_names_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 125 | *(outbuffer + offset + 2) = (this->geom_names_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 126 | *(outbuffer + offset + 3) = (this->geom_names_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 127 | offset += sizeof(this->geom_names_length); |
garyservin | 0:9e9b7db60fd5 | 128 | for( uint32_t i = 0; i < geom_names_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 129 | uint32_t length_geom_namesi = strlen(this->geom_names[i]); |
garyservin | 0:9e9b7db60fd5 | 130 | varToArr(outbuffer + offset, length_geom_namesi); |
garyservin | 0:9e9b7db60fd5 | 131 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 132 | memcpy(outbuffer + offset, this->geom_names[i], length_geom_namesi); |
garyservin | 0:9e9b7db60fd5 | 133 | offset += length_geom_namesi; |
garyservin | 0:9e9b7db60fd5 | 134 | } |
garyservin | 0:9e9b7db60fd5 | 135 | *(outbuffer + offset + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 136 | *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 137 | *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 138 | *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 139 | offset += sizeof(this->joint_names_length); |
garyservin | 0:9e9b7db60fd5 | 140 | for( uint32_t i = 0; i < joint_names_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 141 | uint32_t length_joint_namesi = strlen(this->joint_names[i]); |
garyservin | 0:9e9b7db60fd5 | 142 | varToArr(outbuffer + offset, length_joint_namesi); |
garyservin | 0:9e9b7db60fd5 | 143 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 144 | memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi); |
garyservin | 0:9e9b7db60fd5 | 145 | offset += length_joint_namesi; |
garyservin | 0:9e9b7db60fd5 | 146 | } |
garyservin | 0:9e9b7db60fd5 | 147 | *(outbuffer + offset + 0) = (this->child_model_names_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 148 | *(outbuffer + offset + 1) = (this->child_model_names_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 149 | *(outbuffer + offset + 2) = (this->child_model_names_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 150 | *(outbuffer + offset + 3) = (this->child_model_names_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 151 | offset += sizeof(this->child_model_names_length); |
garyservin | 0:9e9b7db60fd5 | 152 | for( uint32_t i = 0; i < child_model_names_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 153 | uint32_t length_child_model_namesi = strlen(this->child_model_names[i]); |
garyservin | 0:9e9b7db60fd5 | 154 | varToArr(outbuffer + offset, length_child_model_namesi); |
garyservin | 0:9e9b7db60fd5 | 155 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 156 | memcpy(outbuffer + offset, this->child_model_names[i], length_child_model_namesi); |
garyservin | 0:9e9b7db60fd5 | 157 | offset += length_child_model_namesi; |
garyservin | 0:9e9b7db60fd5 | 158 | } |
garyservin | 0:9e9b7db60fd5 | 159 | union { |
garyservin | 0:9e9b7db60fd5 | 160 | bool real; |
garyservin | 0:9e9b7db60fd5 | 161 | uint8_t base; |
garyservin | 0:9e9b7db60fd5 | 162 | } u_is_static; |
garyservin | 0:9e9b7db60fd5 | 163 | u_is_static.real = this->is_static; |
garyservin | 0:9e9b7db60fd5 | 164 | *(outbuffer + offset + 0) = (u_is_static.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 165 | offset += sizeof(this->is_static); |
garyservin | 0:9e9b7db60fd5 | 166 | union { |
garyservin | 0:9e9b7db60fd5 | 167 | bool real; |
garyservin | 0:9e9b7db60fd5 | 168 | uint8_t base; |
garyservin | 0:9e9b7db60fd5 | 169 | } u_success; |
garyservin | 0:9e9b7db60fd5 | 170 | u_success.real = this->success; |
garyservin | 0:9e9b7db60fd5 | 171 | *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 172 | offset += sizeof(this->success); |
garyservin | 0:9e9b7db60fd5 | 173 | uint32_t length_status_message = strlen(this->status_message); |
garyservin | 0:9e9b7db60fd5 | 174 | varToArr(outbuffer + offset, length_status_message); |
garyservin | 0:9e9b7db60fd5 | 175 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 176 | memcpy(outbuffer + offset, this->status_message, length_status_message); |
garyservin | 0:9e9b7db60fd5 | 177 | offset += length_status_message; |
garyservin | 0:9e9b7db60fd5 | 178 | return offset; |
garyservin | 0:9e9b7db60fd5 | 179 | } |
garyservin | 0:9e9b7db60fd5 | 180 | |
garyservin | 0:9e9b7db60fd5 | 181 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:9e9b7db60fd5 | 182 | { |
garyservin | 0:9e9b7db60fd5 | 183 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 184 | uint32_t length_parent_model_name; |
garyservin | 0:9e9b7db60fd5 | 185 | arrToVar(length_parent_model_name, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 186 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 187 | for(unsigned int k= offset; k< offset+length_parent_model_name; ++k){ |
garyservin | 0:9e9b7db60fd5 | 188 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 189 | } |
garyservin | 0:9e9b7db60fd5 | 190 | inbuffer[offset+length_parent_model_name-1]=0; |
garyservin | 0:9e9b7db60fd5 | 191 | this->parent_model_name = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 192 | offset += length_parent_model_name; |
garyservin | 0:9e9b7db60fd5 | 193 | uint32_t length_canonical_body_name; |
garyservin | 0:9e9b7db60fd5 | 194 | arrToVar(length_canonical_body_name, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 195 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 196 | for(unsigned int k= offset; k< offset+length_canonical_body_name; ++k){ |
garyservin | 0:9e9b7db60fd5 | 197 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 198 | } |
garyservin | 0:9e9b7db60fd5 | 199 | inbuffer[offset+length_canonical_body_name-1]=0; |
garyservin | 0:9e9b7db60fd5 | 200 | this->canonical_body_name = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 201 | offset += length_canonical_body_name; |
garyservin | 0:9e9b7db60fd5 | 202 | uint32_t body_names_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 203 | body_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 204 | body_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 205 | body_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 206 | offset += sizeof(this->body_names_length); |
garyservin | 0:9e9b7db60fd5 | 207 | if(body_names_lengthT > body_names_length) |
garyservin | 0:9e9b7db60fd5 | 208 | this->body_names = (char**)realloc(this->body_names, body_names_lengthT * sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 209 | body_names_length = body_names_lengthT; |
garyservin | 0:9e9b7db60fd5 | 210 | for( uint32_t i = 0; i < body_names_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 211 | uint32_t length_st_body_names; |
garyservin | 0:9e9b7db60fd5 | 212 | arrToVar(length_st_body_names, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 213 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 214 | for(unsigned int k= offset; k< offset+length_st_body_names; ++k){ |
garyservin | 0:9e9b7db60fd5 | 215 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 216 | } |
garyservin | 0:9e9b7db60fd5 | 217 | inbuffer[offset+length_st_body_names-1]=0; |
garyservin | 0:9e9b7db60fd5 | 218 | this->st_body_names = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 219 | offset += length_st_body_names; |
garyservin | 0:9e9b7db60fd5 | 220 | memcpy( &(this->body_names[i]), &(this->st_body_names), sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 221 | } |
garyservin | 0:9e9b7db60fd5 | 222 | uint32_t geom_names_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 223 | geom_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 224 | geom_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 225 | geom_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 226 | offset += sizeof(this->geom_names_length); |
garyservin | 0:9e9b7db60fd5 | 227 | if(geom_names_lengthT > geom_names_length) |
garyservin | 0:9e9b7db60fd5 | 228 | this->geom_names = (char**)realloc(this->geom_names, geom_names_lengthT * sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 229 | geom_names_length = geom_names_lengthT; |
garyservin | 0:9e9b7db60fd5 | 230 | for( uint32_t i = 0; i < geom_names_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 231 | uint32_t length_st_geom_names; |
garyservin | 0:9e9b7db60fd5 | 232 | arrToVar(length_st_geom_names, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 233 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 234 | for(unsigned int k= offset; k< offset+length_st_geom_names; ++k){ |
garyservin | 0:9e9b7db60fd5 | 235 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 236 | } |
garyservin | 0:9e9b7db60fd5 | 237 | inbuffer[offset+length_st_geom_names-1]=0; |
garyservin | 0:9e9b7db60fd5 | 238 | this->st_geom_names = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 239 | offset += length_st_geom_names; |
garyservin | 0:9e9b7db60fd5 | 240 | memcpy( &(this->geom_names[i]), &(this->st_geom_names), sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 241 | } |
garyservin | 0:9e9b7db60fd5 | 242 | uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 243 | joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 244 | joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 245 | joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 246 | offset += sizeof(this->joint_names_length); |
garyservin | 0:9e9b7db60fd5 | 247 | if(joint_names_lengthT > joint_names_length) |
garyservin | 0:9e9b7db60fd5 | 248 | this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 249 | joint_names_length = joint_names_lengthT; |
garyservin | 0:9e9b7db60fd5 | 250 | for( uint32_t i = 0; i < joint_names_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 251 | uint32_t length_st_joint_names; |
garyservin | 0:9e9b7db60fd5 | 252 | arrToVar(length_st_joint_names, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 253 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 254 | for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){ |
garyservin | 0:9e9b7db60fd5 | 255 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 256 | } |
garyservin | 0:9e9b7db60fd5 | 257 | inbuffer[offset+length_st_joint_names-1]=0; |
garyservin | 0:9e9b7db60fd5 | 258 | this->st_joint_names = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 259 | offset += length_st_joint_names; |
garyservin | 0:9e9b7db60fd5 | 260 | memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 261 | } |
garyservin | 0:9e9b7db60fd5 | 262 | uint32_t child_model_names_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 263 | child_model_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 264 | child_model_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 265 | child_model_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 266 | offset += sizeof(this->child_model_names_length); |
garyservin | 0:9e9b7db60fd5 | 267 | if(child_model_names_lengthT > child_model_names_length) |
garyservin | 0:9e9b7db60fd5 | 268 | this->child_model_names = (char**)realloc(this->child_model_names, child_model_names_lengthT * sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 269 | child_model_names_length = child_model_names_lengthT; |
garyservin | 0:9e9b7db60fd5 | 270 | for( uint32_t i = 0; i < child_model_names_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 271 | uint32_t length_st_child_model_names; |
garyservin | 0:9e9b7db60fd5 | 272 | arrToVar(length_st_child_model_names, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 273 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 274 | for(unsigned int k= offset; k< offset+length_st_child_model_names; ++k){ |
garyservin | 0:9e9b7db60fd5 | 275 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 276 | } |
garyservin | 0:9e9b7db60fd5 | 277 | inbuffer[offset+length_st_child_model_names-1]=0; |
garyservin | 0:9e9b7db60fd5 | 278 | this->st_child_model_names = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 279 | offset += length_st_child_model_names; |
garyservin | 0:9e9b7db60fd5 | 280 | memcpy( &(this->child_model_names[i]), &(this->st_child_model_names), sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 281 | } |
garyservin | 0:9e9b7db60fd5 | 282 | union { |
garyservin | 0:9e9b7db60fd5 | 283 | bool real; |
garyservin | 0:9e9b7db60fd5 | 284 | uint8_t base; |
garyservin | 0:9e9b7db60fd5 | 285 | } u_is_static; |
garyservin | 0:9e9b7db60fd5 | 286 | u_is_static.base = 0; |
garyservin | 0:9e9b7db60fd5 | 287 | u_is_static.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 288 | this->is_static = u_is_static.real; |
garyservin | 0:9e9b7db60fd5 | 289 | offset += sizeof(this->is_static); |
garyservin | 0:9e9b7db60fd5 | 290 | union { |
garyservin | 0:9e9b7db60fd5 | 291 | bool real; |
garyservin | 0:9e9b7db60fd5 | 292 | uint8_t base; |
garyservin | 0:9e9b7db60fd5 | 293 | } u_success; |
garyservin | 0:9e9b7db60fd5 | 294 | u_success.base = 0; |
garyservin | 0:9e9b7db60fd5 | 295 | u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 296 | this->success = u_success.real; |
garyservin | 0:9e9b7db60fd5 | 297 | offset += sizeof(this->success); |
garyservin | 0:9e9b7db60fd5 | 298 | uint32_t length_status_message; |
garyservin | 0:9e9b7db60fd5 | 299 | arrToVar(length_status_message, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 300 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 301 | for(unsigned int k= offset; k< offset+length_status_message; ++k){ |
garyservin | 0:9e9b7db60fd5 | 302 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 303 | } |
garyservin | 0:9e9b7db60fd5 | 304 | inbuffer[offset+length_status_message-1]=0; |
garyservin | 0:9e9b7db60fd5 | 305 | this->status_message = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 306 | offset += length_status_message; |
garyservin | 0:9e9b7db60fd5 | 307 | return offset; |
garyservin | 0:9e9b7db60fd5 | 308 | } |
garyservin | 0:9e9b7db60fd5 | 309 | |
garyservin | 0:9e9b7db60fd5 | 310 | const char * getType(){ return GETMODELPROPERTIES; }; |
garyservin | 0:9e9b7db60fd5 | 311 | const char * getMD5(){ return "b7f370938ef77b464b95f1bab3ec5028"; }; |
garyservin | 0:9e9b7db60fd5 | 312 | |
garyservin | 0:9e9b7db60fd5 | 313 | }; |
garyservin | 0:9e9b7db60fd5 | 314 | |
garyservin | 0:9e9b7db60fd5 | 315 | class GetModelProperties { |
garyservin | 0:9e9b7db60fd5 | 316 | public: |
garyservin | 0:9e9b7db60fd5 | 317 | typedef GetModelPropertiesRequest Request; |
garyservin | 0:9e9b7db60fd5 | 318 | typedef GetModelPropertiesResponse Response; |
garyservin | 0:9e9b7db60fd5 | 319 | }; |
garyservin | 0:9e9b7db60fd5 | 320 | |
garyservin | 0:9e9b7db60fd5 | 321 | } |
garyservin | 0:9e9b7db60fd5 | 322 | #endif |