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_std_msgs_UInt16_h
nucho 3:1cf99502f396 2 #define _ROS_std_msgs_UInt16_h
nucho 3:1cf99502f396 3
nucho 3:1cf99502f396 4 #include <stdint.h>
nucho 3:1cf99502f396 5 #include <string.h>
nucho 3:1cf99502f396 6 #include <stdlib.h>
nucho 3:1cf99502f396 7 #include "ros/msg.h"
nucho 3:1cf99502f396 8
nucho 3:1cf99502f396 9 namespace std_msgs
nucho 3:1cf99502f396 10 {
nucho 3:1cf99502f396 11
nucho 3:1cf99502f396 12 class UInt16 : public ros::Msg
nucho 3:1cf99502f396 13 {
nucho 3:1cf99502f396 14 public:
nucho 3:1cf99502f396 15 uint16_t data;
nucho 3:1cf99502f396 16
nucho 3:1cf99502f396 17 virtual int serialize(unsigned char *outbuffer) const
nucho 3:1cf99502f396 18 {
nucho 3:1cf99502f396 19 int offset = 0;
nucho 3:1cf99502f396 20 *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF;
nucho 3:1cf99502f396 21 *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF;
nucho 3:1cf99502f396 22 offset += sizeof(this->data);
nucho 3:1cf99502f396 23 return offset;
nucho 3:1cf99502f396 24 }
nucho 3:1cf99502f396 25
nucho 3:1cf99502f396 26 virtual int deserialize(unsigned char *inbuffer)
nucho 3:1cf99502f396 27 {
nucho 3:1cf99502f396 28 int offset = 0;
nucho 3:1cf99502f396 29 this->data |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 3:1cf99502f396 30 this->data |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
nucho 3:1cf99502f396 31 offset += sizeof(this->data);
nucho 3:1cf99502f396 32 return offset;
nucho 3:1cf99502f396 33 }
nucho 3:1cf99502f396 34
nucho 3:1cf99502f396 35 virtual const char * getType(){ return "std_msgs/UInt16"; };
nucho 3:1cf99502f396 36 virtual const char * getMD5(){ return "1df79edf208b629fe6b81923a544552d"; };
nucho 3:1cf99502f396 37
nucho 3:1cf99502f396 38 };
nucho 3:1cf99502f396 39
nucho 3:1cf99502f396 40 }
nucho 0:77afd7560544 41 #endif