ROS Serial library for Mbed platforms for ROS Melodic Morenia. Check http://wiki.ros.org/rosserial_mbed/ for more information.
Revision 2:fa426560b283, committed 2021-05-27
- Comitter:
- krogedal
- Date:
- Thu May 27 19:25:46 2021 +0000
- Parent:
- 1:da82487f547e
- Commit message:
- no change
Changed in this revision
diff -r da82487f547e -r fa426560b283 BufferedSerial.lib --- a/BufferedSerial.lib Fri Nov 08 14:55:04 2019 -0300 +++ b/BufferedSerial.lib Thu May 27 19:25:46 2021 +0000 @@ -1,1 +1,1 @@ -http://mbed.org/users/sam_grove/code/BufferedSerial/#779304f9c5d2 +http://mbed.org/users/sam_grove/code/BufferedSerial/#7e5e866edd3d
diff -r da82487f547e -r fa426560b283 rosserial_arduino/Adc.h --- a/rosserial_arduino/Adc.h Fri Nov 08 14:55:04 2019 -0300 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,92 +0,0 @@ -#ifndef _ROS_rosserial_arduino_Adc_h -#define _ROS_rosserial_arduino_Adc_h - -#include <stdint.h> -#include <string.h> -#include <stdlib.h> -#include "ros/msg.h" - -namespace rosserial_arduino -{ - - class Adc : public ros::Msg - { - public: - typedef uint16_t _adc0_type; - _adc0_type adc0; - typedef uint16_t _adc1_type; - _adc1_type adc1; - typedef uint16_t _adc2_type; - _adc2_type adc2; - typedef uint16_t _adc3_type; - _adc3_type adc3; - typedef uint16_t _adc4_type; - _adc4_type adc4; - typedef uint16_t _adc5_type; - _adc5_type adc5; - - Adc(): - adc0(0), - adc1(0), - adc2(0), - adc3(0), - adc4(0), - adc5(0) - { - } - - virtual int serialize(unsigned char *outbuffer) const - { - int offset = 0; - *(outbuffer + offset + 0) = (this->adc0 >> (8 * 0)) & 0xFF; - *(outbuffer + offset + 1) = (this->adc0 >> (8 * 1)) & 0xFF; - offset += sizeof(this->adc0); - *(outbuffer + offset + 0) = (this->adc1 >> (8 * 0)) & 0xFF; - *(outbuffer + offset + 1) = (this->adc1 >> (8 * 1)) & 0xFF; - offset += sizeof(this->adc1); - *(outbuffer + offset + 0) = (this->adc2 >> (8 * 0)) & 0xFF; - *(outbuffer + offset + 1) = (this->adc2 >> (8 * 1)) & 0xFF; - offset += sizeof(this->adc2); - *(outbuffer + offset + 0) = (this->adc3 >> (8 * 0)) & 0xFF; - *(outbuffer + offset + 1) = (this->adc3 >> (8 * 1)) & 0xFF; - offset += sizeof(this->adc3); - *(outbuffer + offset + 0) = (this->adc4 >> (8 * 0)) & 0xFF; - *(outbuffer + offset + 1) = (this->adc4 >> (8 * 1)) & 0xFF; - offset += sizeof(this->adc4); - *(outbuffer + offset + 0) = (this->adc5 >> (8 * 0)) & 0xFF; - *(outbuffer + offset + 1) = (this->adc5 >> (8 * 1)) & 0xFF; - offset += sizeof(this->adc5); - return offset; - } - - virtual int deserialize(unsigned char *inbuffer) - { - int offset = 0; - this->adc0 = ((uint16_t) (*(inbuffer + offset))); - this->adc0 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); - offset += sizeof(this->adc0); - this->adc1 = ((uint16_t) (*(inbuffer + offset))); - this->adc1 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); - offset += sizeof(this->adc1); - this->adc2 = ((uint16_t) (*(inbuffer + offset))); - this->adc2 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); - offset += sizeof(this->adc2); - this->adc3 = ((uint16_t) (*(inbuffer + offset))); - this->adc3 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); - offset += sizeof(this->adc3); - this->adc4 = ((uint16_t) (*(inbuffer + offset))); - this->adc4 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); - offset += sizeof(this->adc4); - this->adc5 = ((uint16_t) (*(inbuffer + offset))); - this->adc5 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); - offset += sizeof(this->adc5); - return offset; - } - - const char * getType(){ return "rosserial_arduino/Adc"; }; - const char * getMD5(){ return "6d7853a614e2e821319068311f2af25b"; }; - - }; - -} -#endif
diff -r da82487f547e -r fa426560b283 rosserial_arduino/Test.h --- a/rosserial_arduino/Test.h Fri Nov 08 14:55:04 2019 -0300 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,104 +0,0 @@ -#ifndef _ROS_SERVICE_Test_h -#define _ROS_SERVICE_Test_h -#include <stdint.h> -#include <string.h> -#include <stdlib.h> -#include "ros/msg.h" - -namespace rosserial_arduino -{ - -static const char TEST[] = "rosserial_arduino/Test"; - - class TestRequest : public ros::Msg - { - public: - typedef const char* _input_type; - _input_type input; - - TestRequest(): - input("") - { - } - - virtual int serialize(unsigned char *outbuffer) const - { - int offset = 0; - uint32_t length_input = strlen(this->input); - varToArr(outbuffer + offset, length_input); - offset += 4; - memcpy(outbuffer + offset, this->input, length_input); - offset += length_input; - return offset; - } - - virtual int deserialize(unsigned char *inbuffer) - { - int offset = 0; - uint32_t length_input; - arrToVar(length_input, (inbuffer + offset)); - offset += 4; - for(unsigned int k= offset; k< offset+length_input; ++k){ - inbuffer[k-1]=inbuffer[k]; - } - inbuffer[offset+length_input-1]=0; - this->input = (char *)(inbuffer + offset-1); - offset += length_input; - return offset; - } - - const char * getType(){ return TEST; }; - const char * getMD5(){ return "39e92f1778057359c64c7b8a7d7b19de"; }; - - }; - - class TestResponse : public ros::Msg - { - public: - typedef const char* _output_type; - _output_type output; - - TestResponse(): - output("") - { - } - - virtual int serialize(unsigned char *outbuffer) const - { - int offset = 0; - uint32_t length_output = strlen(this->output); - varToArr(outbuffer + offset, length_output); - offset += 4; - memcpy(outbuffer + offset, this->output, length_output); - offset += length_output; - return offset; - } - - virtual int deserialize(unsigned char *inbuffer) - { - int offset = 0; - uint32_t length_output; - arrToVar(length_output, (inbuffer + offset)); - offset += 4; - for(unsigned int k= offset; k< offset+length_output; ++k){ - inbuffer[k-1]=inbuffer[k]; - } - inbuffer[offset+length_output-1]=0; - this->output = (char *)(inbuffer + offset-1); - offset += length_output; - return offset; - } - - const char * getType(){ return TEST; }; - const char * getMD5(){ return "0825d95fdfa2c8f4bbb4e9c74bccd3fd"; }; - - }; - - class Test { - public: - typedef TestRequest Request; - typedef TestResponse Response; - }; - -} -#endif