This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial.

Dependencies:  

Dependents:   rosserial_mbed robot_S2

Committer:
nucho
Date:
Wed Feb 29 23:00:21 2012 +0000
Revision:
4:684f39d0c346
Parent:
3:1cf99502f396

        

Who changed what in which revision?

UserRevisionLine numberNew contents of line
nucho 3:1cf99502f396 1 #ifndef _ROS_geometry_msgs_PoseArray_h
nucho 3:1cf99502f396 2 #define _ROS_geometry_msgs_PoseArray_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 3:1cf99502f396 7 #include "ros/msg.h"
nucho 0:77afd7560544 8 #include "std_msgs/Header.h"
nucho 0:77afd7560544 9 #include "geometry_msgs/Pose.h"
nucho 0:77afd7560544 10
nucho 0:77afd7560544 11 namespace geometry_msgs
nucho 0:77afd7560544 12 {
nucho 0:77afd7560544 13
nucho 0:77afd7560544 14 class PoseArray : public ros::Msg
nucho 0:77afd7560544 15 {
nucho 0:77afd7560544 16 public:
nucho 0:77afd7560544 17 std_msgs::Header header;
nucho 3:1cf99502f396 18 uint8_t poses_length;
nucho 0:77afd7560544 19 geometry_msgs::Pose st_poses;
nucho 0:77afd7560544 20 geometry_msgs::Pose * poses;
nucho 0:77afd7560544 21
nucho 3:1cf99502f396 22 virtual int serialize(unsigned char *outbuffer) const
nucho 0:77afd7560544 23 {
nucho 0:77afd7560544 24 int offset = 0;
nucho 0:77afd7560544 25 offset += this->header.serialize(outbuffer + offset);
nucho 0:77afd7560544 26 *(outbuffer + offset++) = poses_length;
nucho 0:77afd7560544 27 *(outbuffer + offset++) = 0;
nucho 0:77afd7560544 28 *(outbuffer + offset++) = 0;
nucho 0:77afd7560544 29 *(outbuffer + offset++) = 0;
nucho 3:1cf99502f396 30 for( uint8_t i = 0; i < poses_length; i++){
nucho 0:77afd7560544 31 offset += this->poses[i].serialize(outbuffer + offset);
nucho 0:77afd7560544 32 }
nucho 0:77afd7560544 33 return offset;
nucho 0:77afd7560544 34 }
nucho 0:77afd7560544 35
nucho 0:77afd7560544 36 virtual int deserialize(unsigned char *inbuffer)
nucho 0:77afd7560544 37 {
nucho 0:77afd7560544 38 int offset = 0;
nucho 0:77afd7560544 39 offset += this->header.deserialize(inbuffer + offset);
nucho 3:1cf99502f396 40 uint8_t poses_lengthT = *(inbuffer + offset++);
nucho 0:77afd7560544 41 if(poses_lengthT > poses_length)
nucho 0:77afd7560544 42 this->poses = (geometry_msgs::Pose*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::Pose));
nucho 0:77afd7560544 43 offset += 3;
nucho 0:77afd7560544 44 poses_length = poses_lengthT;
nucho 3:1cf99502f396 45 for( uint8_t i = 0; i < poses_length; i++){
nucho 0:77afd7560544 46 offset += this->st_poses.deserialize(inbuffer + offset);
nucho 0:77afd7560544 47 memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::Pose));
nucho 0:77afd7560544 48 }
nucho 0:77afd7560544 49 return offset;
nucho 0:77afd7560544 50 }
nucho 0:77afd7560544 51
nucho 0:77afd7560544 52 virtual const char * getType(){ return "geometry_msgs/PoseArray"; };
nucho 3:1cf99502f396 53 virtual const char * getMD5(){ return "916c28c5764443f268b296bb671b9d97"; };
nucho 0:77afd7560544 54
nucho 0:77afd7560544 55 };
nucho 0:77afd7560544 56
nucho 0:77afd7560544 57 }
nucho 0:77afd7560544 58 #endif