Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed
PickupGoal.h
00001 #ifndef _ROS_moveit_msgs_PickupGoal_h 00002 #define _ROS_moveit_msgs_PickupGoal_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "moveit_msgs/Grasp.h" 00009 #include "moveit_msgs/Constraints.h" 00010 #include "moveit_msgs/PlanningOptions.h" 00011 00012 namespace moveit_msgs 00013 { 00014 00015 class PickupGoal : public ros::Msg 00016 { 00017 public: 00018 typedef const char* _target_name_type; 00019 _target_name_type target_name; 00020 typedef const char* _group_name_type; 00021 _group_name_type group_name; 00022 typedef const char* _end_effector_type; 00023 _end_effector_type end_effector; 00024 uint32_t possible_grasps_length; 00025 typedef moveit_msgs::Grasp _possible_grasps_type; 00026 _possible_grasps_type st_possible_grasps; 00027 _possible_grasps_type * possible_grasps; 00028 typedef const char* _support_surface_name_type; 00029 _support_surface_name_type support_surface_name; 00030 typedef bool _allow_gripper_support_collision_type; 00031 _allow_gripper_support_collision_type allow_gripper_support_collision; 00032 uint32_t attached_object_touch_links_length; 00033 typedef char* _attached_object_touch_links_type; 00034 _attached_object_touch_links_type st_attached_object_touch_links; 00035 _attached_object_touch_links_type * attached_object_touch_links; 00036 typedef bool _minimize_object_distance_type; 00037 _minimize_object_distance_type minimize_object_distance; 00038 typedef moveit_msgs::Constraints _path_constraints_type; 00039 _path_constraints_type path_constraints; 00040 typedef const char* _planner_id_type; 00041 _planner_id_type planner_id; 00042 uint32_t allowed_touch_objects_length; 00043 typedef char* _allowed_touch_objects_type; 00044 _allowed_touch_objects_type st_allowed_touch_objects; 00045 _allowed_touch_objects_type * allowed_touch_objects; 00046 typedef double _allowed_planning_time_type; 00047 _allowed_planning_time_type allowed_planning_time; 00048 typedef moveit_msgs::PlanningOptions _planning_options_type; 00049 _planning_options_type planning_options; 00050 00051 PickupGoal(): 00052 target_name(""), 00053 group_name(""), 00054 end_effector(""), 00055 possible_grasps_length(0), possible_grasps(NULL), 00056 support_surface_name(""), 00057 allow_gripper_support_collision(0), 00058 attached_object_touch_links_length(0), attached_object_touch_links(NULL), 00059 minimize_object_distance(0), 00060 path_constraints(), 00061 planner_id(""), 00062 allowed_touch_objects_length(0), allowed_touch_objects(NULL), 00063 allowed_planning_time(0), 00064 planning_options() 00065 { 00066 } 00067 00068 virtual int serialize(unsigned char *outbuffer) const 00069 { 00070 int offset = 0; 00071 uint32_t length_target_name = strlen(this->target_name); 00072 varToArr(outbuffer + offset, length_target_name); 00073 offset += 4; 00074 memcpy(outbuffer + offset, this->target_name, length_target_name); 00075 offset += length_target_name; 00076 uint32_t length_group_name = strlen(this->group_name); 00077 varToArr(outbuffer + offset, length_group_name); 00078 offset += 4; 00079 memcpy(outbuffer + offset, this->group_name, length_group_name); 00080 offset += length_group_name; 00081 uint32_t length_end_effector = strlen(this->end_effector); 00082 varToArr(outbuffer + offset, length_end_effector); 00083 offset += 4; 00084 memcpy(outbuffer + offset, this->end_effector, length_end_effector); 00085 offset += length_end_effector; 00086 *(outbuffer + offset + 0) = (this->possible_grasps_length >> (8 * 0)) & 0xFF; 00087 *(outbuffer + offset + 1) = (this->possible_grasps_length >> (8 * 1)) & 0xFF; 00088 *(outbuffer + offset + 2) = (this->possible_grasps_length >> (8 * 2)) & 0xFF; 00089 *(outbuffer + offset + 3) = (this->possible_grasps_length >> (8 * 3)) & 0xFF; 00090 offset += sizeof(this->possible_grasps_length); 00091 for( uint32_t i = 0; i < possible_grasps_length; i++){ 00092 offset += this->possible_grasps[i].serialize(outbuffer + offset); 00093 } 00094 uint32_t length_support_surface_name = strlen(this->support_surface_name); 00095 varToArr(outbuffer + offset, length_support_surface_name); 00096 offset += 4; 00097 memcpy(outbuffer + offset, this->support_surface_name, length_support_surface_name); 00098 offset += length_support_surface_name; 00099 union { 00100 bool real; 00101 uint8_t base; 00102 } u_allow_gripper_support_collision; 00103 u_allow_gripper_support_collision.real = this->allow_gripper_support_collision; 00104 *(outbuffer + offset + 0) = (u_allow_gripper_support_collision.base >> (8 * 0)) & 0xFF; 00105 offset += sizeof(this->allow_gripper_support_collision); 00106 *(outbuffer + offset + 0) = (this->attached_object_touch_links_length >> (8 * 0)) & 0xFF; 00107 *(outbuffer + offset + 1) = (this->attached_object_touch_links_length >> (8 * 1)) & 0xFF; 00108 *(outbuffer + offset + 2) = (this->attached_object_touch_links_length >> (8 * 2)) & 0xFF; 00109 *(outbuffer + offset + 3) = (this->attached_object_touch_links_length >> (8 * 3)) & 0xFF; 00110 offset += sizeof(this->attached_object_touch_links_length); 00111 for( uint32_t i = 0; i < attached_object_touch_links_length; i++){ 00112 uint32_t length_attached_object_touch_linksi = strlen(this->attached_object_touch_links[i]); 00113 varToArr(outbuffer + offset, length_attached_object_touch_linksi); 00114 offset += 4; 00115 memcpy(outbuffer + offset, this->attached_object_touch_links[i], length_attached_object_touch_linksi); 00116 offset += length_attached_object_touch_linksi; 00117 } 00118 union { 00119 bool real; 00120 uint8_t base; 00121 } u_minimize_object_distance; 00122 u_minimize_object_distance.real = this->minimize_object_distance; 00123 *(outbuffer + offset + 0) = (u_minimize_object_distance.base >> (8 * 0)) & 0xFF; 00124 offset += sizeof(this->minimize_object_distance); 00125 offset += this->path_constraints.serialize(outbuffer + offset); 00126 uint32_t length_planner_id = strlen(this->planner_id); 00127 varToArr(outbuffer + offset, length_planner_id); 00128 offset += 4; 00129 memcpy(outbuffer + offset, this->planner_id, length_planner_id); 00130 offset += length_planner_id; 00131 *(outbuffer + offset + 0) = (this->allowed_touch_objects_length >> (8 * 0)) & 0xFF; 00132 *(outbuffer + offset + 1) = (this->allowed_touch_objects_length >> (8 * 1)) & 0xFF; 00133 *(outbuffer + offset + 2) = (this->allowed_touch_objects_length >> (8 * 2)) & 0xFF; 00134 *(outbuffer + offset + 3) = (this->allowed_touch_objects_length >> (8 * 3)) & 0xFF; 00135 offset += sizeof(this->allowed_touch_objects_length); 00136 for( uint32_t i = 0; i < allowed_touch_objects_length; i++){ 00137 uint32_t length_allowed_touch_objectsi = strlen(this->allowed_touch_objects[i]); 00138 varToArr(outbuffer + offset, length_allowed_touch_objectsi); 00139 offset += 4; 00140 memcpy(outbuffer + offset, this->allowed_touch_objects[i], length_allowed_touch_objectsi); 00141 offset += length_allowed_touch_objectsi; 00142 } 00143 union { 00144 double real; 00145 uint64_t base; 00146 } u_allowed_planning_time; 00147 u_allowed_planning_time.real = this->allowed_planning_time; 00148 *(outbuffer + offset + 0) = (u_allowed_planning_time.base >> (8 * 0)) & 0xFF; 00149 *(outbuffer + offset + 1) = (u_allowed_planning_time.base >> (8 * 1)) & 0xFF; 00150 *(outbuffer + offset + 2) = (u_allowed_planning_time.base >> (8 * 2)) & 0xFF; 00151 *(outbuffer + offset + 3) = (u_allowed_planning_time.base >> (8 * 3)) & 0xFF; 00152 *(outbuffer + offset + 4) = (u_allowed_planning_time.base >> (8 * 4)) & 0xFF; 00153 *(outbuffer + offset + 5) = (u_allowed_planning_time.base >> (8 * 5)) & 0xFF; 00154 *(outbuffer + offset + 6) = (u_allowed_planning_time.base >> (8 * 6)) & 0xFF; 00155 *(outbuffer + offset + 7) = (u_allowed_planning_time.base >> (8 * 7)) & 0xFF; 00156 offset += sizeof(this->allowed_planning_time); 00157 offset += this->planning_options.serialize(outbuffer + offset); 00158 return offset; 00159 } 00160 00161 virtual int deserialize(unsigned char *inbuffer) 00162 { 00163 int offset = 0; 00164 uint32_t length_target_name; 00165 arrToVar(length_target_name, (inbuffer + offset)); 00166 offset += 4; 00167 for(unsigned int k= offset; k< offset+length_target_name; ++k){ 00168 inbuffer[k-1]=inbuffer[k]; 00169 } 00170 inbuffer[offset+length_target_name-1]=0; 00171 this->target_name = (char *)(inbuffer + offset-1); 00172 offset += length_target_name; 00173 uint32_t length_group_name; 00174 arrToVar(length_group_name, (inbuffer + offset)); 00175 offset += 4; 00176 for(unsigned int k= offset; k< offset+length_group_name; ++k){ 00177 inbuffer[k-1]=inbuffer[k]; 00178 } 00179 inbuffer[offset+length_group_name-1]=0; 00180 this->group_name = (char *)(inbuffer + offset-1); 00181 offset += length_group_name; 00182 uint32_t length_end_effector; 00183 arrToVar(length_end_effector, (inbuffer + offset)); 00184 offset += 4; 00185 for(unsigned int k= offset; k< offset+length_end_effector; ++k){ 00186 inbuffer[k-1]=inbuffer[k]; 00187 } 00188 inbuffer[offset+length_end_effector-1]=0; 00189 this->end_effector = (char *)(inbuffer + offset-1); 00190 offset += length_end_effector; 00191 uint32_t possible_grasps_lengthT = ((uint32_t) (*(inbuffer + offset))); 00192 possible_grasps_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00193 possible_grasps_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00194 possible_grasps_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00195 offset += sizeof(this->possible_grasps_length); 00196 if(possible_grasps_lengthT > possible_grasps_length) 00197 this->possible_grasps = (moveit_msgs::Grasp*)realloc(this->possible_grasps, possible_grasps_lengthT * sizeof(moveit_msgs::Grasp)); 00198 possible_grasps_length = possible_grasps_lengthT; 00199 for( uint32_t i = 0; i < possible_grasps_length; i++){ 00200 offset += this->st_possible_grasps.deserialize(inbuffer + offset); 00201 memcpy( &(this->possible_grasps[i]), &(this->st_possible_grasps), sizeof(moveit_msgs::Grasp)); 00202 } 00203 uint32_t length_support_surface_name; 00204 arrToVar(length_support_surface_name, (inbuffer + offset)); 00205 offset += 4; 00206 for(unsigned int k= offset; k< offset+length_support_surface_name; ++k){ 00207 inbuffer[k-1]=inbuffer[k]; 00208 } 00209 inbuffer[offset+length_support_surface_name-1]=0; 00210 this->support_surface_name = (char *)(inbuffer + offset-1); 00211 offset += length_support_surface_name; 00212 union { 00213 bool real; 00214 uint8_t base; 00215 } u_allow_gripper_support_collision; 00216 u_allow_gripper_support_collision.base = 0; 00217 u_allow_gripper_support_collision.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00218 this->allow_gripper_support_collision = u_allow_gripper_support_collision.real; 00219 offset += sizeof(this->allow_gripper_support_collision); 00220 uint32_t attached_object_touch_links_lengthT = ((uint32_t) (*(inbuffer + offset))); 00221 attached_object_touch_links_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00222 attached_object_touch_links_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00223 attached_object_touch_links_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00224 offset += sizeof(this->attached_object_touch_links_length); 00225 if(attached_object_touch_links_lengthT > attached_object_touch_links_length) 00226 this->attached_object_touch_links = (char**)realloc(this->attached_object_touch_links, attached_object_touch_links_lengthT * sizeof(char*)); 00227 attached_object_touch_links_length = attached_object_touch_links_lengthT; 00228 for( uint32_t i = 0; i < attached_object_touch_links_length; i++){ 00229 uint32_t length_st_attached_object_touch_links; 00230 arrToVar(length_st_attached_object_touch_links, (inbuffer + offset)); 00231 offset += 4; 00232 for(unsigned int k= offset; k< offset+length_st_attached_object_touch_links; ++k){ 00233 inbuffer[k-1]=inbuffer[k]; 00234 } 00235 inbuffer[offset+length_st_attached_object_touch_links-1]=0; 00236 this->st_attached_object_touch_links = (char *)(inbuffer + offset-1); 00237 offset += length_st_attached_object_touch_links; 00238 memcpy( &(this->attached_object_touch_links[i]), &(this->st_attached_object_touch_links), sizeof(char*)); 00239 } 00240 union { 00241 bool real; 00242 uint8_t base; 00243 } u_minimize_object_distance; 00244 u_minimize_object_distance.base = 0; 00245 u_minimize_object_distance.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00246 this->minimize_object_distance = u_minimize_object_distance.real; 00247 offset += sizeof(this->minimize_object_distance); 00248 offset += this->path_constraints.deserialize(inbuffer + offset); 00249 uint32_t length_planner_id; 00250 arrToVar(length_planner_id, (inbuffer + offset)); 00251 offset += 4; 00252 for(unsigned int k= offset; k< offset+length_planner_id; ++k){ 00253 inbuffer[k-1]=inbuffer[k]; 00254 } 00255 inbuffer[offset+length_planner_id-1]=0; 00256 this->planner_id = (char *)(inbuffer + offset-1); 00257 offset += length_planner_id; 00258 uint32_t allowed_touch_objects_lengthT = ((uint32_t) (*(inbuffer + offset))); 00259 allowed_touch_objects_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00260 allowed_touch_objects_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00261 allowed_touch_objects_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00262 offset += sizeof(this->allowed_touch_objects_length); 00263 if(allowed_touch_objects_lengthT > allowed_touch_objects_length) 00264 this->allowed_touch_objects = (char**)realloc(this->allowed_touch_objects, allowed_touch_objects_lengthT * sizeof(char*)); 00265 allowed_touch_objects_length = allowed_touch_objects_lengthT; 00266 for( uint32_t i = 0; i < allowed_touch_objects_length; i++){ 00267 uint32_t length_st_allowed_touch_objects; 00268 arrToVar(length_st_allowed_touch_objects, (inbuffer + offset)); 00269 offset += 4; 00270 for(unsigned int k= offset; k< offset+length_st_allowed_touch_objects; ++k){ 00271 inbuffer[k-1]=inbuffer[k]; 00272 } 00273 inbuffer[offset+length_st_allowed_touch_objects-1]=0; 00274 this->st_allowed_touch_objects = (char *)(inbuffer + offset-1); 00275 offset += length_st_allowed_touch_objects; 00276 memcpy( &(this->allowed_touch_objects[i]), &(this->st_allowed_touch_objects), sizeof(char*)); 00277 } 00278 union { 00279 double real; 00280 uint64_t base; 00281 } u_allowed_planning_time; 00282 u_allowed_planning_time.base = 0; 00283 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00284 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00285 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00286 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00287 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00288 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00289 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00290 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00291 this->allowed_planning_time = u_allowed_planning_time.real; 00292 offset += sizeof(this->allowed_planning_time); 00293 offset += this->planning_options.deserialize(inbuffer + offset); 00294 return offset; 00295 } 00296 00297 virtual const char * getType(){ return "moveit_msgs/PickupGoal"; }; 00298 virtual const char * getMD5(){ return "458c6ab3761d73e99b070063f7b74c2a"; }; 00299 00300 }; 00301 00302 } 00303 #endif
Generated on Mon Sep 26 2022 13:47:02 by
