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

Dependencies:   rosserial_mbed_lib mbed Servo

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers Adc.h Source File

Adc.h

00001 #ifndef _ROS_rosserial_arduino_Adc_h
00002 #define _ROS_rosserial_arduino_Adc_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 
00009 namespace rosserial_arduino
00010 {
00011 
00012   class Adc : public ros::Msg
00013   {
00014     public:
00015       uint16_t adc0;
00016       uint16_t adc1;
00017       uint16_t adc2;
00018       uint16_t adc3;
00019       uint16_t adc4;
00020       uint16_t adc5;
00021 
00022     virtual int serialize(unsigned char *outbuffer) const
00023     {
00024       int offset = 0;
00025       *(outbuffer + offset + 0) = (this->adc0 >> (8 * 0)) & 0xFF;
00026       *(outbuffer + offset + 1) = (this->adc0 >> (8 * 1)) & 0xFF;
00027       offset += sizeof(this->adc0);
00028       *(outbuffer + offset + 0) = (this->adc1 >> (8 * 0)) & 0xFF;
00029       *(outbuffer + offset + 1) = (this->adc1 >> (8 * 1)) & 0xFF;
00030       offset += sizeof(this->adc1);
00031       *(outbuffer + offset + 0) = (this->adc2 >> (8 * 0)) & 0xFF;
00032       *(outbuffer + offset + 1) = (this->adc2 >> (8 * 1)) & 0xFF;
00033       offset += sizeof(this->adc2);
00034       *(outbuffer + offset + 0) = (this->adc3 >> (8 * 0)) & 0xFF;
00035       *(outbuffer + offset + 1) = (this->adc3 >> (8 * 1)) & 0xFF;
00036       offset += sizeof(this->adc3);
00037       *(outbuffer + offset + 0) = (this->adc4 >> (8 * 0)) & 0xFF;
00038       *(outbuffer + offset + 1) = (this->adc4 >> (8 * 1)) & 0xFF;
00039       offset += sizeof(this->adc4);
00040       *(outbuffer + offset + 0) = (this->adc5 >> (8 * 0)) & 0xFF;
00041       *(outbuffer + offset + 1) = (this->adc5 >> (8 * 1)) & 0xFF;
00042       offset += sizeof(this->adc5);
00043       return offset;
00044     }
00045 
00046     virtual int deserialize(unsigned char *inbuffer)
00047     {
00048       int offset = 0;
00049       this->adc0 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
00050       this->adc0 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
00051       offset += sizeof(this->adc0);
00052       this->adc1 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
00053       this->adc1 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
00054       offset += sizeof(this->adc1);
00055       this->adc2 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
00056       this->adc2 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
00057       offset += sizeof(this->adc2);
00058       this->adc3 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
00059       this->adc3 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
00060       offset += sizeof(this->adc3);
00061       this->adc4 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
00062       this->adc4 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
00063       offset += sizeof(this->adc4);
00064       this->adc5 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
00065       this->adc5 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
00066       offset += sizeof(this->adc5);
00067      return offset;
00068     }
00069 
00070     const char * getType(){ return "rosserial_mbed/Adc"; };
00071     const char * getMD5(){ return "6d7853a614e2e821319068311f2af25b"; };
00072 
00073   };
00074 
00075 }
00076 #endif