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.
Dependents: rosserial_mbed robot_S2
std_msgs/Float32MultiArray.h@0:77afd7560544, 2011-08-19 (annotated)
- Committer:
- nucho
- Date:
- Fri Aug 19 09:06:30 2011 +0000
- Revision:
- 0:77afd7560544
- Child:
- 1:ff0ec969dad1
Who changed what in which revision?
| User | Revision | Line number | New contents of line |
|---|---|---|---|
| nucho | 0:77afd7560544 | 1 | #ifndef ros_Float32MultiArray_h |
| nucho | 0:77afd7560544 | 2 | #define ros_Float32MultiArray_h |
| nucho | 0:77afd7560544 | 3 | |
| nucho | 0:77afd7560544 | 4 | #include <stdint.h> |
| nucho | 0:77afd7560544 | 5 | #include <string.h> |
| nucho | 0:77afd7560544 | 6 | #include <stdlib.h> |
| nucho | 0:77afd7560544 | 7 | #include "../ros/msg.h" |
| nucho | 0:77afd7560544 | 8 | #include "std_msgs/MultiArrayLayout.h" |
| nucho | 0:77afd7560544 | 9 | |
| nucho | 0:77afd7560544 | 10 | namespace std_msgs |
| nucho | 0:77afd7560544 | 11 | { |
| nucho | 0:77afd7560544 | 12 | |
| nucho | 0:77afd7560544 | 13 | class Float32MultiArray : public ros::Msg |
| nucho | 0:77afd7560544 | 14 | { |
| nucho | 0:77afd7560544 | 15 | public: |
| nucho | 0:77afd7560544 | 16 | std_msgs::MultiArrayLayout layout; |
| nucho | 0:77afd7560544 | 17 | unsigned char data_length; |
| nucho | 0:77afd7560544 | 18 | float st_data; |
| nucho | 0:77afd7560544 | 19 | float * data; |
| nucho | 0:77afd7560544 | 20 | |
| nucho | 0:77afd7560544 | 21 | virtual int serialize(unsigned char *outbuffer) |
| nucho | 0:77afd7560544 | 22 | { |
| nucho | 0:77afd7560544 | 23 | int offset = 0; |
| nucho | 0:77afd7560544 | 24 | offset += this->layout.serialize(outbuffer + offset); |
| nucho | 0:77afd7560544 | 25 | *(outbuffer + offset++) = data_length; |
| nucho | 0:77afd7560544 | 26 | *(outbuffer + offset++) = 0; |
| nucho | 0:77afd7560544 | 27 | *(outbuffer + offset++) = 0; |
| nucho | 0:77afd7560544 | 28 | *(outbuffer + offset++) = 0; |
| nucho | 0:77afd7560544 | 29 | for( unsigned char i = 0; i < data_length; i++){ |
| nucho | 0:77afd7560544 | 30 | union { |
| nucho | 0:77afd7560544 | 31 | float real; |
| nucho | 0:77afd7560544 | 32 | unsigned long base; |
| nucho | 0:77afd7560544 | 33 | } u_datai; |
| nucho | 0:77afd7560544 | 34 | u_datai.real = this->data[i]; |
| nucho | 0:77afd7560544 | 35 | *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; |
| nucho | 0:77afd7560544 | 36 | *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; |
| nucho | 0:77afd7560544 | 37 | *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; |
| nucho | 0:77afd7560544 | 38 | *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; |
| nucho | 0:77afd7560544 | 39 | offset += sizeof(this->data[i]); |
| nucho | 0:77afd7560544 | 40 | } |
| nucho | 0:77afd7560544 | 41 | return offset; |
| nucho | 0:77afd7560544 | 42 | } |
| nucho | 0:77afd7560544 | 43 | |
| nucho | 0:77afd7560544 | 44 | virtual int deserialize(unsigned char *inbuffer) |
| nucho | 0:77afd7560544 | 45 | { |
| nucho | 0:77afd7560544 | 46 | int offset = 0; |
| nucho | 0:77afd7560544 | 47 | offset += this->layout.deserialize(inbuffer + offset); |
| nucho | 0:77afd7560544 | 48 | unsigned char data_lengthT = *(inbuffer + offset++); |
| nucho | 0:77afd7560544 | 49 | if(data_lengthT > data_length) |
| nucho | 0:77afd7560544 | 50 | this->data = (float*)realloc(this->data, data_lengthT * sizeof(float)); |
| nucho | 0:77afd7560544 | 51 | offset += 3; |
| nucho | 0:77afd7560544 | 52 | data_length = data_lengthT; |
| nucho | 0:77afd7560544 | 53 | for( unsigned char i = 0; i < data_length; i++){ |
| nucho | 0:77afd7560544 | 54 | union { |
| nucho | 0:77afd7560544 | 55 | float real; |
| nucho | 0:77afd7560544 | 56 | unsigned long base; |
| nucho | 0:77afd7560544 | 57 | } u_st_data; |
| nucho | 0:77afd7560544 | 58 | u_st_data.base = 0; |
| nucho | 0:77afd7560544 | 59 | u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0); |
| nucho | 0:77afd7560544 | 60 | u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 1))) << (8 * 1); |
| nucho | 0:77afd7560544 | 61 | u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 2))) << (8 * 2); |
| nucho | 0:77afd7560544 | 62 | u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 3))) << (8 * 3); |
| nucho | 0:77afd7560544 | 63 | this->st_data = u_st_data.real; |
| nucho | 0:77afd7560544 | 64 | offset += sizeof(this->st_data); |
| nucho | 0:77afd7560544 | 65 | memcpy( &(this->data[i]), &(this->st_data), sizeof(float)); |
| nucho | 0:77afd7560544 | 66 | } |
| nucho | 0:77afd7560544 | 67 | return offset; |
| nucho | 0:77afd7560544 | 68 | } |
| nucho | 0:77afd7560544 | 69 | |
| nucho | 0:77afd7560544 | 70 | virtual const char * getType(){ return "std_msgs/Float32MultiArray"; }; |
| nucho | 0:77afd7560544 | 71 | |
| nucho | 0:77afd7560544 | 72 | }; |
| nucho | 0:77afd7560544 | 73 | |
| nucho | 0:77afd7560544 | 74 | } |
| nucho | 0:77afd7560544 | 75 | #endif |