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
WeightedPoseArray.h
00001 #ifndef _ROS_jsk_recognition_msgs_WeightedPoseArray_h 00002 #define _ROS_jsk_recognition_msgs_WeightedPoseArray_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 "geometry_msgs/PoseArray.h" 00010 00011 namespace jsk_recognition_msgs 00012 { 00013 00014 class WeightedPoseArray : public ros::Msg 00015 { 00016 public: 00017 typedef std_msgs::Header _header_type; 00018 _header_type header; 00019 uint32_t weights_length; 00020 typedef float _weights_type; 00021 _weights_type st_weights; 00022 _weights_type * weights; 00023 typedef geometry_msgs::PoseArray _poses_type; 00024 _poses_type poses; 00025 00026 WeightedPoseArray(): 00027 header(), 00028 weights_length(0), weights(NULL), 00029 poses() 00030 { 00031 } 00032 00033 virtual int serialize(unsigned char *outbuffer) const 00034 { 00035 int offset = 0; 00036 offset += this->header.serialize(outbuffer + offset); 00037 *(outbuffer + offset + 0) = (this->weights_length >> (8 * 0)) & 0xFF; 00038 *(outbuffer + offset + 1) = (this->weights_length >> (8 * 1)) & 0xFF; 00039 *(outbuffer + offset + 2) = (this->weights_length >> (8 * 2)) & 0xFF; 00040 *(outbuffer + offset + 3) = (this->weights_length >> (8 * 3)) & 0xFF; 00041 offset += sizeof(this->weights_length); 00042 for( uint32_t i = 0; i < weights_length; i++){ 00043 union { 00044 float real; 00045 uint32_t base; 00046 } u_weightsi; 00047 u_weightsi.real = this->weights[i]; 00048 *(outbuffer + offset + 0) = (u_weightsi.base >> (8 * 0)) & 0xFF; 00049 *(outbuffer + offset + 1) = (u_weightsi.base >> (8 * 1)) & 0xFF; 00050 *(outbuffer + offset + 2) = (u_weightsi.base >> (8 * 2)) & 0xFF; 00051 *(outbuffer + offset + 3) = (u_weightsi.base >> (8 * 3)) & 0xFF; 00052 offset += sizeof(this->weights[i]); 00053 } 00054 offset += this->poses.serialize(outbuffer + offset); 00055 return offset; 00056 } 00057 00058 virtual int deserialize(unsigned char *inbuffer) 00059 { 00060 int offset = 0; 00061 offset += this->header.deserialize(inbuffer + offset); 00062 uint32_t weights_lengthT = ((uint32_t) (*(inbuffer + offset))); 00063 weights_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00064 weights_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00065 weights_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00066 offset += sizeof(this->weights_length); 00067 if(weights_lengthT > weights_length) 00068 this->weights = (float*)realloc(this->weights, weights_lengthT * sizeof(float)); 00069 weights_length = weights_lengthT; 00070 for( uint32_t i = 0; i < weights_length; i++){ 00071 union { 00072 float real; 00073 uint32_t base; 00074 } u_st_weights; 00075 u_st_weights.base = 0; 00076 u_st_weights.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00077 u_st_weights.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00078 u_st_weights.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00079 u_st_weights.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00080 this->st_weights = u_st_weights.real; 00081 offset += sizeof(this->st_weights); 00082 memcpy( &(this->weights[i]), &(this->st_weights), sizeof(float)); 00083 } 00084 offset += this->poses.deserialize(inbuffer + offset); 00085 return offset; 00086 } 00087 00088 virtual const char * getType(){ return "jsk_recognition_msgs/WeightedPoseArray"; }; 00089 virtual const char * getMD5(){ return "40f180494a75a8797b1c2ba81b2cb4c0"; }; 00090 00091 }; 00092 00093 } 00094 #endif
Generated on Mon Sep 26 2022 13:47:04 by
