rosserial library for mbed Inspired by nucho's rosserial library This library is still under development

Dependencies:   MODSERIAL mbed

Dependents:   mbed_roshydro_test

Library still under development!

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?

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