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.
Fork of rosserial_mbed_lib by
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 char * name; 00016 uint8_t values_length; 00017 float st_values; 00018 float * values; 00019 00020 virtual int serialize(unsigned char *outbuffer) const 00021 { 00022 int offset = 0; 00023 uint32_t * length_name = (uint32_t *)(outbuffer + offset); 00024 *length_name = strlen( (const char*) this->name); 00025 offset += 4; 00026 memcpy(outbuffer + offset, this->name, *length_name); 00027 offset += *length_name; 00028 *(outbuffer + offset++) = values_length; 00029 *(outbuffer + offset++) = 0; 00030 *(outbuffer + offset++) = 0; 00031 *(outbuffer + offset++) = 0; 00032 for( uint8_t i = 0; i < values_length; i++){ 00033 union { 00034 float real; 00035 uint32_t base; 00036 } u_valuesi; 00037 u_valuesi.real = this->values[i]; 00038 *(outbuffer + offset + 0) = (u_valuesi.base >> (8 * 0)) & 0xFF; 00039 *(outbuffer + offset + 1) = (u_valuesi.base >> (8 * 1)) & 0xFF; 00040 *(outbuffer + offset + 2) = (u_valuesi.base >> (8 * 2)) & 0xFF; 00041 *(outbuffer + offset + 3) = (u_valuesi.base >> (8 * 3)) & 0xFF; 00042 offset += sizeof(this->values[i]); 00043 } 00044 return offset; 00045 } 00046 00047 virtual int deserialize(unsigned char *inbuffer) 00048 { 00049 int offset = 0; 00050 uint32_t length_name = *(uint32_t *)(inbuffer + offset); 00051 offset += 4; 00052 for(unsigned int k= offset; k< offset+length_name; ++k){ 00053 inbuffer[k-1]=inbuffer[k]; 00054 } 00055 inbuffer[offset+length_name-1]=0; 00056 this->name = (char *)(inbuffer + offset-1); 00057 offset += length_name; 00058 uint8_t values_lengthT = *(inbuffer + offset++); 00059 if(values_lengthT > values_length) 00060 this->values = (float*)realloc(this->values, values_lengthT * sizeof(float)); 00061 offset += 3; 00062 values_length = values_lengthT; 00063 for( uint8_t i = 0; i < values_length; i++){ 00064 union { 00065 float real; 00066 uint32_t base; 00067 } u_st_values; 00068 u_st_values.base = 0; 00069 u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00070 u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00071 u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00072 u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00073 this->st_values = u_st_values.real; 00074 offset += sizeof(this->st_values); 00075 memcpy( &(this->values[i]), &(this->st_values), sizeof(float)); 00076 } 00077 return offset; 00078 } 00079 00080 virtual const char * getType(){ return "sensor_msgs/ChannelFloat32"; }; 00081 virtual const char * getMD5(){ return "3d40139cdd33dfedcb71ffeeeb42ae7f"; }; 00082 00083 }; 00084 00085 } 00086 #endif
Generated on Tue Jul 12 2022 19:53:56 by
 1.7.2
 1.7.2 
    