This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial. This program contains an example.

Dependencies:   rosserial_mbed_lib mbed Servo

Committer:
nucho
Date:
Fri Aug 19 09:06:16 2011 +0000
Revision:
0:06fc856e99ca
Child:
3:dff241b66f84

        

Who changed what in which revision?

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