catchrobo2022 mbed LPC1768 メインプログラム
Dependencies: mbed
PlanningOptions.h
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 typedef moveit_msgs::PlanningScene _planning_scene_diff_type; 00017 _planning_scene_diff_type planning_scene_diff; 00018 typedef bool _plan_only_type; 00019 _plan_only_type plan_only; 00020 typedef bool _look_around_type; 00021 _look_around_type look_around; 00022 typedef int32_t _look_around_attempts_type; 00023 _look_around_attempts_type look_around_attempts; 00024 typedef double _max_safe_execution_cost_type; 00025 _max_safe_execution_cost_type max_safe_execution_cost; 00026 typedef bool _replan_type; 00027 _replan_type replan; 00028 typedef int32_t _replan_attempts_type; 00029 _replan_attempts_type replan_attempts; 00030 typedef double _replan_delay_type; 00031 _replan_delay_type replan_delay; 00032 00033 PlanningOptions(): 00034 planning_scene_diff(), 00035 plan_only(0), 00036 look_around(0), 00037 look_around_attempts(0), 00038 max_safe_execution_cost(0), 00039 replan(0), 00040 replan_attempts(0), 00041 replan_delay(0) 00042 { 00043 } 00044 00045 virtual int serialize(unsigned char *outbuffer) const 00046 { 00047 int offset = 0; 00048 offset += this->planning_scene_diff.serialize(outbuffer + offset); 00049 union { 00050 bool real; 00051 uint8_t base; 00052 } u_plan_only; 00053 u_plan_only.real = this->plan_only; 00054 *(outbuffer + offset + 0) = (u_plan_only.base >> (8 * 0)) & 0xFF; 00055 offset += sizeof(this->plan_only); 00056 union { 00057 bool real; 00058 uint8_t base; 00059 } u_look_around; 00060 u_look_around.real = this->look_around; 00061 *(outbuffer + offset + 0) = (u_look_around.base >> (8 * 0)) & 0xFF; 00062 offset += sizeof(this->look_around); 00063 union { 00064 int32_t real; 00065 uint32_t base; 00066 } u_look_around_attempts; 00067 u_look_around_attempts.real = this->look_around_attempts; 00068 *(outbuffer + offset + 0) = (u_look_around_attempts.base >> (8 * 0)) & 0xFF; 00069 *(outbuffer + offset + 1) = (u_look_around_attempts.base >> (8 * 1)) & 0xFF; 00070 *(outbuffer + offset + 2) = (u_look_around_attempts.base >> (8 * 2)) & 0xFF; 00071 *(outbuffer + offset + 3) = (u_look_around_attempts.base >> (8 * 3)) & 0xFF; 00072 offset += sizeof(this->look_around_attempts); 00073 union { 00074 double real; 00075 uint64_t base; 00076 } u_max_safe_execution_cost; 00077 u_max_safe_execution_cost.real = this->max_safe_execution_cost; 00078 *(outbuffer + offset + 0) = (u_max_safe_execution_cost.base >> (8 * 0)) & 0xFF; 00079 *(outbuffer + offset + 1) = (u_max_safe_execution_cost.base >> (8 * 1)) & 0xFF; 00080 *(outbuffer + offset + 2) = (u_max_safe_execution_cost.base >> (8 * 2)) & 0xFF; 00081 *(outbuffer + offset + 3) = (u_max_safe_execution_cost.base >> (8 * 3)) & 0xFF; 00082 *(outbuffer + offset + 4) = (u_max_safe_execution_cost.base >> (8 * 4)) & 0xFF; 00083 *(outbuffer + offset + 5) = (u_max_safe_execution_cost.base >> (8 * 5)) & 0xFF; 00084 *(outbuffer + offset + 6) = (u_max_safe_execution_cost.base >> (8 * 6)) & 0xFF; 00085 *(outbuffer + offset + 7) = (u_max_safe_execution_cost.base >> (8 * 7)) & 0xFF; 00086 offset += sizeof(this->max_safe_execution_cost); 00087 union { 00088 bool real; 00089 uint8_t base; 00090 } u_replan; 00091 u_replan.real = this->replan; 00092 *(outbuffer + offset + 0) = (u_replan.base >> (8 * 0)) & 0xFF; 00093 offset += sizeof(this->replan); 00094 union { 00095 int32_t real; 00096 uint32_t base; 00097 } u_replan_attempts; 00098 u_replan_attempts.real = this->replan_attempts; 00099 *(outbuffer + offset + 0) = (u_replan_attempts.base >> (8 * 0)) & 0xFF; 00100 *(outbuffer + offset + 1) = (u_replan_attempts.base >> (8 * 1)) & 0xFF; 00101 *(outbuffer + offset + 2) = (u_replan_attempts.base >> (8 * 2)) & 0xFF; 00102 *(outbuffer + offset + 3) = (u_replan_attempts.base >> (8 * 3)) & 0xFF; 00103 offset += sizeof(this->replan_attempts); 00104 union { 00105 double real; 00106 uint64_t base; 00107 } u_replan_delay; 00108 u_replan_delay.real = this->replan_delay; 00109 *(outbuffer + offset + 0) = (u_replan_delay.base >> (8 * 0)) & 0xFF; 00110 *(outbuffer + offset + 1) = (u_replan_delay.base >> (8 * 1)) & 0xFF; 00111 *(outbuffer + offset + 2) = (u_replan_delay.base >> (8 * 2)) & 0xFF; 00112 *(outbuffer + offset + 3) = (u_replan_delay.base >> (8 * 3)) & 0xFF; 00113 *(outbuffer + offset + 4) = (u_replan_delay.base >> (8 * 4)) & 0xFF; 00114 *(outbuffer + offset + 5) = (u_replan_delay.base >> (8 * 5)) & 0xFF; 00115 *(outbuffer + offset + 6) = (u_replan_delay.base >> (8 * 6)) & 0xFF; 00116 *(outbuffer + offset + 7) = (u_replan_delay.base >> (8 * 7)) & 0xFF; 00117 offset += sizeof(this->replan_delay); 00118 return offset; 00119 } 00120 00121 virtual int deserialize(unsigned char *inbuffer) 00122 { 00123 int offset = 0; 00124 offset += this->planning_scene_diff.deserialize(inbuffer + offset); 00125 union { 00126 bool real; 00127 uint8_t base; 00128 } u_plan_only; 00129 u_plan_only.base = 0; 00130 u_plan_only.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00131 this->plan_only = u_plan_only.real; 00132 offset += sizeof(this->plan_only); 00133 union { 00134 bool real; 00135 uint8_t base; 00136 } u_look_around; 00137 u_look_around.base = 0; 00138 u_look_around.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00139 this->look_around = u_look_around.real; 00140 offset += sizeof(this->look_around); 00141 union { 00142 int32_t real; 00143 uint32_t base; 00144 } u_look_around_attempts; 00145 u_look_around_attempts.base = 0; 00146 u_look_around_attempts.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00147 u_look_around_attempts.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00148 u_look_around_attempts.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00149 u_look_around_attempts.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00150 this->look_around_attempts = u_look_around_attempts.real; 00151 offset += sizeof(this->look_around_attempts); 00152 union { 00153 double real; 00154 uint64_t base; 00155 } u_max_safe_execution_cost; 00156 u_max_safe_execution_cost.base = 0; 00157 u_max_safe_execution_cost.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00158 u_max_safe_execution_cost.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00159 u_max_safe_execution_cost.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00160 u_max_safe_execution_cost.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00161 u_max_safe_execution_cost.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00162 u_max_safe_execution_cost.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00163 u_max_safe_execution_cost.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00164 u_max_safe_execution_cost.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00165 this->max_safe_execution_cost = u_max_safe_execution_cost.real; 00166 offset += sizeof(this->max_safe_execution_cost); 00167 union { 00168 bool real; 00169 uint8_t base; 00170 } u_replan; 00171 u_replan.base = 0; 00172 u_replan.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00173 this->replan = u_replan.real; 00174 offset += sizeof(this->replan); 00175 union { 00176 int32_t real; 00177 uint32_t base; 00178 } u_replan_attempts; 00179 u_replan_attempts.base = 0; 00180 u_replan_attempts.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00181 u_replan_attempts.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00182 u_replan_attempts.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00183 u_replan_attempts.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00184 this->replan_attempts = u_replan_attempts.real; 00185 offset += sizeof(this->replan_attempts); 00186 union { 00187 double real; 00188 uint64_t base; 00189 } u_replan_delay; 00190 u_replan_delay.base = 0; 00191 u_replan_delay.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00192 u_replan_delay.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00193 u_replan_delay.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00194 u_replan_delay.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00195 u_replan_delay.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00196 u_replan_delay.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00197 u_replan_delay.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00198 u_replan_delay.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00199 this->replan_delay = u_replan_delay.real; 00200 offset += sizeof(this->replan_delay); 00201 return offset; 00202 } 00203 00204 virtual const char * getType(){ return "moveit_msgs/PlanningOptions"; }; 00205 virtual const char * getMD5(){ return "3934e50ede2ecea03e532aade900ab50"; }; 00206 00207 }; 00208 00209 } 00210 #endif
Generated on Mon Sep 26 2022 13:47:02 by
1.7.2