Personal fork
Dependencies: Servo mbed rosserial_mbed_lib
Fork of rosserial_mbed by
Revision 5:e52b44294b2b, committed 2014-05-01
- Comitter:
- garyservin
- Date:
- Thu May 01 06:20:36 2014 +0000
- Parent:
- 4:2cbca0ac2569
- Commit message:
- Fixed some issues to run on hydro and Freescale KL25Z
Changed in this revision
diff -r 2cbca0ac2569 -r e52b44294b2b MODSERIAL.lib --- a/MODSERIAL.lib Wed Feb 29 23:02:12 2012 +0000 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,1 +0,0 @@ -http://mbed.org/users/AjK/code/MODSERIAL/#af2af4c61c2f
diff -r 2cbca0ac2569 -r e52b44294b2b examples/Blink.cpp --- a/examples/Blink.cpp Wed Feb 29 23:02:12 2012 +0000 +++ b/examples/Blink.cpp Thu May 01 06:20:36 2014 +0000 @@ -1,4 +1,4 @@ -//#define COMPILE_BLINK_CODE_ROSSERIAL +#define COMPILE_BLINK_CODE_ROSSERIAL #ifdef COMPILE_BLINK_CODE_ROSSERIAL /*
diff -r 2cbca0ac2569 -r e52b44294b2b examples/HelloWorld.cpp --- a/examples/HelloWorld.cpp Wed Feb 29 23:02:12 2012 +0000 +++ b/examples/HelloWorld.cpp Thu May 01 06:20:36 2014 +0000 @@ -1,4 +1,4 @@ -#define COMPILE_HELLOWORLD_CODE_ROSSERIAL +//#define COMPILE_HELLOWORLD_CODE_ROSSERIAL #ifdef COMPILE_HELLOWORLD_CODE_ROSSERIAL /* @@ -15,13 +15,16 @@ std_msgs::String str_msg; ros::Publisher chatter("chatter", &str_msg); -char hello[13] = "hello world!"; +//char hello[13] = "hello world!"; +char hello[13] = "Gary Servin!"; +DigitalOut led = LED1; int main() { nh.initNode(); nh.advertise(chatter); while (1) { + led = !led; str_msg.data = hello; chatter.publish( &str_msg ); nh.spinOnce();
diff -r 2cbca0ac2569 -r e52b44294b2b mbed.bld --- a/mbed.bld Wed Feb 29 23:02:12 2012 +0000 +++ b/mbed.bld Thu May 01 06:20:36 2014 +0000 @@ -1,1 +1,1 @@ -http://mbed.org/users/mbed_official/code/mbed/builds/63bcd7ba4912 +http://mbed.org/users/mbed_official/code/mbed/builds/8a40adfe8776 \ No newline at end of file
diff -r 2cbca0ac2569 -r e52b44294b2b rosserial_arduino/Adc.h --- a/rosserial_arduino/Adc.h Wed Feb 29 23:02:12 2012 +0000 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,76 +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: - uint16_t adc0; - uint16_t adc1; - uint16_t adc2; - uint16_t adc3; - uint16_t adc4; - uint16_t adc5; - - 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 + 0))) << (8 * 0); - this->adc0 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); - offset += sizeof(this->adc0); - this->adc1 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); - this->adc1 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); - offset += sizeof(this->adc1); - this->adc2 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); - this->adc2 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); - offset += sizeof(this->adc2); - this->adc3 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); - this->adc3 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); - offset += sizeof(this->adc3); - this->adc4 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); - this->adc4 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); - offset += sizeof(this->adc4); - this->adc5 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); - this->adc5 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); - offset += sizeof(this->adc5); - return offset; - } - - const char * getType(){ return "rosserial_mbed/Adc"; }; - const char * getMD5(){ return "6d7853a614e2e821319068311f2af25b"; }; - - }; - -} -#endif \ No newline at end of file
diff -r 2cbca0ac2569 -r e52b44294b2b rosserial_arduino/Test.h --- a/rosserial_arduino/Test.h Wed Feb 29 23:02:12 2012 +0000 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,90 +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: - char * input; - - virtual int serialize(unsigned char *outbuffer) const - { - int offset = 0; - uint32_t * length_input = (uint32_t *)(outbuffer + offset); - *length_input = strlen( (const char*) this->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 = *(uint32_t *)(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; - } - - virtual const char * getType(){ return TEST; }; - virtual const char * getMD5(){ return "39e92f1778057359c64c7b8a7d7b19de"; }; - - }; - - class TestResponse : public ros::Msg - { - public: - char * output; - - virtual int serialize(unsigned char *outbuffer) const - { - int offset = 0; - uint32_t * length_output = (uint32_t *)(outbuffer + offset); - *length_output = strlen( (const char*) this->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 = *(uint32_t *)(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; - } - - virtual const char * getType(){ return TEST; }; - virtual const char * getMD5(){ return "0825d95fdfa2c8f4bbb4e9c74bccd3fd"; }; - - }; - - class Test { - public: - typedef TestRequest Request; - typedef TestResponse Response; - }; - -} -#endif \ No newline at end of file
diff -r 2cbca0ac2569 -r e52b44294b2b rosserial_mbed_lib.lib --- a/rosserial_mbed_lib.lib Wed Feb 29 23:02:12 2012 +0000 +++ b/rosserial_mbed_lib.lib Thu May 01 06:20:36 2014 +0000 @@ -1,1 +1,1 @@ -http://mbed.org/users/nucho/code/rosserial_mbed_lib/#1cf99502f396 +http://mbed.org/users/garyservin/code/rosserial_mbed_lib/#19c5437ed9fe