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
Diff: sensor_msgs/PointCloud.h
- Revision:
- 3:1cf99502f396
- Parent:
- 0:77afd7560544
--- a/sensor_msgs/PointCloud.h Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/PointCloud.h Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_PointCloud_h
-#define ros_PointCloud_h
+#ifndef _ROS_sensor_msgs_PointCloud_h
+#define _ROS_sensor_msgs_PointCloud_h
#include <stdint.h>
#include <string.h>
#include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
#include "std_msgs/Header.h"
#include "geometry_msgs/Point32.h"
#include "sensor_msgs/ChannelFloat32.h"
@@ -16,14 +16,14 @@
{
public:
std_msgs::Header header;
- unsigned char points_length;
+ uint8_t points_length;
geometry_msgs::Point32 st_points;
geometry_msgs::Point32 * points;
- unsigned char channels_length;
+ uint8_t channels_length;
sensor_msgs::ChannelFloat32 st_channels;
sensor_msgs::ChannelFloat32 * channels;
- virtual int serialize(unsigned char *outbuffer)
+ virtual int serialize(unsigned char *outbuffer) const
{
int offset = 0;
offset += this->header.serialize(outbuffer + offset);
@@ -31,14 +31,14 @@
*(outbuffer + offset++) = 0;
*(outbuffer + offset++) = 0;
*(outbuffer + offset++) = 0;
- for( unsigned char i = 0; i < points_length; i++){
+ for( uint8_t i = 0; i < points_length; i++){
offset += this->points[i].serialize(outbuffer + offset);
}
*(outbuffer + offset++) = channels_length;
*(outbuffer + offset++) = 0;
*(outbuffer + offset++) = 0;
*(outbuffer + offset++) = 0;
- for( unsigned char i = 0; i < channels_length; i++){
+ for( uint8_t i = 0; i < channels_length; i++){
offset += this->channels[i].serialize(outbuffer + offset);
}
return offset;
@@ -48,28 +48,29 @@
{
int offset = 0;
offset += this->header.deserialize(inbuffer + offset);
- unsigned char points_lengthT = *(inbuffer + offset++);
+ uint8_t points_lengthT = *(inbuffer + offset++);
if(points_lengthT > points_length)
this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32));
offset += 3;
points_length = points_lengthT;
- for( unsigned char i = 0; i < points_length; i++){
+ for( uint8_t i = 0; i < points_length; i++){
offset += this->st_points.deserialize(inbuffer + offset);
memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32));
}
- unsigned char channels_lengthT = *(inbuffer + offset++);
+ uint8_t channels_lengthT = *(inbuffer + offset++);
if(channels_lengthT > channels_length)
this->channels = (sensor_msgs::ChannelFloat32*)realloc(this->channels, channels_lengthT * sizeof(sensor_msgs::ChannelFloat32));
offset += 3;
channels_length = channels_lengthT;
- for( unsigned char i = 0; i < channels_length; i++){
+ for( uint8_t i = 0; i < channels_length; i++){
offset += this->st_channels.deserialize(inbuffer + offset);
memcpy( &(this->channels[i]), &(this->st_channels), sizeof(sensor_msgs::ChannelFloat32));
}
return offset;
}
- virtual const char * getType(){ return "sensor_msgs/PointCloud"; };
+ virtual const char * getType(){ return "sensor_msgs/PointCloud"; };
+ virtual const char * getMD5(){ return "d8e9c3f5afbdd8a130fd1d2763945fca"; };
};