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
SaveMesh.h
00001 #ifndef _ROS_SERVICE_SaveMesh_h 00002 #define _ROS_SERVICE_SaveMesh_h 00003 #include <stdint.h> 00004 #include <string.h> 00005 #include <stdlib.h> 00006 #include "ros/msg.h" 00007 #include "jsk_recognition_msgs/BoundingBox.h" 00008 00009 namespace jsk_recognition_msgs 00010 { 00011 00012 static const char SAVEMESH[] = "jsk_recognition_msgs/SaveMesh"; 00013 00014 class SaveMeshRequest : public ros::Msg 00015 { 00016 public: 00017 typedef const char* _ground_frame_id_type; 00018 _ground_frame_id_type ground_frame_id; 00019 typedef jsk_recognition_msgs::BoundingBox _box_type; 00020 _box_type box; 00021 00022 SaveMeshRequest(): 00023 ground_frame_id(""), 00024 box() 00025 { 00026 } 00027 00028 virtual int serialize(unsigned char *outbuffer) const 00029 { 00030 int offset = 0; 00031 uint32_t length_ground_frame_id = strlen(this->ground_frame_id); 00032 varToArr(outbuffer + offset, length_ground_frame_id); 00033 offset += 4; 00034 memcpy(outbuffer + offset, this->ground_frame_id, length_ground_frame_id); 00035 offset += length_ground_frame_id; 00036 offset += this->box.serialize(outbuffer + offset); 00037 return offset; 00038 } 00039 00040 virtual int deserialize(unsigned char *inbuffer) 00041 { 00042 int offset = 0; 00043 uint32_t length_ground_frame_id; 00044 arrToVar(length_ground_frame_id, (inbuffer + offset)); 00045 offset += 4; 00046 for(unsigned int k= offset; k< offset+length_ground_frame_id; ++k){ 00047 inbuffer[k-1]=inbuffer[k]; 00048 } 00049 inbuffer[offset+length_ground_frame_id-1]=0; 00050 this->ground_frame_id = (char *)(inbuffer + offset-1); 00051 offset += length_ground_frame_id; 00052 offset += this->box.deserialize(inbuffer + offset); 00053 return offset; 00054 } 00055 00056 virtual const char * getType(){ return SAVEMESH; }; 00057 virtual const char * getMD5(){ return "aedbb75b25dc1f22d6170286e35b1132"; }; 00058 00059 }; 00060 00061 class SaveMeshResponse : public ros::Msg 00062 { 00063 public: 00064 typedef bool _success_type; 00065 _success_type success; 00066 00067 SaveMeshResponse(): 00068 success(0) 00069 { 00070 } 00071 00072 virtual int serialize(unsigned char *outbuffer) const 00073 { 00074 int offset = 0; 00075 union { 00076 bool real; 00077 uint8_t base; 00078 } u_success; 00079 u_success.real = this->success; 00080 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; 00081 offset += sizeof(this->success); 00082 return offset; 00083 } 00084 00085 virtual int deserialize(unsigned char *inbuffer) 00086 { 00087 int offset = 0; 00088 union { 00089 bool real; 00090 uint8_t base; 00091 } u_success; 00092 u_success.base = 0; 00093 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00094 this->success = u_success.real; 00095 offset += sizeof(this->success); 00096 return offset; 00097 } 00098 00099 virtual const char * getType(){ return SAVEMESH; }; 00100 virtual const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; }; 00101 00102 }; 00103 00104 class SaveMesh { 00105 public: 00106 typedef SaveMeshRequest Request; 00107 typedef SaveMeshResponse Response; 00108 }; 00109 00110 } 00111 #endif
Generated on Mon Sep 26 2022 13:47:03 by
