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