JointLimits.h
Go to the documentation of this file.
00001 #ifndef _ROS_moveit_msgs_JointLimits_h
00002 #define _ROS_moveit_msgs_JointLimits_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 JointLimits : public ros::Msg
00013   {
00014     public:
00015       const char* joint_name;
00016       bool has_position_limits;
00017       float min_position;
00018       float max_position;
00019       bool has_velocity_limits;
00020       float max_velocity;
00021       bool has_acceleration_limits;
00022       float max_acceleration;
00023 
00024     virtual int serialize(unsigned char *outbuffer) const
00025     {
00026       int offset = 0;
00027       uint32_t length_joint_name = strlen(this->joint_name);
00028       memcpy(outbuffer + offset, &length_joint_name, sizeof(uint32_t));
00029       offset += 4;
00030       memcpy(outbuffer + offset, this->joint_name, length_joint_name);
00031       offset += length_joint_name;
00032       union {
00033         bool real;
00034         uint8_t base;
00035       } u_has_position_limits;
00036       u_has_position_limits.real = this->has_position_limits;
00037       *(outbuffer + offset + 0) = (u_has_position_limits.base >> (8 * 0)) & 0xFF;
00038       offset += sizeof(this->has_position_limits);
00039       int32_t * val_min_position = (int32_t *) &(this->min_position);
00040       int32_t exp_min_position = (((*val_min_position)>>23)&255);
00041       if(exp_min_position != 0)
00042         exp_min_position += 1023-127;
00043       int32_t sig_min_position = *val_min_position;
00044       *(outbuffer + offset++) = 0;
00045       *(outbuffer + offset++) = 0;
00046       *(outbuffer + offset++) = 0;
00047       *(outbuffer + offset++) = (sig_min_position<<5) & 0xff;
00048       *(outbuffer + offset++) = (sig_min_position>>3) & 0xff;
00049       *(outbuffer + offset++) = (sig_min_position>>11) & 0xff;
00050       *(outbuffer + offset++) = ((exp_min_position<<4) & 0xF0) | ((sig_min_position>>19)&0x0F);
00051       *(outbuffer + offset++) = (exp_min_position>>4) & 0x7F;
00052       if(this->min_position < 0) *(outbuffer + offset -1) |= 0x80;
00053       int32_t * val_max_position = (int32_t *) &(this->max_position);
00054       int32_t exp_max_position = (((*val_max_position)>>23)&255);
00055       if(exp_max_position != 0)
00056         exp_max_position += 1023-127;
00057       int32_t sig_max_position = *val_max_position;
00058       *(outbuffer + offset++) = 0;
00059       *(outbuffer + offset++) = 0;
00060       *(outbuffer + offset++) = 0;
00061       *(outbuffer + offset++) = (sig_max_position<<5) & 0xff;
00062       *(outbuffer + offset++) = (sig_max_position>>3) & 0xff;
00063       *(outbuffer + offset++) = (sig_max_position>>11) & 0xff;
00064       *(outbuffer + offset++) = ((exp_max_position<<4) & 0xF0) | ((sig_max_position>>19)&0x0F);
00065       *(outbuffer + offset++) = (exp_max_position>>4) & 0x7F;
00066       if(this->max_position < 0) *(outbuffer + offset -1) |= 0x80;
00067       union {
00068         bool real;
00069         uint8_t base;
00070       } u_has_velocity_limits;
00071       u_has_velocity_limits.real = this->has_velocity_limits;
00072       *(outbuffer + offset + 0) = (u_has_velocity_limits.base >> (8 * 0)) & 0xFF;
00073       offset += sizeof(this->has_velocity_limits);
00074       int32_t * val_max_velocity = (int32_t *) &(this->max_velocity);
00075       int32_t exp_max_velocity = (((*val_max_velocity)>>23)&255);
00076       if(exp_max_velocity != 0)
00077         exp_max_velocity += 1023-127;
00078       int32_t sig_max_velocity = *val_max_velocity;
00079       *(outbuffer + offset++) = 0;
00080       *(outbuffer + offset++) = 0;
00081       *(outbuffer + offset++) = 0;
00082       *(outbuffer + offset++) = (sig_max_velocity<<5) & 0xff;
00083       *(outbuffer + offset++) = (sig_max_velocity>>3) & 0xff;
00084       *(outbuffer + offset++) = (sig_max_velocity>>11) & 0xff;
00085       *(outbuffer + offset++) = ((exp_max_velocity<<4) & 0xF0) | ((sig_max_velocity>>19)&0x0F);
00086       *(outbuffer + offset++) = (exp_max_velocity>>4) & 0x7F;
00087       if(this->max_velocity < 0) *(outbuffer + offset -1) |= 0x80;
00088       union {
00089         bool real;
00090         uint8_t base;
00091       } u_has_acceleration_limits;
00092       u_has_acceleration_limits.real = this->has_acceleration_limits;
00093       *(outbuffer + offset + 0) = (u_has_acceleration_limits.base >> (8 * 0)) & 0xFF;
00094       offset += sizeof(this->has_acceleration_limits);
00095       int32_t * val_max_acceleration = (int32_t *) &(this->max_acceleration);
00096       int32_t exp_max_acceleration = (((*val_max_acceleration)>>23)&255);
00097       if(exp_max_acceleration != 0)
00098         exp_max_acceleration += 1023-127;
00099       int32_t sig_max_acceleration = *val_max_acceleration;
00100       *(outbuffer + offset++) = 0;
00101       *(outbuffer + offset++) = 0;
00102       *(outbuffer + offset++) = 0;
00103       *(outbuffer + offset++) = (sig_max_acceleration<<5) & 0xff;
00104       *(outbuffer + offset++) = (sig_max_acceleration>>3) & 0xff;
00105       *(outbuffer + offset++) = (sig_max_acceleration>>11) & 0xff;
00106       *(outbuffer + offset++) = ((exp_max_acceleration<<4) & 0xF0) | ((sig_max_acceleration>>19)&0x0F);
00107       *(outbuffer + offset++) = (exp_max_acceleration>>4) & 0x7F;
00108       if(this->max_acceleration < 0) *(outbuffer + offset -1) |= 0x80;
00109       return offset;
00110     }
00111 
00112     virtual int deserialize(unsigned char *inbuffer)
00113     {
00114       int offset = 0;
00115       uint32_t length_joint_name;
00116       memcpy(&length_joint_name, (inbuffer + offset), sizeof(uint32_t));
00117       offset += 4;
00118       for(unsigned int k= offset; k< offset+length_joint_name; ++k){
00119           inbuffer[k-1]=inbuffer[k];
00120       }
00121       inbuffer[offset+length_joint_name-1]=0;
00122       this->joint_name = (char *)(inbuffer + offset-1);
00123       offset += length_joint_name;
00124       union {
00125         bool real;
00126         uint8_t base;
00127       } u_has_position_limits;
00128       u_has_position_limits.base = 0;
00129       u_has_position_limits.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00130       this->has_position_limits = u_has_position_limits.real;
00131       offset += sizeof(this->has_position_limits);
00132       uint32_t * val_min_position = (uint32_t*) &(this->min_position);
00133       offset += 3;
00134       *val_min_position = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00135       *val_min_position |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00136       *val_min_position |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00137       *val_min_position |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00138       uint32_t exp_min_position = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00139       exp_min_position |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00140       if(exp_min_position !=0)
00141         *val_min_position |= ((exp_min_position)-1023+127)<<23;
00142       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->min_position = -this->min_position;
00143       uint32_t * val_max_position = (uint32_t*) &(this->max_position);
00144       offset += 3;
00145       *val_max_position = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00146       *val_max_position |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00147       *val_max_position |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00148       *val_max_position |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00149       uint32_t exp_max_position = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00150       exp_max_position |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00151       if(exp_max_position !=0)
00152         *val_max_position |= ((exp_max_position)-1023+127)<<23;
00153       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->max_position = -this->max_position;
00154       union {
00155         bool real;
00156         uint8_t base;
00157       } u_has_velocity_limits;
00158       u_has_velocity_limits.base = 0;
00159       u_has_velocity_limits.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00160       this->has_velocity_limits = u_has_velocity_limits.real;
00161       offset += sizeof(this->has_velocity_limits);
00162       uint32_t * val_max_velocity = (uint32_t*) &(this->max_velocity);
00163       offset += 3;
00164       *val_max_velocity = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00165       *val_max_velocity |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00166       *val_max_velocity |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00167       *val_max_velocity |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00168       uint32_t exp_max_velocity = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00169       exp_max_velocity |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00170       if(exp_max_velocity !=0)
00171         *val_max_velocity |= ((exp_max_velocity)-1023+127)<<23;
00172       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->max_velocity = -this->max_velocity;
00173       union {
00174         bool real;
00175         uint8_t base;
00176       } u_has_acceleration_limits;
00177       u_has_acceleration_limits.base = 0;
00178       u_has_acceleration_limits.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00179       this->has_acceleration_limits = u_has_acceleration_limits.real;
00180       offset += sizeof(this->has_acceleration_limits);
00181       uint32_t * val_max_acceleration = (uint32_t*) &(this->max_acceleration);
00182       offset += 3;
00183       *val_max_acceleration = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00184       *val_max_acceleration |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00185       *val_max_acceleration |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00186       *val_max_acceleration |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00187       uint32_t exp_max_acceleration = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00188       exp_max_acceleration |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00189       if(exp_max_acceleration !=0)
00190         *val_max_acceleration |= ((exp_max_acceleration)-1023+127)<<23;
00191       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->max_acceleration = -this->max_acceleration;
00192      return offset;
00193     }
00194 
00195     const char * getType(){ return "moveit_msgs/JointLimits"; };
00196     const char * getMD5(){ return "8ca618c7329ea46142cbc864a2efe856"; };
00197 
00198   };
00199 
00200 }
00201 #endif


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