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
EuclideanSegment.h
00001 #ifndef _ROS_SERVICE_EuclideanSegment_h 00002 #define _ROS_SERVICE_EuclideanSegment_h 00003 #include <stdint.h> 00004 #include <string.h> 00005 #include <stdlib.h> 00006 #include "ros/msg.h" 00007 #include "sensor_msgs/PointCloud2.h" 00008 00009 namespace jsk_recognition_msgs 00010 { 00011 00012 static const char EUCLIDEANSEGMENT[] = "jsk_recognition_msgs/EuclideanSegment"; 00013 00014 class EuclideanSegmentRequest : public ros::Msg 00015 { 00016 public: 00017 typedef sensor_msgs::PointCloud2 _input_type; 00018 _input_type input; 00019 typedef float _tolerance_type; 00020 _tolerance_type tolerance; 00021 00022 EuclideanSegmentRequest(): 00023 input(), 00024 tolerance(0) 00025 { 00026 } 00027 00028 virtual int serialize(unsigned char *outbuffer) const 00029 { 00030 int offset = 0; 00031 offset += this->input.serialize(outbuffer + offset); 00032 union { 00033 float real; 00034 uint32_t base; 00035 } u_tolerance; 00036 u_tolerance.real = this->tolerance; 00037 *(outbuffer + offset + 0) = (u_tolerance.base >> (8 * 0)) & 0xFF; 00038 *(outbuffer + offset + 1) = (u_tolerance.base >> (8 * 1)) & 0xFF; 00039 *(outbuffer + offset + 2) = (u_tolerance.base >> (8 * 2)) & 0xFF; 00040 *(outbuffer + offset + 3) = (u_tolerance.base >> (8 * 3)) & 0xFF; 00041 offset += sizeof(this->tolerance); 00042 return offset; 00043 } 00044 00045 virtual int deserialize(unsigned char *inbuffer) 00046 { 00047 int offset = 0; 00048 offset += this->input.deserialize(inbuffer + offset); 00049 union { 00050 float real; 00051 uint32_t base; 00052 } u_tolerance; 00053 u_tolerance.base = 0; 00054 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00055 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00056 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00057 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00058 this->tolerance = u_tolerance.real; 00059 offset += sizeof(this->tolerance); 00060 return offset; 00061 } 00062 00063 virtual const char * getType(){ return EUCLIDEANSEGMENT; }; 00064 virtual const char * getMD5(){ return "116dd66bdc82f46d7b7414ce880ea794"; }; 00065 00066 }; 00067 00068 class EuclideanSegmentResponse : public ros::Msg 00069 { 00070 public: 00071 uint32_t output_length; 00072 typedef sensor_msgs::PointCloud2 _output_type; 00073 _output_type st_output; 00074 _output_type * output; 00075 00076 EuclideanSegmentResponse(): 00077 output_length(0), output(NULL) 00078 { 00079 } 00080 00081 virtual int serialize(unsigned char *outbuffer) const 00082 { 00083 int offset = 0; 00084 *(outbuffer + offset + 0) = (this->output_length >> (8 * 0)) & 0xFF; 00085 *(outbuffer + offset + 1) = (this->output_length >> (8 * 1)) & 0xFF; 00086 *(outbuffer + offset + 2) = (this->output_length >> (8 * 2)) & 0xFF; 00087 *(outbuffer + offset + 3) = (this->output_length >> (8 * 3)) & 0xFF; 00088 offset += sizeof(this->output_length); 00089 for( uint32_t i = 0; i < output_length; i++){ 00090 offset += this->output[i].serialize(outbuffer + offset); 00091 } 00092 return offset; 00093 } 00094 00095 virtual int deserialize(unsigned char *inbuffer) 00096 { 00097 int offset = 0; 00098 uint32_t output_lengthT = ((uint32_t) (*(inbuffer + offset))); 00099 output_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00100 output_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00101 output_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00102 offset += sizeof(this->output_length); 00103 if(output_lengthT > output_length) 00104 this->output = (sensor_msgs::PointCloud2*)realloc(this->output, output_lengthT * sizeof(sensor_msgs::PointCloud2)); 00105 output_length = output_lengthT; 00106 for( uint32_t i = 0; i < output_length; i++){ 00107 offset += this->st_output.deserialize(inbuffer + offset); 00108 memcpy( &(this->output[i]), &(this->st_output), sizeof(sensor_msgs::PointCloud2)); 00109 } 00110 return offset; 00111 } 00112 00113 virtual const char * getType(){ return EUCLIDEANSEGMENT; }; 00114 virtual const char * getMD5(){ return "6db5ac8d8316fdb3e0c62197115f87cd"; }; 00115 00116 }; 00117 00118 class EuclideanSegment { 00119 public: 00120 typedef EuclideanSegmentRequest Request; 00121 typedef EuclideanSegmentResponse Response; 00122 }; 00123 00124 } 00125 #endif
Generated on Mon Sep 26 2022 13:47:00 by
