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
ICPResult.h
00001 #ifndef _ROS_jsk_recognition_msgs_ICPResult_h 00002 #define _ROS_jsk_recognition_msgs_ICPResult_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/Pose.h" 00010 00011 namespace jsk_recognition_msgs 00012 { 00013 00014 class ICPResult : public ros::Msg 00015 { 00016 public: 00017 typedef std_msgs::Header _header_type; 00018 _header_type header; 00019 typedef geometry_msgs::Pose _pose_type; 00020 _pose_type pose; 00021 typedef const char* _name_type; 00022 _name_type name; 00023 typedef double _score_type; 00024 _score_type score; 00025 00026 ICPResult(): 00027 header(), 00028 pose(), 00029 name(""), 00030 score(0) 00031 { 00032 } 00033 00034 virtual int serialize(unsigned char *outbuffer) const 00035 { 00036 int offset = 0; 00037 offset += this->header.serialize(outbuffer + offset); 00038 offset += this->pose.serialize(outbuffer + offset); 00039 uint32_t length_name = strlen(this->name); 00040 varToArr(outbuffer + offset, length_name); 00041 offset += 4; 00042 memcpy(outbuffer + offset, this->name, length_name); 00043 offset += length_name; 00044 union { 00045 double real; 00046 uint64_t base; 00047 } u_score; 00048 u_score.real = this->score; 00049 *(outbuffer + offset + 0) = (u_score.base >> (8 * 0)) & 0xFF; 00050 *(outbuffer + offset + 1) = (u_score.base >> (8 * 1)) & 0xFF; 00051 *(outbuffer + offset + 2) = (u_score.base >> (8 * 2)) & 0xFF; 00052 *(outbuffer + offset + 3) = (u_score.base >> (8 * 3)) & 0xFF; 00053 *(outbuffer + offset + 4) = (u_score.base >> (8 * 4)) & 0xFF; 00054 *(outbuffer + offset + 5) = (u_score.base >> (8 * 5)) & 0xFF; 00055 *(outbuffer + offset + 6) = (u_score.base >> (8 * 6)) & 0xFF; 00056 *(outbuffer + offset + 7) = (u_score.base >> (8 * 7)) & 0xFF; 00057 offset += sizeof(this->score); 00058 return offset; 00059 } 00060 00061 virtual int deserialize(unsigned char *inbuffer) 00062 { 00063 int offset = 0; 00064 offset += this->header.deserialize(inbuffer + offset); 00065 offset += this->pose.deserialize(inbuffer + offset); 00066 uint32_t length_name; 00067 arrToVar(length_name, (inbuffer + offset)); 00068 offset += 4; 00069 for(unsigned int k= offset; k< offset+length_name; ++k){ 00070 inbuffer[k-1]=inbuffer[k]; 00071 } 00072 inbuffer[offset+length_name-1]=0; 00073 this->name = (char *)(inbuffer + offset-1); 00074 offset += length_name; 00075 union { 00076 double real; 00077 uint64_t base; 00078 } u_score; 00079 u_score.base = 0; 00080 u_score.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00081 u_score.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00082 u_score.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00083 u_score.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00084 u_score.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00085 u_score.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00086 u_score.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00087 u_score.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00088 this->score = u_score.real; 00089 offset += sizeof(this->score); 00090 return offset; 00091 } 00092 00093 virtual const char * getType(){ return "jsk_recognition_msgs/ICPResult"; }; 00094 virtual const char * getMD5(){ return "2d0f1279ba6f378fd67c4a0324acf2d7"; }; 00095 00096 }; 00097 00098 } 00099 #endif
Generated on Mon Sep 26 2022 13:47:01 by
