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
RecognizedObject.h
00001 #ifndef _ROS_object_recognition_msgs_RecognizedObject_h 00002 #define _ROS_object_recognition_msgs_RecognizedObject_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "std_msgs/Header.h" 00009 #include "object_recognition_msgs/ObjectType.h" 00010 #include "sensor_msgs/PointCloud2.h" 00011 #include "shape_msgs/Mesh.h" 00012 #include "geometry_msgs/Point.h" 00013 #include "geometry_msgs/PoseWithCovarianceStamped.h" 00014 00015 namespace object_recognition_msgs 00016 { 00017 00018 class RecognizedObject : public ros::Msg 00019 { 00020 public: 00021 typedef std_msgs::Header _header_type; 00022 _header_type header; 00023 typedef object_recognition_msgs::ObjectType _type_type; 00024 _type_type type; 00025 typedef float _confidence_type; 00026 _confidence_type confidence; 00027 uint32_t point_clouds_length; 00028 typedef sensor_msgs::PointCloud2 _point_clouds_type; 00029 _point_clouds_type st_point_clouds; 00030 _point_clouds_type * point_clouds; 00031 typedef shape_msgs::Mesh _bounding_mesh_type; 00032 _bounding_mesh_type bounding_mesh; 00033 uint32_t bounding_contours_length; 00034 typedef geometry_msgs::Point _bounding_contours_type; 00035 _bounding_contours_type st_bounding_contours; 00036 _bounding_contours_type * bounding_contours; 00037 typedef geometry_msgs::PoseWithCovarianceStamped _pose_type; 00038 _pose_type pose; 00039 00040 RecognizedObject(): 00041 header(), 00042 type(), 00043 confidence(0), 00044 point_clouds_length(0), point_clouds(NULL), 00045 bounding_mesh(), 00046 bounding_contours_length(0), bounding_contours(NULL), 00047 pose() 00048 { 00049 } 00050 00051 virtual int serialize(unsigned char *outbuffer) const 00052 { 00053 int offset = 0; 00054 offset += this->header.serialize(outbuffer + offset); 00055 offset += this->type.serialize(outbuffer + offset); 00056 union { 00057 float real; 00058 uint32_t base; 00059 } u_confidence; 00060 u_confidence.real = this->confidence; 00061 *(outbuffer + offset + 0) = (u_confidence.base >> (8 * 0)) & 0xFF; 00062 *(outbuffer + offset + 1) = (u_confidence.base >> (8 * 1)) & 0xFF; 00063 *(outbuffer + offset + 2) = (u_confidence.base >> (8 * 2)) & 0xFF; 00064 *(outbuffer + offset + 3) = (u_confidence.base >> (8 * 3)) & 0xFF; 00065 offset += sizeof(this->confidence); 00066 *(outbuffer + offset + 0) = (this->point_clouds_length >> (8 * 0)) & 0xFF; 00067 *(outbuffer + offset + 1) = (this->point_clouds_length >> (8 * 1)) & 0xFF; 00068 *(outbuffer + offset + 2) = (this->point_clouds_length >> (8 * 2)) & 0xFF; 00069 *(outbuffer + offset + 3) = (this->point_clouds_length >> (8 * 3)) & 0xFF; 00070 offset += sizeof(this->point_clouds_length); 00071 for( uint32_t i = 0; i < point_clouds_length; i++){ 00072 offset += this->point_clouds[i].serialize(outbuffer + offset); 00073 } 00074 offset += this->bounding_mesh.serialize(outbuffer + offset); 00075 *(outbuffer + offset + 0) = (this->bounding_contours_length >> (8 * 0)) & 0xFF; 00076 *(outbuffer + offset + 1) = (this->bounding_contours_length >> (8 * 1)) & 0xFF; 00077 *(outbuffer + offset + 2) = (this->bounding_contours_length >> (8 * 2)) & 0xFF; 00078 *(outbuffer + offset + 3) = (this->bounding_contours_length >> (8 * 3)) & 0xFF; 00079 offset += sizeof(this->bounding_contours_length); 00080 for( uint32_t i = 0; i < bounding_contours_length; i++){ 00081 offset += this->bounding_contours[i].serialize(outbuffer + offset); 00082 } 00083 offset += this->pose.serialize(outbuffer + offset); 00084 return offset; 00085 } 00086 00087 virtual int deserialize(unsigned char *inbuffer) 00088 { 00089 int offset = 0; 00090 offset += this->header.deserialize(inbuffer + offset); 00091 offset += this->type.deserialize(inbuffer + offset); 00092 union { 00093 float real; 00094 uint32_t base; 00095 } u_confidence; 00096 u_confidence.base = 0; 00097 u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00098 u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00099 u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00100 u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00101 this->confidence = u_confidence.real; 00102 offset += sizeof(this->confidence); 00103 uint32_t point_clouds_lengthT = ((uint32_t) (*(inbuffer + offset))); 00104 point_clouds_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00105 point_clouds_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00106 point_clouds_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00107 offset += sizeof(this->point_clouds_length); 00108 if(point_clouds_lengthT > point_clouds_length) 00109 this->point_clouds = (sensor_msgs::PointCloud2*)realloc(this->point_clouds, point_clouds_lengthT * sizeof(sensor_msgs::PointCloud2)); 00110 point_clouds_length = point_clouds_lengthT; 00111 for( uint32_t i = 0; i < point_clouds_length; i++){ 00112 offset += this->st_point_clouds.deserialize(inbuffer + offset); 00113 memcpy( &(this->point_clouds[i]), &(this->st_point_clouds), sizeof(sensor_msgs::PointCloud2)); 00114 } 00115 offset += this->bounding_mesh.deserialize(inbuffer + offset); 00116 uint32_t bounding_contours_lengthT = ((uint32_t) (*(inbuffer + offset))); 00117 bounding_contours_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00118 bounding_contours_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00119 bounding_contours_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00120 offset += sizeof(this->bounding_contours_length); 00121 if(bounding_contours_lengthT > bounding_contours_length) 00122 this->bounding_contours = (geometry_msgs::Point*)realloc(this->bounding_contours, bounding_contours_lengthT * sizeof(geometry_msgs::Point)); 00123 bounding_contours_length = bounding_contours_lengthT; 00124 for( uint32_t i = 0; i < bounding_contours_length; i++){ 00125 offset += this->st_bounding_contours.deserialize(inbuffer + offset); 00126 memcpy( &(this->bounding_contours[i]), &(this->st_bounding_contours), sizeof(geometry_msgs::Point)); 00127 } 00128 offset += this->pose.deserialize(inbuffer + offset); 00129 return offset; 00130 } 00131 00132 virtual const char * getType(){ return "object_recognition_msgs/RecognizedObject"; }; 00133 virtual const char * getMD5(){ return "f92c4cb29ba11f26c5f7219de97e900d"; }; 00134 00135 }; 00136 00137 } 00138 #endif
Generated on Mon Sep 26 2022 13:47:03 by
