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
PlaceLocation.h
00001 #ifndef _ROS_moveit_msgs_PlaceLocation_h 00002 #define _ROS_moveit_msgs_PlaceLocation_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "trajectory_msgs/JointTrajectory.h" 00009 #include "geometry_msgs/PoseStamped.h" 00010 #include "moveit_msgs/GripperTranslation.h" 00011 00012 namespace moveit_msgs 00013 { 00014 00015 class PlaceLocation : public ros::Msg 00016 { 00017 public: 00018 typedef const char* _id_type; 00019 _id_type id; 00020 typedef trajectory_msgs::JointTrajectory _post_place_posture_type; 00021 _post_place_posture_type post_place_posture; 00022 typedef geometry_msgs::PoseStamped _place_pose_type; 00023 _place_pose_type place_pose; 00024 typedef moveit_msgs::GripperTranslation _pre_place_approach_type; 00025 _pre_place_approach_type pre_place_approach; 00026 typedef moveit_msgs::GripperTranslation _post_place_retreat_type; 00027 _post_place_retreat_type post_place_retreat; 00028 uint32_t allowed_touch_objects_length; 00029 typedef char* _allowed_touch_objects_type; 00030 _allowed_touch_objects_type st_allowed_touch_objects; 00031 _allowed_touch_objects_type * allowed_touch_objects; 00032 00033 PlaceLocation(): 00034 id(""), 00035 post_place_posture(), 00036 place_pose(), 00037 pre_place_approach(), 00038 post_place_retreat(), 00039 allowed_touch_objects_length(0), allowed_touch_objects(NULL) 00040 { 00041 } 00042 00043 virtual int serialize(unsigned char *outbuffer) const 00044 { 00045 int offset = 0; 00046 uint32_t length_id = strlen(this->id); 00047 varToArr(outbuffer + offset, length_id); 00048 offset += 4; 00049 memcpy(outbuffer + offset, this->id, length_id); 00050 offset += length_id; 00051 offset += this->post_place_posture.serialize(outbuffer + offset); 00052 offset += this->place_pose.serialize(outbuffer + offset); 00053 offset += this->pre_place_approach.serialize(outbuffer + offset); 00054 offset += this->post_place_retreat.serialize(outbuffer + offset); 00055 *(outbuffer + offset + 0) = (this->allowed_touch_objects_length >> (8 * 0)) & 0xFF; 00056 *(outbuffer + offset + 1) = (this->allowed_touch_objects_length >> (8 * 1)) & 0xFF; 00057 *(outbuffer + offset + 2) = (this->allowed_touch_objects_length >> (8 * 2)) & 0xFF; 00058 *(outbuffer + offset + 3) = (this->allowed_touch_objects_length >> (8 * 3)) & 0xFF; 00059 offset += sizeof(this->allowed_touch_objects_length); 00060 for( uint32_t i = 0; i < allowed_touch_objects_length; i++){ 00061 uint32_t length_allowed_touch_objectsi = strlen(this->allowed_touch_objects[i]); 00062 varToArr(outbuffer + offset, length_allowed_touch_objectsi); 00063 offset += 4; 00064 memcpy(outbuffer + offset, this->allowed_touch_objects[i], length_allowed_touch_objectsi); 00065 offset += length_allowed_touch_objectsi; 00066 } 00067 return offset; 00068 } 00069 00070 virtual int deserialize(unsigned char *inbuffer) 00071 { 00072 int offset = 0; 00073 uint32_t length_id; 00074 arrToVar(length_id, (inbuffer + offset)); 00075 offset += 4; 00076 for(unsigned int k= offset; k< offset+length_id; ++k){ 00077 inbuffer[k-1]=inbuffer[k]; 00078 } 00079 inbuffer[offset+length_id-1]=0; 00080 this->id = (char *)(inbuffer + offset-1); 00081 offset += length_id; 00082 offset += this->post_place_posture.deserialize(inbuffer + offset); 00083 offset += this->place_pose.deserialize(inbuffer + offset); 00084 offset += this->pre_place_approach.deserialize(inbuffer + offset); 00085 offset += this->post_place_retreat.deserialize(inbuffer + offset); 00086 uint32_t allowed_touch_objects_lengthT = ((uint32_t) (*(inbuffer + offset))); 00087 allowed_touch_objects_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00088 allowed_touch_objects_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00089 allowed_touch_objects_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00090 offset += sizeof(this->allowed_touch_objects_length); 00091 if(allowed_touch_objects_lengthT > allowed_touch_objects_length) 00092 this->allowed_touch_objects = (char**)realloc(this->allowed_touch_objects, allowed_touch_objects_lengthT * sizeof(char*)); 00093 allowed_touch_objects_length = allowed_touch_objects_lengthT; 00094 for( uint32_t i = 0; i < allowed_touch_objects_length; i++){ 00095 uint32_t length_st_allowed_touch_objects; 00096 arrToVar(length_st_allowed_touch_objects, (inbuffer + offset)); 00097 offset += 4; 00098 for(unsigned int k= offset; k< offset+length_st_allowed_touch_objects; ++k){ 00099 inbuffer[k-1]=inbuffer[k]; 00100 } 00101 inbuffer[offset+length_st_allowed_touch_objects-1]=0; 00102 this->st_allowed_touch_objects = (char *)(inbuffer + offset-1); 00103 offset += length_st_allowed_touch_objects; 00104 memcpy( &(this->allowed_touch_objects[i]), &(this->st_allowed_touch_objects), sizeof(char*)); 00105 } 00106 return offset; 00107 } 00108 00109 virtual const char * getType(){ return "moveit_msgs/PlaceLocation"; }; 00110 virtual const char * getMD5(){ return "f3dbcaca40fb29ede2af78b3e1831128"; }; 00111 00112 }; 00113 00114 } 00115 #endif
Generated on Mon Sep 26 2022 13:47:02 by
