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
PlaceGoal.h
00001 #ifndef _ROS_moveit_msgs_PlaceGoal_h 00002 #define _ROS_moveit_msgs_PlaceGoal_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "moveit_msgs/PlaceLocation.h" 00009 #include "moveit_msgs/Constraints.h" 00010 #include "moveit_msgs/PlanningOptions.h" 00011 00012 namespace moveit_msgs 00013 { 00014 00015 class PlaceGoal : public ros::Msg 00016 { 00017 public: 00018 typedef const char* _group_name_type; 00019 _group_name_type group_name; 00020 typedef const char* _attached_object_name_type; 00021 _attached_object_name_type attached_object_name; 00022 uint32_t place_locations_length; 00023 typedef moveit_msgs::PlaceLocation _place_locations_type; 00024 _place_locations_type st_place_locations; 00025 _place_locations_type * place_locations; 00026 typedef bool _place_eef_type; 00027 _place_eef_type place_eef; 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 typedef moveit_msgs::Constraints _path_constraints_type; 00033 _path_constraints_type path_constraints; 00034 typedef const char* _planner_id_type; 00035 _planner_id_type planner_id; 00036 uint32_t allowed_touch_objects_length; 00037 typedef char* _allowed_touch_objects_type; 00038 _allowed_touch_objects_type st_allowed_touch_objects; 00039 _allowed_touch_objects_type * allowed_touch_objects; 00040 typedef double _allowed_planning_time_type; 00041 _allowed_planning_time_type allowed_planning_time; 00042 typedef moveit_msgs::PlanningOptions _planning_options_type; 00043 _planning_options_type planning_options; 00044 00045 PlaceGoal(): 00046 group_name(""), 00047 attached_object_name(""), 00048 place_locations_length(0), place_locations(NULL), 00049 place_eef(0), 00050 support_surface_name(""), 00051 allow_gripper_support_collision(0), 00052 path_constraints(), 00053 planner_id(""), 00054 allowed_touch_objects_length(0), allowed_touch_objects(NULL), 00055 allowed_planning_time(0), 00056 planning_options() 00057 { 00058 } 00059 00060 virtual int serialize(unsigned char *outbuffer) const 00061 { 00062 int offset = 0; 00063 uint32_t length_group_name = strlen(this->group_name); 00064 varToArr(outbuffer + offset, length_group_name); 00065 offset += 4; 00066 memcpy(outbuffer + offset, this->group_name, length_group_name); 00067 offset += length_group_name; 00068 uint32_t length_attached_object_name = strlen(this->attached_object_name); 00069 varToArr(outbuffer + offset, length_attached_object_name); 00070 offset += 4; 00071 memcpy(outbuffer + offset, this->attached_object_name, length_attached_object_name); 00072 offset += length_attached_object_name; 00073 *(outbuffer + offset + 0) = (this->place_locations_length >> (8 * 0)) & 0xFF; 00074 *(outbuffer + offset + 1) = (this->place_locations_length >> (8 * 1)) & 0xFF; 00075 *(outbuffer + offset + 2) = (this->place_locations_length >> (8 * 2)) & 0xFF; 00076 *(outbuffer + offset + 3) = (this->place_locations_length >> (8 * 3)) & 0xFF; 00077 offset += sizeof(this->place_locations_length); 00078 for( uint32_t i = 0; i < place_locations_length; i++){ 00079 offset += this->place_locations[i].serialize(outbuffer + offset); 00080 } 00081 union { 00082 bool real; 00083 uint8_t base; 00084 } u_place_eef; 00085 u_place_eef.real = this->place_eef; 00086 *(outbuffer + offset + 0) = (u_place_eef.base >> (8 * 0)) & 0xFF; 00087 offset += sizeof(this->place_eef); 00088 uint32_t length_support_surface_name = strlen(this->support_surface_name); 00089 varToArr(outbuffer + offset, length_support_surface_name); 00090 offset += 4; 00091 memcpy(outbuffer + offset, this->support_surface_name, length_support_surface_name); 00092 offset += length_support_surface_name; 00093 union { 00094 bool real; 00095 uint8_t base; 00096 } u_allow_gripper_support_collision; 00097 u_allow_gripper_support_collision.real = this->allow_gripper_support_collision; 00098 *(outbuffer + offset + 0) = (u_allow_gripper_support_collision.base >> (8 * 0)) & 0xFF; 00099 offset += sizeof(this->allow_gripper_support_collision); 00100 offset += this->path_constraints.serialize(outbuffer + offset); 00101 uint32_t length_planner_id = strlen(this->planner_id); 00102 varToArr(outbuffer + offset, length_planner_id); 00103 offset += 4; 00104 memcpy(outbuffer + offset, this->planner_id, length_planner_id); 00105 offset += length_planner_id; 00106 *(outbuffer + offset + 0) = (this->allowed_touch_objects_length >> (8 * 0)) & 0xFF; 00107 *(outbuffer + offset + 1) = (this->allowed_touch_objects_length >> (8 * 1)) & 0xFF; 00108 *(outbuffer + offset + 2) = (this->allowed_touch_objects_length >> (8 * 2)) & 0xFF; 00109 *(outbuffer + offset + 3) = (this->allowed_touch_objects_length >> (8 * 3)) & 0xFF; 00110 offset += sizeof(this->allowed_touch_objects_length); 00111 for( uint32_t i = 0; i < allowed_touch_objects_length; i++){ 00112 uint32_t length_allowed_touch_objectsi = strlen(this->allowed_touch_objects[i]); 00113 varToArr(outbuffer + offset, length_allowed_touch_objectsi); 00114 offset += 4; 00115 memcpy(outbuffer + offset, this->allowed_touch_objects[i], length_allowed_touch_objectsi); 00116 offset += length_allowed_touch_objectsi; 00117 } 00118 union { 00119 double real; 00120 uint64_t base; 00121 } u_allowed_planning_time; 00122 u_allowed_planning_time.real = this->allowed_planning_time; 00123 *(outbuffer + offset + 0) = (u_allowed_planning_time.base >> (8 * 0)) & 0xFF; 00124 *(outbuffer + offset + 1) = (u_allowed_planning_time.base >> (8 * 1)) & 0xFF; 00125 *(outbuffer + offset + 2) = (u_allowed_planning_time.base >> (8 * 2)) & 0xFF; 00126 *(outbuffer + offset + 3) = (u_allowed_planning_time.base >> (8 * 3)) & 0xFF; 00127 *(outbuffer + offset + 4) = (u_allowed_planning_time.base >> (8 * 4)) & 0xFF; 00128 *(outbuffer + offset + 5) = (u_allowed_planning_time.base >> (8 * 5)) & 0xFF; 00129 *(outbuffer + offset + 6) = (u_allowed_planning_time.base >> (8 * 6)) & 0xFF; 00130 *(outbuffer + offset + 7) = (u_allowed_planning_time.base >> (8 * 7)) & 0xFF; 00131 offset += sizeof(this->allowed_planning_time); 00132 offset += this->planning_options.serialize(outbuffer + offset); 00133 return offset; 00134 } 00135 00136 virtual int deserialize(unsigned char *inbuffer) 00137 { 00138 int offset = 0; 00139 uint32_t length_group_name; 00140 arrToVar(length_group_name, (inbuffer + offset)); 00141 offset += 4; 00142 for(unsigned int k= offset; k< offset+length_group_name; ++k){ 00143 inbuffer[k-1]=inbuffer[k]; 00144 } 00145 inbuffer[offset+length_group_name-1]=0; 00146 this->group_name = (char *)(inbuffer + offset-1); 00147 offset += length_group_name; 00148 uint32_t length_attached_object_name; 00149 arrToVar(length_attached_object_name, (inbuffer + offset)); 00150 offset += 4; 00151 for(unsigned int k= offset; k< offset+length_attached_object_name; ++k){ 00152 inbuffer[k-1]=inbuffer[k]; 00153 } 00154 inbuffer[offset+length_attached_object_name-1]=0; 00155 this->attached_object_name = (char *)(inbuffer + offset-1); 00156 offset += length_attached_object_name; 00157 uint32_t place_locations_lengthT = ((uint32_t) (*(inbuffer + offset))); 00158 place_locations_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00159 place_locations_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00160 place_locations_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00161 offset += sizeof(this->place_locations_length); 00162 if(place_locations_lengthT > place_locations_length) 00163 this->place_locations = (moveit_msgs::PlaceLocation*)realloc(this->place_locations, place_locations_lengthT * sizeof(moveit_msgs::PlaceLocation)); 00164 place_locations_length = place_locations_lengthT; 00165 for( uint32_t i = 0; i < place_locations_length; i++){ 00166 offset += this->st_place_locations.deserialize(inbuffer + offset); 00167 memcpy( &(this->place_locations[i]), &(this->st_place_locations), sizeof(moveit_msgs::PlaceLocation)); 00168 } 00169 union { 00170 bool real; 00171 uint8_t base; 00172 } u_place_eef; 00173 u_place_eef.base = 0; 00174 u_place_eef.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00175 this->place_eef = u_place_eef.real; 00176 offset += sizeof(this->place_eef); 00177 uint32_t length_support_surface_name; 00178 arrToVar(length_support_surface_name, (inbuffer + offset)); 00179 offset += 4; 00180 for(unsigned int k= offset; k< offset+length_support_surface_name; ++k){ 00181 inbuffer[k-1]=inbuffer[k]; 00182 } 00183 inbuffer[offset+length_support_surface_name-1]=0; 00184 this->support_surface_name = (char *)(inbuffer + offset-1); 00185 offset += length_support_surface_name; 00186 union { 00187 bool real; 00188 uint8_t base; 00189 } u_allow_gripper_support_collision; 00190 u_allow_gripper_support_collision.base = 0; 00191 u_allow_gripper_support_collision.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00192 this->allow_gripper_support_collision = u_allow_gripper_support_collision.real; 00193 offset += sizeof(this->allow_gripper_support_collision); 00194 offset += this->path_constraints.deserialize(inbuffer + offset); 00195 uint32_t length_planner_id; 00196 arrToVar(length_planner_id, (inbuffer + offset)); 00197 offset += 4; 00198 for(unsigned int k= offset; k< offset+length_planner_id; ++k){ 00199 inbuffer[k-1]=inbuffer[k]; 00200 } 00201 inbuffer[offset+length_planner_id-1]=0; 00202 this->planner_id = (char *)(inbuffer + offset-1); 00203 offset += length_planner_id; 00204 uint32_t allowed_touch_objects_lengthT = ((uint32_t) (*(inbuffer + offset))); 00205 allowed_touch_objects_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00206 allowed_touch_objects_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00207 allowed_touch_objects_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00208 offset += sizeof(this->allowed_touch_objects_length); 00209 if(allowed_touch_objects_lengthT > allowed_touch_objects_length) 00210 this->allowed_touch_objects = (char**)realloc(this->allowed_touch_objects, allowed_touch_objects_lengthT * sizeof(char*)); 00211 allowed_touch_objects_length = allowed_touch_objects_lengthT; 00212 for( uint32_t i = 0; i < allowed_touch_objects_length; i++){ 00213 uint32_t length_st_allowed_touch_objects; 00214 arrToVar(length_st_allowed_touch_objects, (inbuffer + offset)); 00215 offset += 4; 00216 for(unsigned int k= offset; k< offset+length_st_allowed_touch_objects; ++k){ 00217 inbuffer[k-1]=inbuffer[k]; 00218 } 00219 inbuffer[offset+length_st_allowed_touch_objects-1]=0; 00220 this->st_allowed_touch_objects = (char *)(inbuffer + offset-1); 00221 offset += length_st_allowed_touch_objects; 00222 memcpy( &(this->allowed_touch_objects[i]), &(this->st_allowed_touch_objects), sizeof(char*)); 00223 } 00224 union { 00225 double real; 00226 uint64_t base; 00227 } u_allowed_planning_time; 00228 u_allowed_planning_time.base = 0; 00229 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00230 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00231 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00232 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00233 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00234 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00235 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00236 u_allowed_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00237 this->allowed_planning_time = u_allowed_planning_time.real; 00238 offset += sizeof(this->allowed_planning_time); 00239 offset += this->planning_options.deserialize(inbuffer + offset); 00240 return offset; 00241 } 00242 00243 virtual const char * getType(){ return "moveit_msgs/PlaceGoal"; }; 00244 virtual const char * getMD5(){ return "e3f3e956e536ccd313fd8f23023f0a94"; }; 00245 00246 }; 00247 00248 } 00249 #endif
Generated on Mon Sep 26 2022 13:47:02 by
