PlanningOptions.h
Go to the documentation of this file.
00001 #ifndef _ROS_moveit_msgs_PlanningOptions_h
00002 #define _ROS_moveit_msgs_PlanningOptions_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "moveit_msgs/PlanningScene.h"
00009 
00010 namespace moveit_msgs
00011 {
00012 
00013   class PlanningOptions : public ros::Msg
00014   {
00015     public:
00016       moveit_msgs::PlanningScene planning_scene_diff;
00017       bool plan_only;
00018       bool look_around;
00019       int32_t look_around_attempts;
00020       float max_safe_execution_cost;
00021       bool replan;
00022       int32_t replan_attempts;
00023       float replan_delay;
00024 
00025     virtual int serialize(unsigned char *outbuffer) const
00026     {
00027       int offset = 0;
00028       offset += this->planning_scene_diff.serialize(outbuffer + offset);
00029       union {
00030         bool real;
00031         uint8_t base;
00032       } u_plan_only;
00033       u_plan_only.real = this->plan_only;
00034       *(outbuffer + offset + 0) = (u_plan_only.base >> (8 * 0)) & 0xFF;
00035       offset += sizeof(this->plan_only);
00036       union {
00037         bool real;
00038         uint8_t base;
00039       } u_look_around;
00040       u_look_around.real = this->look_around;
00041       *(outbuffer + offset + 0) = (u_look_around.base >> (8 * 0)) & 0xFF;
00042       offset += sizeof(this->look_around);
00043       union {
00044         int32_t real;
00045         uint32_t base;
00046       } u_look_around_attempts;
00047       u_look_around_attempts.real = this->look_around_attempts;
00048       *(outbuffer + offset + 0) = (u_look_around_attempts.base >> (8 * 0)) & 0xFF;
00049       *(outbuffer + offset + 1) = (u_look_around_attempts.base >> (8 * 1)) & 0xFF;
00050       *(outbuffer + offset + 2) = (u_look_around_attempts.base >> (8 * 2)) & 0xFF;
00051       *(outbuffer + offset + 3) = (u_look_around_attempts.base >> (8 * 3)) & 0xFF;
00052       offset += sizeof(this->look_around_attempts);
00053       int32_t * val_max_safe_execution_cost = (int32_t *) &(this->max_safe_execution_cost);
00054       int32_t exp_max_safe_execution_cost = (((*val_max_safe_execution_cost)>>23)&255);
00055       if(exp_max_safe_execution_cost != 0)
00056         exp_max_safe_execution_cost += 1023-127;
00057       int32_t sig_max_safe_execution_cost = *val_max_safe_execution_cost;
00058       *(outbuffer + offset++) = 0;
00059       *(outbuffer + offset++) = 0;
00060       *(outbuffer + offset++) = 0;
00061       *(outbuffer + offset++) = (sig_max_safe_execution_cost<<5) & 0xff;
00062       *(outbuffer + offset++) = (sig_max_safe_execution_cost>>3) & 0xff;
00063       *(outbuffer + offset++) = (sig_max_safe_execution_cost>>11) & 0xff;
00064       *(outbuffer + offset++) = ((exp_max_safe_execution_cost<<4) & 0xF0) | ((sig_max_safe_execution_cost>>19)&0x0F);
00065       *(outbuffer + offset++) = (exp_max_safe_execution_cost>>4) & 0x7F;
00066       if(this->max_safe_execution_cost < 0) *(outbuffer + offset -1) |= 0x80;
00067       union {
00068         bool real;
00069         uint8_t base;
00070       } u_replan;
00071       u_replan.real = this->replan;
00072       *(outbuffer + offset + 0) = (u_replan.base >> (8 * 0)) & 0xFF;
00073       offset += sizeof(this->replan);
00074       union {
00075         int32_t real;
00076         uint32_t base;
00077       } u_replan_attempts;
00078       u_replan_attempts.real = this->replan_attempts;
00079       *(outbuffer + offset + 0) = (u_replan_attempts.base >> (8 * 0)) & 0xFF;
00080       *(outbuffer + offset + 1) = (u_replan_attempts.base >> (8 * 1)) & 0xFF;
00081       *(outbuffer + offset + 2) = (u_replan_attempts.base >> (8 * 2)) & 0xFF;
00082       *(outbuffer + offset + 3) = (u_replan_attempts.base >> (8 * 3)) & 0xFF;
00083       offset += sizeof(this->replan_attempts);
00084       int32_t * val_replan_delay = (int32_t *) &(this->replan_delay);
00085       int32_t exp_replan_delay = (((*val_replan_delay)>>23)&255);
00086       if(exp_replan_delay != 0)
00087         exp_replan_delay += 1023-127;
00088       int32_t sig_replan_delay = *val_replan_delay;
00089       *(outbuffer + offset++) = 0;
00090       *(outbuffer + offset++) = 0;
00091       *(outbuffer + offset++) = 0;
00092       *(outbuffer + offset++) = (sig_replan_delay<<5) & 0xff;
00093       *(outbuffer + offset++) = (sig_replan_delay>>3) & 0xff;
00094       *(outbuffer + offset++) = (sig_replan_delay>>11) & 0xff;
00095       *(outbuffer + offset++) = ((exp_replan_delay<<4) & 0xF0) | ((sig_replan_delay>>19)&0x0F);
00096       *(outbuffer + offset++) = (exp_replan_delay>>4) & 0x7F;
00097       if(this->replan_delay < 0) *(outbuffer + offset -1) |= 0x80;
00098       return offset;
00099     }
00100 
00101     virtual int deserialize(unsigned char *inbuffer)
00102     {
00103       int offset = 0;
00104       offset += this->planning_scene_diff.deserialize(inbuffer + offset);
00105       union {
00106         bool real;
00107         uint8_t base;
00108       } u_plan_only;
00109       u_plan_only.base = 0;
00110       u_plan_only.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00111       this->plan_only = u_plan_only.real;
00112       offset += sizeof(this->plan_only);
00113       union {
00114         bool real;
00115         uint8_t base;
00116       } u_look_around;
00117       u_look_around.base = 0;
00118       u_look_around.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00119       this->look_around = u_look_around.real;
00120       offset += sizeof(this->look_around);
00121       union {
00122         int32_t real;
00123         uint32_t base;
00124       } u_look_around_attempts;
00125       u_look_around_attempts.base = 0;
00126       u_look_around_attempts.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00127       u_look_around_attempts.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00128       u_look_around_attempts.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00129       u_look_around_attempts.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00130       this->look_around_attempts = u_look_around_attempts.real;
00131       offset += sizeof(this->look_around_attempts);
00132       uint32_t * val_max_safe_execution_cost = (uint32_t*) &(this->max_safe_execution_cost);
00133       offset += 3;
00134       *val_max_safe_execution_cost = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00135       *val_max_safe_execution_cost |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00136       *val_max_safe_execution_cost |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00137       *val_max_safe_execution_cost |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00138       uint32_t exp_max_safe_execution_cost = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00139       exp_max_safe_execution_cost |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00140       if(exp_max_safe_execution_cost !=0)
00141         *val_max_safe_execution_cost |= ((exp_max_safe_execution_cost)-1023+127)<<23;
00142       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->max_safe_execution_cost = -this->max_safe_execution_cost;
00143       union {
00144         bool real;
00145         uint8_t base;
00146       } u_replan;
00147       u_replan.base = 0;
00148       u_replan.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00149       this->replan = u_replan.real;
00150       offset += sizeof(this->replan);
00151       union {
00152         int32_t real;
00153         uint32_t base;
00154       } u_replan_attempts;
00155       u_replan_attempts.base = 0;
00156       u_replan_attempts.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00157       u_replan_attempts.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00158       u_replan_attempts.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00159       u_replan_attempts.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00160       this->replan_attempts = u_replan_attempts.real;
00161       offset += sizeof(this->replan_attempts);
00162       uint32_t * val_replan_delay = (uint32_t*) &(this->replan_delay);
00163       offset += 3;
00164       *val_replan_delay = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00165       *val_replan_delay |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00166       *val_replan_delay |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00167       *val_replan_delay |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00168       uint32_t exp_replan_delay = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00169       exp_replan_delay |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00170       if(exp_replan_delay !=0)
00171         *val_replan_delay |= ((exp_replan_delay)-1023+127)<<23;
00172       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->replan_delay = -this->replan_delay;
00173      return offset;
00174     }
00175 
00176     const char * getType(){ return "moveit_msgs/PlanningOptions"; };
00177     const char * getMD5(){ return "3934e50ede2ecea03e532aade900ab50"; };
00178 
00179   };
00180 
00181 }
00182 #endif


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