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.
ChannelFloat32.h
00001 #ifndef _ROS_sensor_msgs_ChannelFloat32_h 00002 #define _ROS_sensor_msgs_ChannelFloat32_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 00009 namespace sensor_msgs 00010 { 00011 00012 class ChannelFloat32 : public ros::Msg 00013 { 00014 public: 00015 typedef const char* _name_type; 00016 _name_type name; 00017 uint32_t values_length; 00018 typedef float _values_type; 00019 _values_type st_values; 00020 _values_type * values; 00021 00022 ChannelFloat32(): 00023 name(""), 00024 values_length(0), values(NULL) 00025 { 00026 } 00027 00028 virtual int serialize(unsigned char *outbuffer) const 00029 { 00030 int offset = 0; 00031 uint32_t length_name = strlen(this->name); 00032 varToArr(outbuffer + offset, length_name); 00033 offset += 4; 00034 memcpy(outbuffer + offset, this->name, length_name); 00035 offset += length_name; 00036 *(outbuffer + offset + 0) = (this->values_length >> (8 * 0)) & 0xFF; 00037 *(outbuffer + offset + 1) = (this->values_length >> (8 * 1)) & 0xFF; 00038 *(outbuffer + offset + 2) = (this->values_length >> (8 * 2)) & 0xFF; 00039 *(outbuffer + offset + 3) = (this->values_length >> (8 * 3)) & 0xFF; 00040 offset += sizeof(this->values_length); 00041 for( uint32_t i = 0; i < values_length; i++){ 00042 union { 00043 float real; 00044 uint32_t base; 00045 } u_valuesi; 00046 u_valuesi.real = this->values[i]; 00047 *(outbuffer + offset + 0) = (u_valuesi.base >> (8 * 0)) & 0xFF; 00048 *(outbuffer + offset + 1) = (u_valuesi.base >> (8 * 1)) & 0xFF; 00049 *(outbuffer + offset + 2) = (u_valuesi.base >> (8 * 2)) & 0xFF; 00050 *(outbuffer + offset + 3) = (u_valuesi.base >> (8 * 3)) & 0xFF; 00051 offset += sizeof(this->values[i]); 00052 } 00053 return offset; 00054 } 00055 00056 virtual int deserialize(unsigned char *inbuffer) 00057 { 00058 int offset = 0; 00059 uint32_t length_name; 00060 arrToVar(length_name, (inbuffer + offset)); 00061 offset += 4; 00062 for(unsigned int k= offset; k< offset+length_name; ++k){ 00063 inbuffer[k-1]=inbuffer[k]; 00064 } 00065 inbuffer[offset+length_name-1]=0; 00066 this->name = (char *)(inbuffer + offset-1); 00067 offset += length_name; 00068 uint32_t values_lengthT = ((uint32_t) (*(inbuffer + offset))); 00069 values_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00070 values_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00071 values_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00072 offset += sizeof(this->values_length); 00073 if(values_lengthT > values_length) 00074 this->values = (float*)realloc(this->values, values_lengthT * sizeof(float)); 00075 values_length = values_lengthT; 00076 for( uint32_t i = 0; i < values_length; i++){ 00077 union { 00078 float real; 00079 uint32_t base; 00080 } u_st_values; 00081 u_st_values.base = 0; 00082 u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00083 u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00084 u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00085 u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00086 this->st_values = u_st_values.real; 00087 offset += sizeof(this->st_values); 00088 memcpy( &(this->values[i]), &(this->st_values), sizeof(float)); 00089 } 00090 return offset; 00091 } 00092 00093 const char * getType(){ return "sensor_msgs/ChannelFloat32"; }; 00094 const char * getMD5(){ return "3d40139cdd33dfedcb71ffeeeb42ae7f"; }; 00095 00096 }; 00097 00098 } 00099 #endif
Generated on Tue Jul 12 2022 17:32:44 by
