modify for Hydro version
Fork of rosserial_mbed_lib by
sensor_msgs/JointState.h@6:3c54bc7badd4, 2013-10-26 (annotated)
- Committer:
- jjzak
- Date:
- Sat Oct 26 15:39:01 2013 +0000
- Revision:
- 6:3c54bc7badd4
modify for Hydro version;
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
jjzak | 6:3c54bc7badd4 | 1 | #ifndef _ROS_sensor_msgs_JointState_h |
jjzak | 6:3c54bc7badd4 | 2 | #define _ROS_sensor_msgs_JointState_h |
jjzak | 6:3c54bc7badd4 | 3 | |
jjzak | 6:3c54bc7badd4 | 4 | #include <stdint.h> |
jjzak | 6:3c54bc7badd4 | 5 | #include <string.h> |
jjzak | 6:3c54bc7badd4 | 6 | #include <stdlib.h> |
jjzak | 6:3c54bc7badd4 | 7 | #include "ros/msg.h" |
jjzak | 6:3c54bc7badd4 | 8 | #include "std_msgs/Header.h" |
jjzak | 6:3c54bc7badd4 | 9 | |
jjzak | 6:3c54bc7badd4 | 10 | namespace sensor_msgs |
jjzak | 6:3c54bc7badd4 | 11 | { |
jjzak | 6:3c54bc7badd4 | 12 | |
jjzak | 6:3c54bc7badd4 | 13 | class JointState : public ros::Msg |
jjzak | 6:3c54bc7badd4 | 14 | { |
jjzak | 6:3c54bc7badd4 | 15 | public: |
jjzak | 6:3c54bc7badd4 | 16 | std_msgs::Header header; |
jjzak | 6:3c54bc7badd4 | 17 | uint8_t name_length; |
jjzak | 6:3c54bc7badd4 | 18 | char* st_name; |
jjzak | 6:3c54bc7badd4 | 19 | char* * name; |
jjzak | 6:3c54bc7badd4 | 20 | uint8_t position_length; |
jjzak | 6:3c54bc7badd4 | 21 | float st_position; |
jjzak | 6:3c54bc7badd4 | 22 | float * position; |
jjzak | 6:3c54bc7badd4 | 23 | uint8_t velocity_length; |
jjzak | 6:3c54bc7badd4 | 24 | float st_velocity; |
jjzak | 6:3c54bc7badd4 | 25 | float * velocity; |
jjzak | 6:3c54bc7badd4 | 26 | uint8_t effort_length; |
jjzak | 6:3c54bc7badd4 | 27 | float st_effort; |
jjzak | 6:3c54bc7badd4 | 28 | float * effort; |
jjzak | 6:3c54bc7badd4 | 29 | |
jjzak | 6:3c54bc7badd4 | 30 | virtual int serialize(unsigned char *outbuffer) const |
jjzak | 6:3c54bc7badd4 | 31 | { |
jjzak | 6:3c54bc7badd4 | 32 | int offset = 0; |
jjzak | 6:3c54bc7badd4 | 33 | offset += this->header.serialize(outbuffer + offset); |
jjzak | 6:3c54bc7badd4 | 34 | *(outbuffer + offset++) = name_length; |
jjzak | 6:3c54bc7badd4 | 35 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 36 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 37 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 38 | for( uint8_t i = 0; i < name_length; i++){ |
jjzak | 6:3c54bc7badd4 | 39 | uint32_t length_namei = strlen( (const char*) this->name[i]); |
jjzak | 6:3c54bc7badd4 | 40 | memcpy(outbuffer + offset, &length_namei, sizeof(uint32_t)); |
jjzak | 6:3c54bc7badd4 | 41 | offset += 4; |
jjzak | 6:3c54bc7badd4 | 42 | memcpy(outbuffer + offset, this->name[i], length_namei); |
jjzak | 6:3c54bc7badd4 | 43 | offset += length_namei; |
jjzak | 6:3c54bc7badd4 | 44 | } |
jjzak | 6:3c54bc7badd4 | 45 | *(outbuffer + offset++) = position_length; |
jjzak | 6:3c54bc7badd4 | 46 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 47 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 48 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 49 | for( uint8_t i = 0; i < position_length; i++){ |
jjzak | 6:3c54bc7badd4 | 50 | int32_t * val_positioni = (int32_t *) &(this->position[i]); |
jjzak | 6:3c54bc7badd4 | 51 | int32_t exp_positioni = (((*val_positioni)>>23)&255); |
jjzak | 6:3c54bc7badd4 | 52 | if(exp_positioni != 0) |
jjzak | 6:3c54bc7badd4 | 53 | exp_positioni += 1023-127; |
jjzak | 6:3c54bc7badd4 | 54 | int32_t sig_positioni = *val_positioni; |
jjzak | 6:3c54bc7badd4 | 55 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 56 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 57 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 58 | *(outbuffer + offset++) = (sig_positioni<<5) & 0xff; |
jjzak | 6:3c54bc7badd4 | 59 | *(outbuffer + offset++) = (sig_positioni>>3) & 0xff; |
jjzak | 6:3c54bc7badd4 | 60 | *(outbuffer + offset++) = (sig_positioni>>11) & 0xff; |
jjzak | 6:3c54bc7badd4 | 61 | *(outbuffer + offset++) = ((exp_positioni<<4) & 0xF0) | ((sig_positioni>>19)&0x0F); |
jjzak | 6:3c54bc7badd4 | 62 | *(outbuffer + offset++) = (exp_positioni>>4) & 0x7F; |
jjzak | 6:3c54bc7badd4 | 63 | if(this->position[i] < 0) *(outbuffer + offset -1) |= 0x80; |
jjzak | 6:3c54bc7badd4 | 64 | } |
jjzak | 6:3c54bc7badd4 | 65 | *(outbuffer + offset++) = velocity_length; |
jjzak | 6:3c54bc7badd4 | 66 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 67 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 68 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 69 | for( uint8_t i = 0; i < velocity_length; i++){ |
jjzak | 6:3c54bc7badd4 | 70 | int32_t * val_velocityi = (int32_t *) &(this->velocity[i]); |
jjzak | 6:3c54bc7badd4 | 71 | int32_t exp_velocityi = (((*val_velocityi)>>23)&255); |
jjzak | 6:3c54bc7badd4 | 72 | if(exp_velocityi != 0) |
jjzak | 6:3c54bc7badd4 | 73 | exp_velocityi += 1023-127; |
jjzak | 6:3c54bc7badd4 | 74 | int32_t sig_velocityi = *val_velocityi; |
jjzak | 6:3c54bc7badd4 | 75 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 76 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 77 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 78 | *(outbuffer + offset++) = (sig_velocityi<<5) & 0xff; |
jjzak | 6:3c54bc7badd4 | 79 | *(outbuffer + offset++) = (sig_velocityi>>3) & 0xff; |
jjzak | 6:3c54bc7badd4 | 80 | *(outbuffer + offset++) = (sig_velocityi>>11) & 0xff; |
jjzak | 6:3c54bc7badd4 | 81 | *(outbuffer + offset++) = ((exp_velocityi<<4) & 0xF0) | ((sig_velocityi>>19)&0x0F); |
jjzak | 6:3c54bc7badd4 | 82 | *(outbuffer + offset++) = (exp_velocityi>>4) & 0x7F; |
jjzak | 6:3c54bc7badd4 | 83 | if(this->velocity[i] < 0) *(outbuffer + offset -1) |= 0x80; |
jjzak | 6:3c54bc7badd4 | 84 | } |
jjzak | 6:3c54bc7badd4 | 85 | *(outbuffer + offset++) = effort_length; |
jjzak | 6:3c54bc7badd4 | 86 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 87 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 88 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 89 | for( uint8_t i = 0; i < effort_length; i++){ |
jjzak | 6:3c54bc7badd4 | 90 | int32_t * val_efforti = (int32_t *) &(this->effort[i]); |
jjzak | 6:3c54bc7badd4 | 91 | int32_t exp_efforti = (((*val_efforti)>>23)&255); |
jjzak | 6:3c54bc7badd4 | 92 | if(exp_efforti != 0) |
jjzak | 6:3c54bc7badd4 | 93 | exp_efforti += 1023-127; |
jjzak | 6:3c54bc7badd4 | 94 | int32_t sig_efforti = *val_efforti; |
jjzak | 6:3c54bc7badd4 | 95 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 96 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 97 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 98 | *(outbuffer + offset++) = (sig_efforti<<5) & 0xff; |
jjzak | 6:3c54bc7badd4 | 99 | *(outbuffer + offset++) = (sig_efforti>>3) & 0xff; |
jjzak | 6:3c54bc7badd4 | 100 | *(outbuffer + offset++) = (sig_efforti>>11) & 0xff; |
jjzak | 6:3c54bc7badd4 | 101 | *(outbuffer + offset++) = ((exp_efforti<<4) & 0xF0) | ((sig_efforti>>19)&0x0F); |
jjzak | 6:3c54bc7badd4 | 102 | *(outbuffer + offset++) = (exp_efforti>>4) & 0x7F; |
jjzak | 6:3c54bc7badd4 | 103 | if(this->effort[i] < 0) *(outbuffer + offset -1) |= 0x80; |
jjzak | 6:3c54bc7badd4 | 104 | } |
jjzak | 6:3c54bc7badd4 | 105 | return offset; |
jjzak | 6:3c54bc7badd4 | 106 | } |
jjzak | 6:3c54bc7badd4 | 107 | |
jjzak | 6:3c54bc7badd4 | 108 | virtual int deserialize(unsigned char *inbuffer) |
jjzak | 6:3c54bc7badd4 | 109 | { |
jjzak | 6:3c54bc7badd4 | 110 | int offset = 0; |
jjzak | 6:3c54bc7badd4 | 111 | offset += this->header.deserialize(inbuffer + offset); |
jjzak | 6:3c54bc7badd4 | 112 | uint8_t name_lengthT = *(inbuffer + offset++); |
jjzak | 6:3c54bc7badd4 | 113 | if(name_lengthT > name_length) |
jjzak | 6:3c54bc7badd4 | 114 | this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); |
jjzak | 6:3c54bc7badd4 | 115 | offset += 3; |
jjzak | 6:3c54bc7badd4 | 116 | name_length = name_lengthT; |
jjzak | 6:3c54bc7badd4 | 117 | for( uint8_t i = 0; i < name_length; i++){ |
jjzak | 6:3c54bc7badd4 | 118 | uint32_t length_st_name; |
jjzak | 6:3c54bc7badd4 | 119 | memcpy(&length_st_name, (inbuffer + offset), sizeof(uint32_t)); |
jjzak | 6:3c54bc7badd4 | 120 | offset += 4; |
jjzak | 6:3c54bc7badd4 | 121 | for(unsigned int k= offset; k< offset+length_st_name; ++k){ |
jjzak | 6:3c54bc7badd4 | 122 | inbuffer[k-1]=inbuffer[k]; |
jjzak | 6:3c54bc7badd4 | 123 | } |
jjzak | 6:3c54bc7badd4 | 124 | inbuffer[offset+length_st_name-1]=0; |
jjzak | 6:3c54bc7badd4 | 125 | this->st_name = (char *)(inbuffer + offset-1); |
jjzak | 6:3c54bc7badd4 | 126 | offset += length_st_name; |
jjzak | 6:3c54bc7badd4 | 127 | memcpy( &(this->name[i]), &(this->st_name), sizeof(char*)); |
jjzak | 6:3c54bc7badd4 | 128 | } |
jjzak | 6:3c54bc7badd4 | 129 | uint8_t position_lengthT = *(inbuffer + offset++); |
jjzak | 6:3c54bc7badd4 | 130 | if(position_lengthT > position_length) |
jjzak | 6:3c54bc7badd4 | 131 | this->position = (float*)realloc(this->position, position_lengthT * sizeof(float)); |
jjzak | 6:3c54bc7badd4 | 132 | offset += 3; |
jjzak | 6:3c54bc7badd4 | 133 | position_length = position_lengthT; |
jjzak | 6:3c54bc7badd4 | 134 | for( uint8_t i = 0; i < position_length; i++){ |
jjzak | 6:3c54bc7badd4 | 135 | uint32_t * val_st_position = (uint32_t*) &(this->st_position); |
jjzak | 6:3c54bc7badd4 | 136 | offset += 3; |
jjzak | 6:3c54bc7badd4 | 137 | *val_st_position = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); |
jjzak | 6:3c54bc7badd4 | 138 | *val_st_position |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; |
jjzak | 6:3c54bc7badd4 | 139 | *val_st_position |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; |
jjzak | 6:3c54bc7badd4 | 140 | *val_st_position |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; |
jjzak | 6:3c54bc7badd4 | 141 | uint32_t exp_st_position = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; |
jjzak | 6:3c54bc7badd4 | 142 | exp_st_position |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; |
jjzak | 6:3c54bc7badd4 | 143 | if(exp_st_position !=0) |
jjzak | 6:3c54bc7badd4 | 144 | *val_st_position |= ((exp_st_position)-1023+127)<<23; |
jjzak | 6:3c54bc7badd4 | 145 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_position = -this->st_position; |
jjzak | 6:3c54bc7badd4 | 146 | memcpy( &(this->position[i]), &(this->st_position), sizeof(float)); |
jjzak | 6:3c54bc7badd4 | 147 | } |
jjzak | 6:3c54bc7badd4 | 148 | uint8_t velocity_lengthT = *(inbuffer + offset++); |
jjzak | 6:3c54bc7badd4 | 149 | if(velocity_lengthT > velocity_length) |
jjzak | 6:3c54bc7badd4 | 150 | this->velocity = (float*)realloc(this->velocity, velocity_lengthT * sizeof(float)); |
jjzak | 6:3c54bc7badd4 | 151 | offset += 3; |
jjzak | 6:3c54bc7badd4 | 152 | velocity_length = velocity_lengthT; |
jjzak | 6:3c54bc7badd4 | 153 | for( uint8_t i = 0; i < velocity_length; i++){ |
jjzak | 6:3c54bc7badd4 | 154 | uint32_t * val_st_velocity = (uint32_t*) &(this->st_velocity); |
jjzak | 6:3c54bc7badd4 | 155 | offset += 3; |
jjzak | 6:3c54bc7badd4 | 156 | *val_st_velocity = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); |
jjzak | 6:3c54bc7badd4 | 157 | *val_st_velocity |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; |
jjzak | 6:3c54bc7badd4 | 158 | *val_st_velocity |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; |
jjzak | 6:3c54bc7badd4 | 159 | *val_st_velocity |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; |
jjzak | 6:3c54bc7badd4 | 160 | uint32_t exp_st_velocity = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; |
jjzak | 6:3c54bc7badd4 | 161 | exp_st_velocity |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; |
jjzak | 6:3c54bc7badd4 | 162 | if(exp_st_velocity !=0) |
jjzak | 6:3c54bc7badd4 | 163 | *val_st_velocity |= ((exp_st_velocity)-1023+127)<<23; |
jjzak | 6:3c54bc7badd4 | 164 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_velocity = -this->st_velocity; |
jjzak | 6:3c54bc7badd4 | 165 | memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(float)); |
jjzak | 6:3c54bc7badd4 | 166 | } |
jjzak | 6:3c54bc7badd4 | 167 | uint8_t effort_lengthT = *(inbuffer + offset++); |
jjzak | 6:3c54bc7badd4 | 168 | if(effort_lengthT > effort_length) |
jjzak | 6:3c54bc7badd4 | 169 | this->effort = (float*)realloc(this->effort, effort_lengthT * sizeof(float)); |
jjzak | 6:3c54bc7badd4 | 170 | offset += 3; |
jjzak | 6:3c54bc7badd4 | 171 | effort_length = effort_lengthT; |
jjzak | 6:3c54bc7badd4 | 172 | for( uint8_t i = 0; i < effort_length; i++){ |
jjzak | 6:3c54bc7badd4 | 173 | uint32_t * val_st_effort = (uint32_t*) &(this->st_effort); |
jjzak | 6:3c54bc7badd4 | 174 | offset += 3; |
jjzak | 6:3c54bc7badd4 | 175 | *val_st_effort = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); |
jjzak | 6:3c54bc7badd4 | 176 | *val_st_effort |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; |
jjzak | 6:3c54bc7badd4 | 177 | *val_st_effort |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; |
jjzak | 6:3c54bc7badd4 | 178 | *val_st_effort |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; |
jjzak | 6:3c54bc7badd4 | 179 | uint32_t exp_st_effort = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; |
jjzak | 6:3c54bc7badd4 | 180 | exp_st_effort |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; |
jjzak | 6:3c54bc7badd4 | 181 | if(exp_st_effort !=0) |
jjzak | 6:3c54bc7badd4 | 182 | *val_st_effort |= ((exp_st_effort)-1023+127)<<23; |
jjzak | 6:3c54bc7badd4 | 183 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_effort = -this->st_effort; |
jjzak | 6:3c54bc7badd4 | 184 | memcpy( &(this->effort[i]), &(this->st_effort), sizeof(float)); |
jjzak | 6:3c54bc7badd4 | 185 | } |
jjzak | 6:3c54bc7badd4 | 186 | return offset; |
jjzak | 6:3c54bc7badd4 | 187 | } |
jjzak | 6:3c54bc7badd4 | 188 | |
jjzak | 6:3c54bc7badd4 | 189 | const char * getType(){ return "sensor_msgs/JointState"; }; |
jjzak | 6:3c54bc7badd4 | 190 | const char * getMD5(){ return "3066dcd76a6cfaef579bd0f34173e9fd"; }; |
jjzak | 6:3c54bc7badd4 | 191 | |
jjzak | 6:3c54bc7badd4 | 192 | }; |
jjzak | 6:3c54bc7badd4 | 193 | |
jjzak | 6:3c54bc7badd4 | 194 | } |
jjzak | 6:3c54bc7badd4 | 195 | #endif |