LinkScale.h
Go to the documentation of this file.
00001 #ifndef _ROS_moveit_msgs_LinkScale_h
00002 #define _ROS_moveit_msgs_LinkScale_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 
00009 namespace moveit_msgs
00010 {
00011 
00012   class LinkScale : public ros::Msg
00013   {
00014     public:
00015       const char* link_name;
00016       float scale;
00017 
00018     virtual int serialize(unsigned char *outbuffer) const
00019     {
00020       int offset = 0;
00021       uint32_t length_link_name = strlen(this->link_name);
00022       memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t));
00023       offset += 4;
00024       memcpy(outbuffer + offset, this->link_name, length_link_name);
00025       offset += length_link_name;
00026       int32_t * val_scale = (int32_t *) &(this->scale);
00027       int32_t exp_scale = (((*val_scale)>>23)&255);
00028       if(exp_scale != 0)
00029         exp_scale += 1023-127;
00030       int32_t sig_scale = *val_scale;
00031       *(outbuffer + offset++) = 0;
00032       *(outbuffer + offset++) = 0;
00033       *(outbuffer + offset++) = 0;
00034       *(outbuffer + offset++) = (sig_scale<<5) & 0xff;
00035       *(outbuffer + offset++) = (sig_scale>>3) & 0xff;
00036       *(outbuffer + offset++) = (sig_scale>>11) & 0xff;
00037       *(outbuffer + offset++) = ((exp_scale<<4) & 0xF0) | ((sig_scale>>19)&0x0F);
00038       *(outbuffer + offset++) = (exp_scale>>4) & 0x7F;
00039       if(this->scale < 0) *(outbuffer + offset -1) |= 0x80;
00040       return offset;
00041     }
00042 
00043     virtual int deserialize(unsigned char *inbuffer)
00044     {
00045       int offset = 0;
00046       uint32_t length_link_name;
00047       memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t));
00048       offset += 4;
00049       for(unsigned int k= offset; k< offset+length_link_name; ++k){
00050           inbuffer[k-1]=inbuffer[k];
00051       }
00052       inbuffer[offset+length_link_name-1]=0;
00053       this->link_name = (char *)(inbuffer + offset-1);
00054       offset += length_link_name;
00055       uint32_t * val_scale = (uint32_t*) &(this->scale);
00056       offset += 3;
00057       *val_scale = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00058       *val_scale |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00059       *val_scale |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00060       *val_scale |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00061       uint32_t exp_scale = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00062       exp_scale |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00063       if(exp_scale !=0)
00064         *val_scale |= ((exp_scale)-1023+127)<<23;
00065       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->scale = -this->scale;
00066      return offset;
00067     }
00068 
00069     const char * getType(){ return "moveit_msgs/LinkScale"; };
00070     const char * getMD5(){ return "19faf226446bfb2f645a4da6f2a56166"; };
00071 
00072   };
00073 
00074 }
00075 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Thu Aug 27 2015 14:39:49