ROS Serial library for Mbed platforms for ROS Melodic Morenia. Check http://wiki.ros.org/rosserial_mbed/ for more information.

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_melodic Motortest Nucleo_vr_servo_project NucleoFM ... more

ROSSerial_mbed for Melodic Distribution

The Robot Operating System (ROS) is a flexible framework for writing robot software. It is a collection of tools, libraries, and conventions that aim to simplify the task of creating complex and robust robot behavior across a wide variety of robotic platforms.

The rosserial_mbed package allows to write ROS nodes on any mbed enabled devices and have them connected to a running ROS system on your computer using the serial port.

Hello World (example publisher)

Import programrosserial_mbed_hello_world_publisher_melodic

rosserial_mbed Hello World example for Melodic Morenia distribution

Running the Code

Now, launch the roscore in a new terminal window:

Quote:

$ roscore

Next, run the rosserial client application that forwards your MBED messages to the rest of ROS. Make sure to use the correct serial port:

Quote:

$ rosrun rosserial_python serial_node.py /dev/ttyACM0

Finally, watch the greetings come in from your MBED by launching a new terminal window and entering :

Quote:

$ rostopic echo chatter

See Also

More examples

Blink

/*
 * rosserial Subscriber Example
 * Blinks an LED on callback
 */
#include "mbed.h"
#include <ros.h>
#include <std_msgs/Empty.h>

ros::NodeHandle nh;
DigitalOut myled(LED1);

void messageCb(const std_msgs::Empty& toggle_msg){
    myled = !myled;   // blink the led
}

ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb);

int main() {
    nh.initNode();
    nh.subscribe(sub);

    while (1) {
        nh.spinOnce();
        wait_ms(1);
    }
}

Push

/*
 * Button Example for Rosserial
 */

#include "mbed.h"
#include <ros.h>
#include <std_msgs/Bool.h>

PinName button = p20;

ros::NodeHandle nh;

std_msgs::Bool pushed_msg;
ros::Publisher pub_button("pushed", &pushed_msg);

DigitalIn button_pin(button);
DigitalOut led_pin(LED1);

bool last_reading;
long last_debounce_time=0;
long debounce_delay=50;
bool published = true;

Timer t;
int main() {
    t.start();
    nh.initNode();
    nh.advertise(pub_button);

    //Enable the pullup resistor on the button
    button_pin.mode(PullUp);

    //The button is a normally button
    last_reading = ! button_pin;

    while (1) {
        bool reading = ! button_pin;

        if (last_reading!= reading) {
            last_debounce_time = t.read_ms();
            published = false;
        }

        //if the button value has not changed for the debounce delay, we know its stable
        if ( !published && (t.read_ms() - last_debounce_time)  > debounce_delay) {
            led_pin = reading;
            pushed_msg.data = reading;
            pub_button.publish(&pushed_msg);
            published = true;
        }

        last_reading = reading;

        nh.spinOnce();
    }
}
Committer:
Gary Servin
Date:
Fri Nov 08 14:55:04 2019 -0300
Revision:
1:da82487f547e
Parent:
0:04ac6be8229a
Add missing round() method

Who changed what in which revision?

UserRevisionLine numberNew contents of line
Gary Servin 0:04ac6be8229a 1 #ifndef _ROS_actionlib_TestRequestGoal_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_actionlib_TestRequestGoal_h
Gary Servin 0:04ac6be8229a 3
Gary Servin 0:04ac6be8229a 4 #include <stdint.h>
Gary Servin 0:04ac6be8229a 5 #include <string.h>
Gary Servin 0:04ac6be8229a 6 #include <stdlib.h>
Gary Servin 0:04ac6be8229a 7 #include "ros/msg.h"
Gary Servin 0:04ac6be8229a 8 #include "ros/duration.h"
Gary Servin 0:04ac6be8229a 9
Gary Servin 0:04ac6be8229a 10 namespace actionlib
Gary Servin 0:04ac6be8229a 11 {
Gary Servin 0:04ac6be8229a 12
Gary Servin 0:04ac6be8229a 13 class TestRequestGoal : public ros::Msg
Gary Servin 0:04ac6be8229a 14 {
Gary Servin 0:04ac6be8229a 15 public:
Gary Servin 0:04ac6be8229a 16 typedef int32_t _terminate_status_type;
Gary Servin 0:04ac6be8229a 17 _terminate_status_type terminate_status;
Gary Servin 0:04ac6be8229a 18 typedef bool _ignore_cancel_type;
Gary Servin 0:04ac6be8229a 19 _ignore_cancel_type ignore_cancel;
Gary Servin 0:04ac6be8229a 20 typedef const char* _result_text_type;
Gary Servin 0:04ac6be8229a 21 _result_text_type result_text;
Gary Servin 0:04ac6be8229a 22 typedef int32_t _the_result_type;
Gary Servin 0:04ac6be8229a 23 _the_result_type the_result;
Gary Servin 0:04ac6be8229a 24 typedef bool _is_simple_client_type;
Gary Servin 0:04ac6be8229a 25 _is_simple_client_type is_simple_client;
Gary Servin 0:04ac6be8229a 26 typedef ros::Duration _delay_accept_type;
Gary Servin 0:04ac6be8229a 27 _delay_accept_type delay_accept;
Gary Servin 0:04ac6be8229a 28 typedef ros::Duration _delay_terminate_type;
Gary Servin 0:04ac6be8229a 29 _delay_terminate_type delay_terminate;
Gary Servin 0:04ac6be8229a 30 typedef ros::Duration _pause_status_type;
Gary Servin 0:04ac6be8229a 31 _pause_status_type pause_status;
Gary Servin 0:04ac6be8229a 32 enum { TERMINATE_SUCCESS = 0 };
Gary Servin 0:04ac6be8229a 33 enum { TERMINATE_ABORTED = 1 };
Gary Servin 0:04ac6be8229a 34 enum { TERMINATE_REJECTED = 2 };
Gary Servin 0:04ac6be8229a 35 enum { TERMINATE_LOSE = 3 };
Gary Servin 0:04ac6be8229a 36 enum { TERMINATE_DROP = 4 };
Gary Servin 0:04ac6be8229a 37 enum { TERMINATE_EXCEPTION = 5 };
Gary Servin 0:04ac6be8229a 38
Gary Servin 0:04ac6be8229a 39 TestRequestGoal():
Gary Servin 0:04ac6be8229a 40 terminate_status(0),
Gary Servin 0:04ac6be8229a 41 ignore_cancel(0),
Gary Servin 0:04ac6be8229a 42 result_text(""),
Gary Servin 0:04ac6be8229a 43 the_result(0),
Gary Servin 0:04ac6be8229a 44 is_simple_client(0),
Gary Servin 0:04ac6be8229a 45 delay_accept(),
Gary Servin 0:04ac6be8229a 46 delay_terminate(),
Gary Servin 0:04ac6be8229a 47 pause_status()
Gary Servin 0:04ac6be8229a 48 {
Gary Servin 0:04ac6be8229a 49 }
Gary Servin 0:04ac6be8229a 50
Gary Servin 0:04ac6be8229a 51 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 52 {
Gary Servin 0:04ac6be8229a 53 int offset = 0;
Gary Servin 0:04ac6be8229a 54 union {
Gary Servin 0:04ac6be8229a 55 int32_t real;
Gary Servin 0:04ac6be8229a 56 uint32_t base;
Gary Servin 0:04ac6be8229a 57 } u_terminate_status;
Gary Servin 0:04ac6be8229a 58 u_terminate_status.real = this->terminate_status;
Gary Servin 0:04ac6be8229a 59 *(outbuffer + offset + 0) = (u_terminate_status.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 60 *(outbuffer + offset + 1) = (u_terminate_status.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 61 *(outbuffer + offset + 2) = (u_terminate_status.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 62 *(outbuffer + offset + 3) = (u_terminate_status.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 63 offset += sizeof(this->terminate_status);
Gary Servin 0:04ac6be8229a 64 union {
Gary Servin 0:04ac6be8229a 65 bool real;
Gary Servin 0:04ac6be8229a 66 uint8_t base;
Gary Servin 0:04ac6be8229a 67 } u_ignore_cancel;
Gary Servin 0:04ac6be8229a 68 u_ignore_cancel.real = this->ignore_cancel;
Gary Servin 0:04ac6be8229a 69 *(outbuffer + offset + 0) = (u_ignore_cancel.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 70 offset += sizeof(this->ignore_cancel);
Gary Servin 0:04ac6be8229a 71 uint32_t length_result_text = strlen(this->result_text);
Gary Servin 0:04ac6be8229a 72 varToArr(outbuffer + offset, length_result_text);
Gary Servin 0:04ac6be8229a 73 offset += 4;
Gary Servin 0:04ac6be8229a 74 memcpy(outbuffer + offset, this->result_text, length_result_text);
Gary Servin 0:04ac6be8229a 75 offset += length_result_text;
Gary Servin 0:04ac6be8229a 76 union {
Gary Servin 0:04ac6be8229a 77 int32_t real;
Gary Servin 0:04ac6be8229a 78 uint32_t base;
Gary Servin 0:04ac6be8229a 79 } u_the_result;
Gary Servin 0:04ac6be8229a 80 u_the_result.real = this->the_result;
Gary Servin 0:04ac6be8229a 81 *(outbuffer + offset + 0) = (u_the_result.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 82 *(outbuffer + offset + 1) = (u_the_result.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 83 *(outbuffer + offset + 2) = (u_the_result.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 84 *(outbuffer + offset + 3) = (u_the_result.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 85 offset += sizeof(this->the_result);
Gary Servin 0:04ac6be8229a 86 union {
Gary Servin 0:04ac6be8229a 87 bool real;
Gary Servin 0:04ac6be8229a 88 uint8_t base;
Gary Servin 0:04ac6be8229a 89 } u_is_simple_client;
Gary Servin 0:04ac6be8229a 90 u_is_simple_client.real = this->is_simple_client;
Gary Servin 0:04ac6be8229a 91 *(outbuffer + offset + 0) = (u_is_simple_client.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 92 offset += sizeof(this->is_simple_client);
Gary Servin 0:04ac6be8229a 93 *(outbuffer + offset + 0) = (this->delay_accept.sec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 94 *(outbuffer + offset + 1) = (this->delay_accept.sec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 95 *(outbuffer + offset + 2) = (this->delay_accept.sec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 96 *(outbuffer + offset + 3) = (this->delay_accept.sec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 97 offset += sizeof(this->delay_accept.sec);
Gary Servin 0:04ac6be8229a 98 *(outbuffer + offset + 0) = (this->delay_accept.nsec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 99 *(outbuffer + offset + 1) = (this->delay_accept.nsec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 100 *(outbuffer + offset + 2) = (this->delay_accept.nsec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 101 *(outbuffer + offset + 3) = (this->delay_accept.nsec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 102 offset += sizeof(this->delay_accept.nsec);
Gary Servin 0:04ac6be8229a 103 *(outbuffer + offset + 0) = (this->delay_terminate.sec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 104 *(outbuffer + offset + 1) = (this->delay_terminate.sec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 105 *(outbuffer + offset + 2) = (this->delay_terminate.sec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 106 *(outbuffer + offset + 3) = (this->delay_terminate.sec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 107 offset += sizeof(this->delay_terminate.sec);
Gary Servin 0:04ac6be8229a 108 *(outbuffer + offset + 0) = (this->delay_terminate.nsec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 109 *(outbuffer + offset + 1) = (this->delay_terminate.nsec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 110 *(outbuffer + offset + 2) = (this->delay_terminate.nsec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 111 *(outbuffer + offset + 3) = (this->delay_terminate.nsec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 112 offset += sizeof(this->delay_terminate.nsec);
Gary Servin 0:04ac6be8229a 113 *(outbuffer + offset + 0) = (this->pause_status.sec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 114 *(outbuffer + offset + 1) = (this->pause_status.sec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 115 *(outbuffer + offset + 2) = (this->pause_status.sec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 116 *(outbuffer + offset + 3) = (this->pause_status.sec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 117 offset += sizeof(this->pause_status.sec);
Gary Servin 0:04ac6be8229a 118 *(outbuffer + offset + 0) = (this->pause_status.nsec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 119 *(outbuffer + offset + 1) = (this->pause_status.nsec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 120 *(outbuffer + offset + 2) = (this->pause_status.nsec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 121 *(outbuffer + offset + 3) = (this->pause_status.nsec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 122 offset += sizeof(this->pause_status.nsec);
Gary Servin 0:04ac6be8229a 123 return offset;
Gary Servin 0:04ac6be8229a 124 }
Gary Servin 0:04ac6be8229a 125
Gary Servin 0:04ac6be8229a 126 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 127 {
Gary Servin 0:04ac6be8229a 128 int offset = 0;
Gary Servin 0:04ac6be8229a 129 union {
Gary Servin 0:04ac6be8229a 130 int32_t real;
Gary Servin 0:04ac6be8229a 131 uint32_t base;
Gary Servin 0:04ac6be8229a 132 } u_terminate_status;
Gary Servin 0:04ac6be8229a 133 u_terminate_status.base = 0;
Gary Servin 0:04ac6be8229a 134 u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 135 u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 136 u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 137 u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 138 this->terminate_status = u_terminate_status.real;
Gary Servin 0:04ac6be8229a 139 offset += sizeof(this->terminate_status);
Gary Servin 0:04ac6be8229a 140 union {
Gary Servin 0:04ac6be8229a 141 bool real;
Gary Servin 0:04ac6be8229a 142 uint8_t base;
Gary Servin 0:04ac6be8229a 143 } u_ignore_cancel;
Gary Servin 0:04ac6be8229a 144 u_ignore_cancel.base = 0;
Gary Servin 0:04ac6be8229a 145 u_ignore_cancel.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 146 this->ignore_cancel = u_ignore_cancel.real;
Gary Servin 0:04ac6be8229a 147 offset += sizeof(this->ignore_cancel);
Gary Servin 0:04ac6be8229a 148 uint32_t length_result_text;
Gary Servin 0:04ac6be8229a 149 arrToVar(length_result_text, (inbuffer + offset));
Gary Servin 0:04ac6be8229a 150 offset += 4;
Gary Servin 0:04ac6be8229a 151 for(unsigned int k= offset; k< offset+length_result_text; ++k){
Gary Servin 0:04ac6be8229a 152 inbuffer[k-1]=inbuffer[k];
Gary Servin 0:04ac6be8229a 153 }
Gary Servin 0:04ac6be8229a 154 inbuffer[offset+length_result_text-1]=0;
Gary Servin 0:04ac6be8229a 155 this->result_text = (char *)(inbuffer + offset-1);
Gary Servin 0:04ac6be8229a 156 offset += length_result_text;
Gary Servin 0:04ac6be8229a 157 union {
Gary Servin 0:04ac6be8229a 158 int32_t real;
Gary Servin 0:04ac6be8229a 159 uint32_t base;
Gary Servin 0:04ac6be8229a 160 } u_the_result;
Gary Servin 0:04ac6be8229a 161 u_the_result.base = 0;
Gary Servin 0:04ac6be8229a 162 u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 163 u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 164 u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 165 u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 166 this->the_result = u_the_result.real;
Gary Servin 0:04ac6be8229a 167 offset += sizeof(this->the_result);
Gary Servin 0:04ac6be8229a 168 union {
Gary Servin 0:04ac6be8229a 169 bool real;
Gary Servin 0:04ac6be8229a 170 uint8_t base;
Gary Servin 0:04ac6be8229a 171 } u_is_simple_client;
Gary Servin 0:04ac6be8229a 172 u_is_simple_client.base = 0;
Gary Servin 0:04ac6be8229a 173 u_is_simple_client.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 174 this->is_simple_client = u_is_simple_client.real;
Gary Servin 0:04ac6be8229a 175 offset += sizeof(this->is_simple_client);
Gary Servin 0:04ac6be8229a 176 this->delay_accept.sec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 177 this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 178 this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 179 this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 180 offset += sizeof(this->delay_accept.sec);
Gary Servin 0:04ac6be8229a 181 this->delay_accept.nsec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 182 this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 183 this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 184 this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 185 offset += sizeof(this->delay_accept.nsec);
Gary Servin 0:04ac6be8229a 186 this->delay_terminate.sec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 187 this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 188 this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 189 this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 190 offset += sizeof(this->delay_terminate.sec);
Gary Servin 0:04ac6be8229a 191 this->delay_terminate.nsec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 192 this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 193 this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 194 this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 195 offset += sizeof(this->delay_terminate.nsec);
Gary Servin 0:04ac6be8229a 196 this->pause_status.sec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 197 this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 198 this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 199 this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 200 offset += sizeof(this->pause_status.sec);
Gary Servin 0:04ac6be8229a 201 this->pause_status.nsec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 202 this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 203 this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 204 this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 205 offset += sizeof(this->pause_status.nsec);
Gary Servin 0:04ac6be8229a 206 return offset;
Gary Servin 0:04ac6be8229a 207 }
Gary Servin 0:04ac6be8229a 208
Gary Servin 0:04ac6be8229a 209 const char * getType(){ return "actionlib/TestRequestGoal"; };
Gary Servin 0:04ac6be8229a 210 const char * getMD5(){ return "db5d00ba98302d6c6dd3737e9a03ceea"; };
Gary Servin 0:04ac6be8229a 211
Gary Servin 0:04ac6be8229a 212 };
Gary Servin 0:04ac6be8229a 213
Gary Servin 0:04ac6be8229a 214 }
Gary Servin 0:04ac6be8229a 215 #endif