JointControllerState.h
Go to the documentation of this file.
00001 #ifndef _ROS_control_msgs_JointControllerState_h
00002 #define _ROS_control_msgs_JointControllerState_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "std_msgs/Header.h"
00009 
00010 namespace control_msgs
00011 {
00012 
00013   class JointControllerState : public ros::Msg
00014   {
00015     public:
00016       std_msgs::Header header;
00017       float set_point;
00018       float process_value;
00019       float process_value_dot;
00020       float error;
00021       float time_step;
00022       float command;
00023       float p;
00024       float i;
00025       float d;
00026       float i_clamp;
00027 
00028     virtual int serialize(unsigned char *outbuffer) const
00029     {
00030       int offset = 0;
00031       offset += this->header.serialize(outbuffer + offset);
00032       int32_t * val_set_point = (int32_t *) &(this->set_point);
00033       int32_t exp_set_point = (((*val_set_point)>>23)&255);
00034       if(exp_set_point != 0)
00035         exp_set_point += 1023-127;
00036       int32_t sig_set_point = *val_set_point;
00037       *(outbuffer + offset++) = 0;
00038       *(outbuffer + offset++) = 0;
00039       *(outbuffer + offset++) = 0;
00040       *(outbuffer + offset++) = (sig_set_point<<5) & 0xff;
00041       *(outbuffer + offset++) = (sig_set_point>>3) & 0xff;
00042       *(outbuffer + offset++) = (sig_set_point>>11) & 0xff;
00043       *(outbuffer + offset++) = ((exp_set_point<<4) & 0xF0) | ((sig_set_point>>19)&0x0F);
00044       *(outbuffer + offset++) = (exp_set_point>>4) & 0x7F;
00045       if(this->set_point < 0) *(outbuffer + offset -1) |= 0x80;
00046       int32_t * val_process_value = (int32_t *) &(this->process_value);
00047       int32_t exp_process_value = (((*val_process_value)>>23)&255);
00048       if(exp_process_value != 0)
00049         exp_process_value += 1023-127;
00050       int32_t sig_process_value = *val_process_value;
00051       *(outbuffer + offset++) = 0;
00052       *(outbuffer + offset++) = 0;
00053       *(outbuffer + offset++) = 0;
00054       *(outbuffer + offset++) = (sig_process_value<<5) & 0xff;
00055       *(outbuffer + offset++) = (sig_process_value>>3) & 0xff;
00056       *(outbuffer + offset++) = (sig_process_value>>11) & 0xff;
00057       *(outbuffer + offset++) = ((exp_process_value<<4) & 0xF0) | ((sig_process_value>>19)&0x0F);
00058       *(outbuffer + offset++) = (exp_process_value>>4) & 0x7F;
00059       if(this->process_value < 0) *(outbuffer + offset -1) |= 0x80;
00060       int32_t * val_process_value_dot = (int32_t *) &(this->process_value_dot);
00061       int32_t exp_process_value_dot = (((*val_process_value_dot)>>23)&255);
00062       if(exp_process_value_dot != 0)
00063         exp_process_value_dot += 1023-127;
00064       int32_t sig_process_value_dot = *val_process_value_dot;
00065       *(outbuffer + offset++) = 0;
00066       *(outbuffer + offset++) = 0;
00067       *(outbuffer + offset++) = 0;
00068       *(outbuffer + offset++) = (sig_process_value_dot<<5) & 0xff;
00069       *(outbuffer + offset++) = (sig_process_value_dot>>3) & 0xff;
00070       *(outbuffer + offset++) = (sig_process_value_dot>>11) & 0xff;
00071       *(outbuffer + offset++) = ((exp_process_value_dot<<4) & 0xF0) | ((sig_process_value_dot>>19)&0x0F);
00072       *(outbuffer + offset++) = (exp_process_value_dot>>4) & 0x7F;
00073       if(this->process_value_dot < 0) *(outbuffer + offset -1) |= 0x80;
00074       int32_t * val_error = (int32_t *) &(this->error);
00075       int32_t exp_error = (((*val_error)>>23)&255);
00076       if(exp_error != 0)
00077         exp_error += 1023-127;
00078       int32_t sig_error = *val_error;
00079       *(outbuffer + offset++) = 0;
00080       *(outbuffer + offset++) = 0;
00081       *(outbuffer + offset++) = 0;
00082       *(outbuffer + offset++) = (sig_error<<5) & 0xff;
00083       *(outbuffer + offset++) = (sig_error>>3) & 0xff;
00084       *(outbuffer + offset++) = (sig_error>>11) & 0xff;
00085       *(outbuffer + offset++) = ((exp_error<<4) & 0xF0) | ((sig_error>>19)&0x0F);
00086       *(outbuffer + offset++) = (exp_error>>4) & 0x7F;
00087       if(this->error < 0) *(outbuffer + offset -1) |= 0x80;
00088       int32_t * val_time_step = (int32_t *) &(this->time_step);
00089       int32_t exp_time_step = (((*val_time_step)>>23)&255);
00090       if(exp_time_step != 0)
00091         exp_time_step += 1023-127;
00092       int32_t sig_time_step = *val_time_step;
00093       *(outbuffer + offset++) = 0;
00094       *(outbuffer + offset++) = 0;
00095       *(outbuffer + offset++) = 0;
00096       *(outbuffer + offset++) = (sig_time_step<<5) & 0xff;
00097       *(outbuffer + offset++) = (sig_time_step>>3) & 0xff;
00098       *(outbuffer + offset++) = (sig_time_step>>11) & 0xff;
00099       *(outbuffer + offset++) = ((exp_time_step<<4) & 0xF0) | ((sig_time_step>>19)&0x0F);
00100       *(outbuffer + offset++) = (exp_time_step>>4) & 0x7F;
00101       if(this->time_step < 0) *(outbuffer + offset -1) |= 0x80;
00102       int32_t * val_command = (int32_t *) &(this->command);
00103       int32_t exp_command = (((*val_command)>>23)&255);
00104       if(exp_command != 0)
00105         exp_command += 1023-127;
00106       int32_t sig_command = *val_command;
00107       *(outbuffer + offset++) = 0;
00108       *(outbuffer + offset++) = 0;
00109       *(outbuffer + offset++) = 0;
00110       *(outbuffer + offset++) = (sig_command<<5) & 0xff;
00111       *(outbuffer + offset++) = (sig_command>>3) & 0xff;
00112       *(outbuffer + offset++) = (sig_command>>11) & 0xff;
00113       *(outbuffer + offset++) = ((exp_command<<4) & 0xF0) | ((sig_command>>19)&0x0F);
00114       *(outbuffer + offset++) = (exp_command>>4) & 0x7F;
00115       if(this->command < 0) *(outbuffer + offset -1) |= 0x80;
00116       int32_t * val_p = (int32_t *) &(this->p);
00117       int32_t exp_p = (((*val_p)>>23)&255);
00118       if(exp_p != 0)
00119         exp_p += 1023-127;
00120       int32_t sig_p = *val_p;
00121       *(outbuffer + offset++) = 0;
00122       *(outbuffer + offset++) = 0;
00123       *(outbuffer + offset++) = 0;
00124       *(outbuffer + offset++) = (sig_p<<5) & 0xff;
00125       *(outbuffer + offset++) = (sig_p>>3) & 0xff;
00126       *(outbuffer + offset++) = (sig_p>>11) & 0xff;
00127       *(outbuffer + offset++) = ((exp_p<<4) & 0xF0) | ((sig_p>>19)&0x0F);
00128       *(outbuffer + offset++) = (exp_p>>4) & 0x7F;
00129       if(this->p < 0) *(outbuffer + offset -1) |= 0x80;
00130       int32_t * val_i = (int32_t *) &(this->i);
00131       int32_t exp_i = (((*val_i)>>23)&255);
00132       if(exp_i != 0)
00133         exp_i += 1023-127;
00134       int32_t sig_i = *val_i;
00135       *(outbuffer + offset++) = 0;
00136       *(outbuffer + offset++) = 0;
00137       *(outbuffer + offset++) = 0;
00138       *(outbuffer + offset++) = (sig_i<<5) & 0xff;
00139       *(outbuffer + offset++) = (sig_i>>3) & 0xff;
00140       *(outbuffer + offset++) = (sig_i>>11) & 0xff;
00141       *(outbuffer + offset++) = ((exp_i<<4) & 0xF0) | ((sig_i>>19)&0x0F);
00142       *(outbuffer + offset++) = (exp_i>>4) & 0x7F;
00143       if(this->i < 0) *(outbuffer + offset -1) |= 0x80;
00144       int32_t * val_d = (int32_t *) &(this->d);
00145       int32_t exp_d = (((*val_d)>>23)&255);
00146       if(exp_d != 0)
00147         exp_d += 1023-127;
00148       int32_t sig_d = *val_d;
00149       *(outbuffer + offset++) = 0;
00150       *(outbuffer + offset++) = 0;
00151       *(outbuffer + offset++) = 0;
00152       *(outbuffer + offset++) = (sig_d<<5) & 0xff;
00153       *(outbuffer + offset++) = (sig_d>>3) & 0xff;
00154       *(outbuffer + offset++) = (sig_d>>11) & 0xff;
00155       *(outbuffer + offset++) = ((exp_d<<4) & 0xF0) | ((sig_d>>19)&0x0F);
00156       *(outbuffer + offset++) = (exp_d>>4) & 0x7F;
00157       if(this->d < 0) *(outbuffer + offset -1) |= 0x80;
00158       int32_t * val_i_clamp = (int32_t *) &(this->i_clamp);
00159       int32_t exp_i_clamp = (((*val_i_clamp)>>23)&255);
00160       if(exp_i_clamp != 0)
00161         exp_i_clamp += 1023-127;
00162       int32_t sig_i_clamp = *val_i_clamp;
00163       *(outbuffer + offset++) = 0;
00164       *(outbuffer + offset++) = 0;
00165       *(outbuffer + offset++) = 0;
00166       *(outbuffer + offset++) = (sig_i_clamp<<5) & 0xff;
00167       *(outbuffer + offset++) = (sig_i_clamp>>3) & 0xff;
00168       *(outbuffer + offset++) = (sig_i_clamp>>11) & 0xff;
00169       *(outbuffer + offset++) = ((exp_i_clamp<<4) & 0xF0) | ((sig_i_clamp>>19)&0x0F);
00170       *(outbuffer + offset++) = (exp_i_clamp>>4) & 0x7F;
00171       if(this->i_clamp < 0) *(outbuffer + offset -1) |= 0x80;
00172       return offset;
00173     }
00174 
00175     virtual int deserialize(unsigned char *inbuffer)
00176     {
00177       int offset = 0;
00178       offset += this->header.deserialize(inbuffer + offset);
00179       uint32_t * val_set_point = (uint32_t*) &(this->set_point);
00180       offset += 3;
00181       *val_set_point = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00182       *val_set_point |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00183       *val_set_point |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00184       *val_set_point |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00185       uint32_t exp_set_point = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00186       exp_set_point |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00187       if(exp_set_point !=0)
00188         *val_set_point |= ((exp_set_point)-1023+127)<<23;
00189       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->set_point = -this->set_point;
00190       uint32_t * val_process_value = (uint32_t*) &(this->process_value);
00191       offset += 3;
00192       *val_process_value = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00193       *val_process_value |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00194       *val_process_value |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00195       *val_process_value |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00196       uint32_t exp_process_value = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00197       exp_process_value |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00198       if(exp_process_value !=0)
00199         *val_process_value |= ((exp_process_value)-1023+127)<<23;
00200       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->process_value = -this->process_value;
00201       uint32_t * val_process_value_dot = (uint32_t*) &(this->process_value_dot);
00202       offset += 3;
00203       *val_process_value_dot = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00204       *val_process_value_dot |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00205       *val_process_value_dot |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00206       *val_process_value_dot |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00207       uint32_t exp_process_value_dot = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00208       exp_process_value_dot |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00209       if(exp_process_value_dot !=0)
00210         *val_process_value_dot |= ((exp_process_value_dot)-1023+127)<<23;
00211       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->process_value_dot = -this->process_value_dot;
00212       uint32_t * val_error = (uint32_t*) &(this->error);
00213       offset += 3;
00214       *val_error = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00215       *val_error |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00216       *val_error |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00217       *val_error |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00218       uint32_t exp_error = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00219       exp_error |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00220       if(exp_error !=0)
00221         *val_error |= ((exp_error)-1023+127)<<23;
00222       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->error = -this->error;
00223       uint32_t * val_time_step = (uint32_t*) &(this->time_step);
00224       offset += 3;
00225       *val_time_step = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00226       *val_time_step |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00227       *val_time_step |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00228       *val_time_step |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00229       uint32_t exp_time_step = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00230       exp_time_step |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00231       if(exp_time_step !=0)
00232         *val_time_step |= ((exp_time_step)-1023+127)<<23;
00233       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->time_step = -this->time_step;
00234       uint32_t * val_command = (uint32_t*) &(this->command);
00235       offset += 3;
00236       *val_command = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00237       *val_command |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00238       *val_command |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00239       *val_command |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00240       uint32_t exp_command = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00241       exp_command |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00242       if(exp_command !=0)
00243         *val_command |= ((exp_command)-1023+127)<<23;
00244       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->command = -this->command;
00245       uint32_t * val_p = (uint32_t*) &(this->p);
00246       offset += 3;
00247       *val_p = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00248       *val_p |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00249       *val_p |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00250       *val_p |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00251       uint32_t exp_p = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00252       exp_p |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00253       if(exp_p !=0)
00254         *val_p |= ((exp_p)-1023+127)<<23;
00255       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->p = -this->p;
00256       uint32_t * val_i = (uint32_t*) &(this->i);
00257       offset += 3;
00258       *val_i = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00259       *val_i |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00260       *val_i |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00261       *val_i |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00262       uint32_t exp_i = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00263       exp_i |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00264       if(exp_i !=0)
00265         *val_i |= ((exp_i)-1023+127)<<23;
00266       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->i = -this->i;
00267       uint32_t * val_d = (uint32_t*) &(this->d);
00268       offset += 3;
00269       *val_d = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00270       *val_d |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00271       *val_d |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00272       *val_d |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00273       uint32_t exp_d = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00274       exp_d |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00275       if(exp_d !=0)
00276         *val_d |= ((exp_d)-1023+127)<<23;
00277       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->d = -this->d;
00278       uint32_t * val_i_clamp = (uint32_t*) &(this->i_clamp);
00279       offset += 3;
00280       *val_i_clamp = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00281       *val_i_clamp |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00282       *val_i_clamp |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00283       *val_i_clamp |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00284       uint32_t exp_i_clamp = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00285       exp_i_clamp |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00286       if(exp_i_clamp !=0)
00287         *val_i_clamp |= ((exp_i_clamp)-1023+127)<<23;
00288       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->i_clamp = -this->i_clamp;
00289      return offset;
00290     }
00291 
00292     const char * getType(){ return "control_msgs/JointControllerState"; };
00293     const char * getMD5(){ return "c0d034a7bf20aeb1c37f3eccb7992b69"; };
00294 
00295   };
00296 
00297 }
00298 #endif


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