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
Diff: tf/tfMessage.h
- Revision:
- 3:1cf99502f396
- Parent:
- 0:77afd7560544
--- a/tf/tfMessage.h Sun Oct 16 09:35:11 2011 +0000
+++ b/tf/tfMessage.h Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_tfMessage_h
-#define ros_tfMessage_h
+#ifndef _ROS_tf_tfMessage_h
+#define _ROS_tf_tfMessage_h
#include <stdint.h>
#include <string.h>
#include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
#include "geometry_msgs/TransformStamped.h"
namespace tf
@@ -13,18 +13,18 @@
class tfMessage : public ros::Msg
{
public:
- unsigned char transforms_length;
+ uint8_t transforms_length;
geometry_msgs::TransformStamped st_transforms;
geometry_msgs::TransformStamped * transforms;
- virtual int serialize(unsigned char *outbuffer)
+ virtual int serialize(unsigned char *outbuffer) const
{
int offset = 0;
*(outbuffer + offset++) = transforms_length;
*(outbuffer + offset++) = 0;
*(outbuffer + offset++) = 0;
*(outbuffer + offset++) = 0;
- for( unsigned char i = 0; i < transforms_length; i++){
+ for( uint8_t i = 0; i < transforms_length; i++){
offset += this->transforms[i].serialize(outbuffer + offset);
}
return offset;
@@ -33,12 +33,12 @@
virtual int deserialize(unsigned char *inbuffer)
{
int offset = 0;
- unsigned char transforms_lengthT = *(inbuffer + offset++);
+ uint8_t transforms_lengthT = *(inbuffer + offset++);
if(transforms_lengthT > transforms_length)
this->transforms = (geometry_msgs::TransformStamped*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::TransformStamped));
offset += 3;
transforms_length = transforms_lengthT;
- for( unsigned char i = 0; i < transforms_length; i++){
+ for( uint8_t i = 0; i < transforms_length; i++){
offset += this->st_transforms.deserialize(inbuffer + offset);
memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::TransformStamped));
}
@@ -46,6 +46,7 @@
}
virtual const char * getType(){ return "tf/tfMessage"; };
+ virtual const char * getMD5(){ return "94810edda583a504dfda3829e70d7eec"; };
};
