rosserial library for mbed Inspired by nucho's rosserial library This library is still under development
Dependents: mbed_roshydro_test
Library still under development!
moveit_msgs/PickupGoal.h@0:30537dec6e0b, 2015-02-15 (annotated)
- Committer:
- akashvibhute
- Date:
- Sun Feb 15 10:53:43 2015 +0000
- Revision:
- 0:30537dec6e0b
First commit; Library still need to be debugged, compilation issues with new mbed and modserial updates.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
akashvibhute | 0:30537dec6e0b | 1 | #ifndef _ROS_moveit_msgs_PickupGoal_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_moveit_msgs_PickupGoal_h |
akashvibhute | 0:30537dec6e0b | 3 | |
akashvibhute | 0:30537dec6e0b | 4 | #include <stdint.h> |
akashvibhute | 0:30537dec6e0b | 5 | #include <string.h> |
akashvibhute | 0:30537dec6e0b | 6 | #include <stdlib.h> |
akashvibhute | 0:30537dec6e0b | 7 | #include "ros/msg.h" |
akashvibhute | 0:30537dec6e0b | 8 | #include "moveit_msgs/Grasp.h" |
akashvibhute | 0:30537dec6e0b | 9 | #include "moveit_msgs/Constraints.h" |
akashvibhute | 0:30537dec6e0b | 10 | #include "moveit_msgs/PlanningOptions.h" |
akashvibhute | 0:30537dec6e0b | 11 | |
akashvibhute | 0:30537dec6e0b | 12 | namespace moveit_msgs |
akashvibhute | 0:30537dec6e0b | 13 | { |
akashvibhute | 0:30537dec6e0b | 14 | |
akashvibhute | 0:30537dec6e0b | 15 | class PickupGoal : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 16 | { |
akashvibhute | 0:30537dec6e0b | 17 | public: |
akashvibhute | 0:30537dec6e0b | 18 | const char* target_name; |
akashvibhute | 0:30537dec6e0b | 19 | const char* group_name; |
akashvibhute | 0:30537dec6e0b | 20 | const char* end_effector; |
akashvibhute | 0:30537dec6e0b | 21 | uint8_t possible_grasps_length; |
akashvibhute | 0:30537dec6e0b | 22 | moveit_msgs::Grasp st_possible_grasps; |
akashvibhute | 0:30537dec6e0b | 23 | moveit_msgs::Grasp * possible_grasps; |
akashvibhute | 0:30537dec6e0b | 24 | const char* support_surface_name; |
akashvibhute | 0:30537dec6e0b | 25 | bool allow_gripper_support_collision; |
akashvibhute | 0:30537dec6e0b | 26 | uint8_t attached_object_touch_links_length; |
akashvibhute | 0:30537dec6e0b | 27 | char* st_attached_object_touch_links; |
akashvibhute | 0:30537dec6e0b | 28 | char* * attached_object_touch_links; |
akashvibhute | 0:30537dec6e0b | 29 | bool minimize_object_distance; |
akashvibhute | 0:30537dec6e0b | 30 | moveit_msgs::Constraints path_constraints; |
akashvibhute | 0:30537dec6e0b | 31 | const char* planner_id; |
akashvibhute | 0:30537dec6e0b | 32 | uint8_t allowed_touch_objects_length; |
akashvibhute | 0:30537dec6e0b | 33 | char* st_allowed_touch_objects; |
akashvibhute | 0:30537dec6e0b | 34 | char* * allowed_touch_objects; |
akashvibhute | 0:30537dec6e0b | 35 | float allowed_planning_time; |
akashvibhute | 0:30537dec6e0b | 36 | moveit_msgs::PlanningOptions planning_options; |
akashvibhute | 0:30537dec6e0b | 37 | |
akashvibhute | 0:30537dec6e0b | 38 | PickupGoal(): |
akashvibhute | 0:30537dec6e0b | 39 | target_name(""), |
akashvibhute | 0:30537dec6e0b | 40 | group_name(""), |
akashvibhute | 0:30537dec6e0b | 41 | end_effector(""), |
akashvibhute | 0:30537dec6e0b | 42 | possible_grasps_length(0), possible_grasps(NULL), |
akashvibhute | 0:30537dec6e0b | 43 | support_surface_name(""), |
akashvibhute | 0:30537dec6e0b | 44 | allow_gripper_support_collision(0), |
akashvibhute | 0:30537dec6e0b | 45 | attached_object_touch_links_length(0), attached_object_touch_links(NULL), |
akashvibhute | 0:30537dec6e0b | 46 | minimize_object_distance(0), |
akashvibhute | 0:30537dec6e0b | 47 | path_constraints(), |
akashvibhute | 0:30537dec6e0b | 48 | planner_id(""), |
akashvibhute | 0:30537dec6e0b | 49 | allowed_touch_objects_length(0), allowed_touch_objects(NULL), |
akashvibhute | 0:30537dec6e0b | 50 | allowed_planning_time(0), |
akashvibhute | 0:30537dec6e0b | 51 | planning_options() |
akashvibhute | 0:30537dec6e0b | 52 | { |
akashvibhute | 0:30537dec6e0b | 53 | } |
akashvibhute | 0:30537dec6e0b | 54 | |
akashvibhute | 0:30537dec6e0b | 55 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 56 | { |
akashvibhute | 0:30537dec6e0b | 57 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 58 | uint32_t length_target_name = strlen(this->target_name); |
akashvibhute | 0:30537dec6e0b | 59 | memcpy(outbuffer + offset, &length_target_name, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 60 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 61 | memcpy(outbuffer + offset, this->target_name, length_target_name); |
akashvibhute | 0:30537dec6e0b | 62 | offset += length_target_name; |
akashvibhute | 0:30537dec6e0b | 63 | uint32_t length_group_name = strlen(this->group_name); |
akashvibhute | 0:30537dec6e0b | 64 | memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 65 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 66 | memcpy(outbuffer + offset, this->group_name, length_group_name); |
akashvibhute | 0:30537dec6e0b | 67 | offset += length_group_name; |
akashvibhute | 0:30537dec6e0b | 68 | uint32_t length_end_effector = strlen(this->end_effector); |
akashvibhute | 0:30537dec6e0b | 69 | memcpy(outbuffer + offset, &length_end_effector, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 70 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 71 | memcpy(outbuffer + offset, this->end_effector, length_end_effector); |
akashvibhute | 0:30537dec6e0b | 72 | offset += length_end_effector; |
akashvibhute | 0:30537dec6e0b | 73 | *(outbuffer + offset++) = possible_grasps_length; |
akashvibhute | 0:30537dec6e0b | 74 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 75 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 76 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 77 | for( uint8_t i = 0; i < possible_grasps_length; i++){ |
akashvibhute | 0:30537dec6e0b | 78 | offset += this->possible_grasps[i].serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 79 | } |
akashvibhute | 0:30537dec6e0b | 80 | uint32_t length_support_surface_name = strlen(this->support_surface_name); |
akashvibhute | 0:30537dec6e0b | 81 | memcpy(outbuffer + offset, &length_support_surface_name, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 82 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 83 | memcpy(outbuffer + offset, this->support_surface_name, length_support_surface_name); |
akashvibhute | 0:30537dec6e0b | 84 | offset += length_support_surface_name; |
akashvibhute | 0:30537dec6e0b | 85 | union { |
akashvibhute | 0:30537dec6e0b | 86 | bool real; |
akashvibhute | 0:30537dec6e0b | 87 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 88 | } u_allow_gripper_support_collision; |
akashvibhute | 0:30537dec6e0b | 89 | u_allow_gripper_support_collision.real = this->allow_gripper_support_collision; |
akashvibhute | 0:30537dec6e0b | 90 | *(outbuffer + offset + 0) = (u_allow_gripper_support_collision.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 91 | offset += sizeof(this->allow_gripper_support_collision); |
akashvibhute | 0:30537dec6e0b | 92 | *(outbuffer + offset++) = attached_object_touch_links_length; |
akashvibhute | 0:30537dec6e0b | 93 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 94 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 95 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 96 | for( uint8_t i = 0; i < attached_object_touch_links_length; i++){ |
akashvibhute | 0:30537dec6e0b | 97 | uint32_t length_attached_object_touch_linksi = strlen(this->attached_object_touch_links[i]); |
akashvibhute | 0:30537dec6e0b | 98 | memcpy(outbuffer + offset, &length_attached_object_touch_linksi, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 99 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 100 | memcpy(outbuffer + offset, this->attached_object_touch_links[i], length_attached_object_touch_linksi); |
akashvibhute | 0:30537dec6e0b | 101 | offset += length_attached_object_touch_linksi; |
akashvibhute | 0:30537dec6e0b | 102 | } |
akashvibhute | 0:30537dec6e0b | 103 | union { |
akashvibhute | 0:30537dec6e0b | 104 | bool real; |
akashvibhute | 0:30537dec6e0b | 105 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 106 | } u_minimize_object_distance; |
akashvibhute | 0:30537dec6e0b | 107 | u_minimize_object_distance.real = this->minimize_object_distance; |
akashvibhute | 0:30537dec6e0b | 108 | *(outbuffer + offset + 0) = (u_minimize_object_distance.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 109 | offset += sizeof(this->minimize_object_distance); |
akashvibhute | 0:30537dec6e0b | 110 | offset += this->path_constraints.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 111 | uint32_t length_planner_id = strlen(this->planner_id); |
akashvibhute | 0:30537dec6e0b | 112 | memcpy(outbuffer + offset, &length_planner_id, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 113 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 114 | memcpy(outbuffer + offset, this->planner_id, length_planner_id); |
akashvibhute | 0:30537dec6e0b | 115 | offset += length_planner_id; |
akashvibhute | 0:30537dec6e0b | 116 | *(outbuffer + offset++) = allowed_touch_objects_length; |
akashvibhute | 0:30537dec6e0b | 117 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 118 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 119 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 120 | for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ |
akashvibhute | 0:30537dec6e0b | 121 | uint32_t length_allowed_touch_objectsi = strlen(this->allowed_touch_objects[i]); |
akashvibhute | 0:30537dec6e0b | 122 | memcpy(outbuffer + offset, &length_allowed_touch_objectsi, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 123 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 124 | memcpy(outbuffer + offset, this->allowed_touch_objects[i], length_allowed_touch_objectsi); |
akashvibhute | 0:30537dec6e0b | 125 | offset += length_allowed_touch_objectsi; |
akashvibhute | 0:30537dec6e0b | 126 | } |
akashvibhute | 0:30537dec6e0b | 127 | offset += serializeAvrFloat64(outbuffer + offset, this->allowed_planning_time); |
akashvibhute | 0:30537dec6e0b | 128 | offset += this->planning_options.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 129 | return offset; |
akashvibhute | 0:30537dec6e0b | 130 | } |
akashvibhute | 0:30537dec6e0b | 131 | |
akashvibhute | 0:30537dec6e0b | 132 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 133 | { |
akashvibhute | 0:30537dec6e0b | 134 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 135 | uint32_t length_target_name; |
akashvibhute | 0:30537dec6e0b | 136 | memcpy(&length_target_name, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 137 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 138 | for(unsigned int k= offset; k< offset+length_target_name; ++k){ |
akashvibhute | 0:30537dec6e0b | 139 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 140 | } |
akashvibhute | 0:30537dec6e0b | 141 | inbuffer[offset+length_target_name-1]=0; |
akashvibhute | 0:30537dec6e0b | 142 | this->target_name = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 143 | offset += length_target_name; |
akashvibhute | 0:30537dec6e0b | 144 | uint32_t length_group_name; |
akashvibhute | 0:30537dec6e0b | 145 | memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 146 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 147 | for(unsigned int k= offset; k< offset+length_group_name; ++k){ |
akashvibhute | 0:30537dec6e0b | 148 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 149 | } |
akashvibhute | 0:30537dec6e0b | 150 | inbuffer[offset+length_group_name-1]=0; |
akashvibhute | 0:30537dec6e0b | 151 | this->group_name = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 152 | offset += length_group_name; |
akashvibhute | 0:30537dec6e0b | 153 | uint32_t length_end_effector; |
akashvibhute | 0:30537dec6e0b | 154 | memcpy(&length_end_effector, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 155 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 156 | for(unsigned int k= offset; k< offset+length_end_effector; ++k){ |
akashvibhute | 0:30537dec6e0b | 157 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 158 | } |
akashvibhute | 0:30537dec6e0b | 159 | inbuffer[offset+length_end_effector-1]=0; |
akashvibhute | 0:30537dec6e0b | 160 | this->end_effector = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 161 | offset += length_end_effector; |
akashvibhute | 0:30537dec6e0b | 162 | uint8_t possible_grasps_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 163 | if(possible_grasps_lengthT > possible_grasps_length) |
akashvibhute | 0:30537dec6e0b | 164 | this->possible_grasps = (moveit_msgs::Grasp*)realloc(this->possible_grasps, possible_grasps_lengthT * sizeof(moveit_msgs::Grasp)); |
akashvibhute | 0:30537dec6e0b | 165 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 166 | possible_grasps_length = possible_grasps_lengthT; |
akashvibhute | 0:30537dec6e0b | 167 | for( uint8_t i = 0; i < possible_grasps_length; i++){ |
akashvibhute | 0:30537dec6e0b | 168 | offset += this->st_possible_grasps.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 169 | memcpy( &(this->possible_grasps[i]), &(this->st_possible_grasps), sizeof(moveit_msgs::Grasp)); |
akashvibhute | 0:30537dec6e0b | 170 | } |
akashvibhute | 0:30537dec6e0b | 171 | uint32_t length_support_surface_name; |
akashvibhute | 0:30537dec6e0b | 172 | memcpy(&length_support_surface_name, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 173 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 174 | for(unsigned int k= offset; k< offset+length_support_surface_name; ++k){ |
akashvibhute | 0:30537dec6e0b | 175 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 176 | } |
akashvibhute | 0:30537dec6e0b | 177 | inbuffer[offset+length_support_surface_name-1]=0; |
akashvibhute | 0:30537dec6e0b | 178 | this->support_surface_name = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 179 | offset += length_support_surface_name; |
akashvibhute | 0:30537dec6e0b | 180 | union { |
akashvibhute | 0:30537dec6e0b | 181 | bool real; |
akashvibhute | 0:30537dec6e0b | 182 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 183 | } u_allow_gripper_support_collision; |
akashvibhute | 0:30537dec6e0b | 184 | u_allow_gripper_support_collision.base = 0; |
akashvibhute | 0:30537dec6e0b | 185 | u_allow_gripper_support_collision.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 186 | this->allow_gripper_support_collision = u_allow_gripper_support_collision.real; |
akashvibhute | 0:30537dec6e0b | 187 | offset += sizeof(this->allow_gripper_support_collision); |
akashvibhute | 0:30537dec6e0b | 188 | uint8_t attached_object_touch_links_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 189 | if(attached_object_touch_links_lengthT > attached_object_touch_links_length) |
akashvibhute | 0:30537dec6e0b | 190 | this->attached_object_touch_links = (char**)realloc(this->attached_object_touch_links, attached_object_touch_links_lengthT * sizeof(char*)); |
akashvibhute | 0:30537dec6e0b | 191 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 192 | attached_object_touch_links_length = attached_object_touch_links_lengthT; |
akashvibhute | 0:30537dec6e0b | 193 | for( uint8_t i = 0; i < attached_object_touch_links_length; i++){ |
akashvibhute | 0:30537dec6e0b | 194 | uint32_t length_st_attached_object_touch_links; |
akashvibhute | 0:30537dec6e0b | 195 | memcpy(&length_st_attached_object_touch_links, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 196 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 197 | for(unsigned int k= offset; k< offset+length_st_attached_object_touch_links; ++k){ |
akashvibhute | 0:30537dec6e0b | 198 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 199 | } |
akashvibhute | 0:30537dec6e0b | 200 | inbuffer[offset+length_st_attached_object_touch_links-1]=0; |
akashvibhute | 0:30537dec6e0b | 201 | this->st_attached_object_touch_links = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 202 | offset += length_st_attached_object_touch_links; |
akashvibhute | 0:30537dec6e0b | 203 | memcpy( &(this->attached_object_touch_links[i]), &(this->st_attached_object_touch_links), sizeof(char*)); |
akashvibhute | 0:30537dec6e0b | 204 | } |
akashvibhute | 0:30537dec6e0b | 205 | union { |
akashvibhute | 0:30537dec6e0b | 206 | bool real; |
akashvibhute | 0:30537dec6e0b | 207 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 208 | } u_minimize_object_distance; |
akashvibhute | 0:30537dec6e0b | 209 | u_minimize_object_distance.base = 0; |
akashvibhute | 0:30537dec6e0b | 210 | u_minimize_object_distance.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 211 | this->minimize_object_distance = u_minimize_object_distance.real; |
akashvibhute | 0:30537dec6e0b | 212 | offset += sizeof(this->minimize_object_distance); |
akashvibhute | 0:30537dec6e0b | 213 | offset += this->path_constraints.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 214 | uint32_t length_planner_id; |
akashvibhute | 0:30537dec6e0b | 215 | memcpy(&length_planner_id, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 216 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 217 | for(unsigned int k= offset; k< offset+length_planner_id; ++k){ |
akashvibhute | 0:30537dec6e0b | 218 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 219 | } |
akashvibhute | 0:30537dec6e0b | 220 | inbuffer[offset+length_planner_id-1]=0; |
akashvibhute | 0:30537dec6e0b | 221 | this->planner_id = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 222 | offset += length_planner_id; |
akashvibhute | 0:30537dec6e0b | 223 | uint8_t allowed_touch_objects_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 224 | if(allowed_touch_objects_lengthT > allowed_touch_objects_length) |
akashvibhute | 0:30537dec6e0b | 225 | this->allowed_touch_objects = (char**)realloc(this->allowed_touch_objects, allowed_touch_objects_lengthT * sizeof(char*)); |
akashvibhute | 0:30537dec6e0b | 226 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 227 | allowed_touch_objects_length = allowed_touch_objects_lengthT; |
akashvibhute | 0:30537dec6e0b | 228 | for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ |
akashvibhute | 0:30537dec6e0b | 229 | uint32_t length_st_allowed_touch_objects; |
akashvibhute | 0:30537dec6e0b | 230 | memcpy(&length_st_allowed_touch_objects, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 231 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 232 | for(unsigned int k= offset; k< offset+length_st_allowed_touch_objects; ++k){ |
akashvibhute | 0:30537dec6e0b | 233 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 234 | } |
akashvibhute | 0:30537dec6e0b | 235 | inbuffer[offset+length_st_allowed_touch_objects-1]=0; |
akashvibhute | 0:30537dec6e0b | 236 | this->st_allowed_touch_objects = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 237 | offset += length_st_allowed_touch_objects; |
akashvibhute | 0:30537dec6e0b | 238 | memcpy( &(this->allowed_touch_objects[i]), &(this->st_allowed_touch_objects), sizeof(char*)); |
akashvibhute | 0:30537dec6e0b | 239 | } |
akashvibhute | 0:30537dec6e0b | 240 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->allowed_planning_time)); |
akashvibhute | 0:30537dec6e0b | 241 | offset += this->planning_options.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 242 | return offset; |
akashvibhute | 0:30537dec6e0b | 243 | } |
akashvibhute | 0:30537dec6e0b | 244 | |
akashvibhute | 0:30537dec6e0b | 245 | const char * getType(){ return "moveit_msgs/PickupGoal"; }; |
akashvibhute | 0:30537dec6e0b | 246 | const char * getMD5(){ return "458c6ab3761d73e99b070063f7b74c2a"; }; |
akashvibhute | 0:30537dec6e0b | 247 | |
akashvibhute | 0:30537dec6e0b | 248 | }; |
akashvibhute | 0:30537dec6e0b | 249 | |
akashvibhute | 0:30537dec6e0b | 250 | } |
akashvibhute | 0:30537dec6e0b | 251 | #endif |