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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_jade

ROSSerial_mbed for Jade 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_jade

rosserial_mbed Hello World example for jade 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:
garyservin
Date:
Thu Mar 31 23:23:15 2016 +0000
Revision:
0:a906bb7c7831
ROS Serial library for Mbed platforms for ROS Jade Turtle. Check http://wiki.ros.org/rosserial_mbed/ for more information.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:a906bb7c7831 1 #ifndef _ROS_SERVICE_GetLinkProperties_h
garyservin 0:a906bb7c7831 2 #define _ROS_SERVICE_GetLinkProperties_h
garyservin 0:a906bb7c7831 3 #include <stdint.h>
garyservin 0:a906bb7c7831 4 #include <string.h>
garyservin 0:a906bb7c7831 5 #include <stdlib.h>
garyservin 0:a906bb7c7831 6 #include "ros/msg.h"
garyservin 0:a906bb7c7831 7 #include "geometry_msgs/Pose.h"
garyservin 0:a906bb7c7831 8
garyservin 0:a906bb7c7831 9 namespace gazebo_msgs
garyservin 0:a906bb7c7831 10 {
garyservin 0:a906bb7c7831 11
garyservin 0:a906bb7c7831 12 static const char GETLINKPROPERTIES[] = "gazebo_msgs/GetLinkProperties";
garyservin 0:a906bb7c7831 13
garyservin 0:a906bb7c7831 14 class GetLinkPropertiesRequest : public ros::Msg
garyservin 0:a906bb7c7831 15 {
garyservin 0:a906bb7c7831 16 public:
garyservin 0:a906bb7c7831 17 const char* link_name;
garyservin 0:a906bb7c7831 18
garyservin 0:a906bb7c7831 19 GetLinkPropertiesRequest():
garyservin 0:a906bb7c7831 20 link_name("")
garyservin 0:a906bb7c7831 21 {
garyservin 0:a906bb7c7831 22 }
garyservin 0:a906bb7c7831 23
garyservin 0:a906bb7c7831 24 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:a906bb7c7831 25 {
garyservin 0:a906bb7c7831 26 int offset = 0;
garyservin 0:a906bb7c7831 27 uint32_t length_link_name = strlen(this->link_name);
garyservin 0:a906bb7c7831 28 memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t));
garyservin 0:a906bb7c7831 29 offset += 4;
garyservin 0:a906bb7c7831 30 memcpy(outbuffer + offset, this->link_name, length_link_name);
garyservin 0:a906bb7c7831 31 offset += length_link_name;
garyservin 0:a906bb7c7831 32 return offset;
garyservin 0:a906bb7c7831 33 }
garyservin 0:a906bb7c7831 34
garyservin 0:a906bb7c7831 35 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:a906bb7c7831 36 {
garyservin 0:a906bb7c7831 37 int offset = 0;
garyservin 0:a906bb7c7831 38 uint32_t length_link_name;
garyservin 0:a906bb7c7831 39 memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:a906bb7c7831 40 offset += 4;
garyservin 0:a906bb7c7831 41 for(unsigned int k= offset; k< offset+length_link_name; ++k){
garyservin 0:a906bb7c7831 42 inbuffer[k-1]=inbuffer[k];
garyservin 0:a906bb7c7831 43 }
garyservin 0:a906bb7c7831 44 inbuffer[offset+length_link_name-1]=0;
garyservin 0:a906bb7c7831 45 this->link_name = (char *)(inbuffer + offset-1);
garyservin 0:a906bb7c7831 46 offset += length_link_name;
garyservin 0:a906bb7c7831 47 return offset;
garyservin 0:a906bb7c7831 48 }
garyservin 0:a906bb7c7831 49
garyservin 0:a906bb7c7831 50 const char * getType(){ return GETLINKPROPERTIES; };
garyservin 0:a906bb7c7831 51 const char * getMD5(){ return "7d82d60381f1b66a30f2157f60884345"; };
garyservin 0:a906bb7c7831 52
garyservin 0:a906bb7c7831 53 };
garyservin 0:a906bb7c7831 54
garyservin 0:a906bb7c7831 55 class GetLinkPropertiesResponse : public ros::Msg
garyservin 0:a906bb7c7831 56 {
garyservin 0:a906bb7c7831 57 public:
garyservin 0:a906bb7c7831 58 geometry_msgs::Pose com;
garyservin 0:a906bb7c7831 59 bool gravity_mode;
garyservin 0:a906bb7c7831 60 double mass;
garyservin 0:a906bb7c7831 61 double ixx;
garyservin 0:a906bb7c7831 62 double ixy;
garyservin 0:a906bb7c7831 63 double ixz;
garyservin 0:a906bb7c7831 64 double iyy;
garyservin 0:a906bb7c7831 65 double iyz;
garyservin 0:a906bb7c7831 66 double izz;
garyservin 0:a906bb7c7831 67 bool success;
garyservin 0:a906bb7c7831 68 const char* status_message;
garyservin 0:a906bb7c7831 69
garyservin 0:a906bb7c7831 70 GetLinkPropertiesResponse():
garyservin 0:a906bb7c7831 71 com(),
garyservin 0:a906bb7c7831 72 gravity_mode(0),
garyservin 0:a906bb7c7831 73 mass(0),
garyservin 0:a906bb7c7831 74 ixx(0),
garyservin 0:a906bb7c7831 75 ixy(0),
garyservin 0:a906bb7c7831 76 ixz(0),
garyservin 0:a906bb7c7831 77 iyy(0),
garyservin 0:a906bb7c7831 78 iyz(0),
garyservin 0:a906bb7c7831 79 izz(0),
garyservin 0:a906bb7c7831 80 success(0),
garyservin 0:a906bb7c7831 81 status_message("")
garyservin 0:a906bb7c7831 82 {
garyservin 0:a906bb7c7831 83 }
garyservin 0:a906bb7c7831 84
garyservin 0:a906bb7c7831 85 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:a906bb7c7831 86 {
garyservin 0:a906bb7c7831 87 int offset = 0;
garyservin 0:a906bb7c7831 88 offset += this->com.serialize(outbuffer + offset);
garyservin 0:a906bb7c7831 89 union {
garyservin 0:a906bb7c7831 90 bool real;
garyservin 0:a906bb7c7831 91 uint8_t base;
garyservin 0:a906bb7c7831 92 } u_gravity_mode;
garyservin 0:a906bb7c7831 93 u_gravity_mode.real = this->gravity_mode;
garyservin 0:a906bb7c7831 94 *(outbuffer + offset + 0) = (u_gravity_mode.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 95 offset += sizeof(this->gravity_mode);
garyservin 0:a906bb7c7831 96 union {
garyservin 0:a906bb7c7831 97 double real;
garyservin 0:a906bb7c7831 98 uint64_t base;
garyservin 0:a906bb7c7831 99 } u_mass;
garyservin 0:a906bb7c7831 100 u_mass.real = this->mass;
garyservin 0:a906bb7c7831 101 *(outbuffer + offset + 0) = (u_mass.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 102 *(outbuffer + offset + 1) = (u_mass.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 103 *(outbuffer + offset + 2) = (u_mass.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 104 *(outbuffer + offset + 3) = (u_mass.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 105 *(outbuffer + offset + 4) = (u_mass.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 106 *(outbuffer + offset + 5) = (u_mass.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 107 *(outbuffer + offset + 6) = (u_mass.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 108 *(outbuffer + offset + 7) = (u_mass.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 109 offset += sizeof(this->mass);
garyservin 0:a906bb7c7831 110 union {
garyservin 0:a906bb7c7831 111 double real;
garyservin 0:a906bb7c7831 112 uint64_t base;
garyservin 0:a906bb7c7831 113 } u_ixx;
garyservin 0:a906bb7c7831 114 u_ixx.real = this->ixx;
garyservin 0:a906bb7c7831 115 *(outbuffer + offset + 0) = (u_ixx.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 116 *(outbuffer + offset + 1) = (u_ixx.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 117 *(outbuffer + offset + 2) = (u_ixx.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 118 *(outbuffer + offset + 3) = (u_ixx.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 119 *(outbuffer + offset + 4) = (u_ixx.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 120 *(outbuffer + offset + 5) = (u_ixx.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 121 *(outbuffer + offset + 6) = (u_ixx.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 122 *(outbuffer + offset + 7) = (u_ixx.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 123 offset += sizeof(this->ixx);
garyservin 0:a906bb7c7831 124 union {
garyservin 0:a906bb7c7831 125 double real;
garyservin 0:a906bb7c7831 126 uint64_t base;
garyservin 0:a906bb7c7831 127 } u_ixy;
garyservin 0:a906bb7c7831 128 u_ixy.real = this->ixy;
garyservin 0:a906bb7c7831 129 *(outbuffer + offset + 0) = (u_ixy.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 130 *(outbuffer + offset + 1) = (u_ixy.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 131 *(outbuffer + offset + 2) = (u_ixy.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 132 *(outbuffer + offset + 3) = (u_ixy.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 133 *(outbuffer + offset + 4) = (u_ixy.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 134 *(outbuffer + offset + 5) = (u_ixy.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 135 *(outbuffer + offset + 6) = (u_ixy.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 136 *(outbuffer + offset + 7) = (u_ixy.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 137 offset += sizeof(this->ixy);
garyservin 0:a906bb7c7831 138 union {
garyservin 0:a906bb7c7831 139 double real;
garyservin 0:a906bb7c7831 140 uint64_t base;
garyservin 0:a906bb7c7831 141 } u_ixz;
garyservin 0:a906bb7c7831 142 u_ixz.real = this->ixz;
garyservin 0:a906bb7c7831 143 *(outbuffer + offset + 0) = (u_ixz.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 144 *(outbuffer + offset + 1) = (u_ixz.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 145 *(outbuffer + offset + 2) = (u_ixz.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 146 *(outbuffer + offset + 3) = (u_ixz.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 147 *(outbuffer + offset + 4) = (u_ixz.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 148 *(outbuffer + offset + 5) = (u_ixz.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 149 *(outbuffer + offset + 6) = (u_ixz.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 150 *(outbuffer + offset + 7) = (u_ixz.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 151 offset += sizeof(this->ixz);
garyservin 0:a906bb7c7831 152 union {
garyservin 0:a906bb7c7831 153 double real;
garyservin 0:a906bb7c7831 154 uint64_t base;
garyservin 0:a906bb7c7831 155 } u_iyy;
garyservin 0:a906bb7c7831 156 u_iyy.real = this->iyy;
garyservin 0:a906bb7c7831 157 *(outbuffer + offset + 0) = (u_iyy.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 158 *(outbuffer + offset + 1) = (u_iyy.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 159 *(outbuffer + offset + 2) = (u_iyy.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 160 *(outbuffer + offset + 3) = (u_iyy.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 161 *(outbuffer + offset + 4) = (u_iyy.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 162 *(outbuffer + offset + 5) = (u_iyy.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 163 *(outbuffer + offset + 6) = (u_iyy.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 164 *(outbuffer + offset + 7) = (u_iyy.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 165 offset += sizeof(this->iyy);
garyservin 0:a906bb7c7831 166 union {
garyservin 0:a906bb7c7831 167 double real;
garyservin 0:a906bb7c7831 168 uint64_t base;
garyservin 0:a906bb7c7831 169 } u_iyz;
garyservin 0:a906bb7c7831 170 u_iyz.real = this->iyz;
garyservin 0:a906bb7c7831 171 *(outbuffer + offset + 0) = (u_iyz.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 172 *(outbuffer + offset + 1) = (u_iyz.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 173 *(outbuffer + offset + 2) = (u_iyz.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 174 *(outbuffer + offset + 3) = (u_iyz.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 175 *(outbuffer + offset + 4) = (u_iyz.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 176 *(outbuffer + offset + 5) = (u_iyz.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 177 *(outbuffer + offset + 6) = (u_iyz.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 178 *(outbuffer + offset + 7) = (u_iyz.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 179 offset += sizeof(this->iyz);
garyservin 0:a906bb7c7831 180 union {
garyservin 0:a906bb7c7831 181 double real;
garyservin 0:a906bb7c7831 182 uint64_t base;
garyservin 0:a906bb7c7831 183 } u_izz;
garyservin 0:a906bb7c7831 184 u_izz.real = this->izz;
garyservin 0:a906bb7c7831 185 *(outbuffer + offset + 0) = (u_izz.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 186 *(outbuffer + offset + 1) = (u_izz.base >> (8 * 1)) & 0xFF;
garyservin 0:a906bb7c7831 187 *(outbuffer + offset + 2) = (u_izz.base >> (8 * 2)) & 0xFF;
garyservin 0:a906bb7c7831 188 *(outbuffer + offset + 3) = (u_izz.base >> (8 * 3)) & 0xFF;
garyservin 0:a906bb7c7831 189 *(outbuffer + offset + 4) = (u_izz.base >> (8 * 4)) & 0xFF;
garyservin 0:a906bb7c7831 190 *(outbuffer + offset + 5) = (u_izz.base >> (8 * 5)) & 0xFF;
garyservin 0:a906bb7c7831 191 *(outbuffer + offset + 6) = (u_izz.base >> (8 * 6)) & 0xFF;
garyservin 0:a906bb7c7831 192 *(outbuffer + offset + 7) = (u_izz.base >> (8 * 7)) & 0xFF;
garyservin 0:a906bb7c7831 193 offset += sizeof(this->izz);
garyservin 0:a906bb7c7831 194 union {
garyservin 0:a906bb7c7831 195 bool real;
garyservin 0:a906bb7c7831 196 uint8_t base;
garyservin 0:a906bb7c7831 197 } u_success;
garyservin 0:a906bb7c7831 198 u_success.real = this->success;
garyservin 0:a906bb7c7831 199 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
garyservin 0:a906bb7c7831 200 offset += sizeof(this->success);
garyservin 0:a906bb7c7831 201 uint32_t length_status_message = strlen(this->status_message);
garyservin 0:a906bb7c7831 202 memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
garyservin 0:a906bb7c7831 203 offset += 4;
garyservin 0:a906bb7c7831 204 memcpy(outbuffer + offset, this->status_message, length_status_message);
garyservin 0:a906bb7c7831 205 offset += length_status_message;
garyservin 0:a906bb7c7831 206 return offset;
garyservin 0:a906bb7c7831 207 }
garyservin 0:a906bb7c7831 208
garyservin 0:a906bb7c7831 209 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:a906bb7c7831 210 {
garyservin 0:a906bb7c7831 211 int offset = 0;
garyservin 0:a906bb7c7831 212 offset += this->com.deserialize(inbuffer + offset);
garyservin 0:a906bb7c7831 213 union {
garyservin 0:a906bb7c7831 214 bool real;
garyservin 0:a906bb7c7831 215 uint8_t base;
garyservin 0:a906bb7c7831 216 } u_gravity_mode;
garyservin 0:a906bb7c7831 217 u_gravity_mode.base = 0;
garyservin 0:a906bb7c7831 218 u_gravity_mode.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 219 this->gravity_mode = u_gravity_mode.real;
garyservin 0:a906bb7c7831 220 offset += sizeof(this->gravity_mode);
garyservin 0:a906bb7c7831 221 union {
garyservin 0:a906bb7c7831 222 double real;
garyservin 0:a906bb7c7831 223 uint64_t base;
garyservin 0:a906bb7c7831 224 } u_mass;
garyservin 0:a906bb7c7831 225 u_mass.base = 0;
garyservin 0:a906bb7c7831 226 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 227 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 228 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 229 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 230 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 231 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 232 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 233 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 234 this->mass = u_mass.real;
garyservin 0:a906bb7c7831 235 offset += sizeof(this->mass);
garyservin 0:a906bb7c7831 236 union {
garyservin 0:a906bb7c7831 237 double real;
garyservin 0:a906bb7c7831 238 uint64_t base;
garyservin 0:a906bb7c7831 239 } u_ixx;
garyservin 0:a906bb7c7831 240 u_ixx.base = 0;
garyservin 0:a906bb7c7831 241 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 242 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 243 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 244 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 245 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 246 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 247 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 248 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 249 this->ixx = u_ixx.real;
garyservin 0:a906bb7c7831 250 offset += sizeof(this->ixx);
garyservin 0:a906bb7c7831 251 union {
garyservin 0:a906bb7c7831 252 double real;
garyservin 0:a906bb7c7831 253 uint64_t base;
garyservin 0:a906bb7c7831 254 } u_ixy;
garyservin 0:a906bb7c7831 255 u_ixy.base = 0;
garyservin 0:a906bb7c7831 256 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 257 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 258 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 259 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 260 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 261 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 262 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 263 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 264 this->ixy = u_ixy.real;
garyservin 0:a906bb7c7831 265 offset += sizeof(this->ixy);
garyservin 0:a906bb7c7831 266 union {
garyservin 0:a906bb7c7831 267 double real;
garyservin 0:a906bb7c7831 268 uint64_t base;
garyservin 0:a906bb7c7831 269 } u_ixz;
garyservin 0:a906bb7c7831 270 u_ixz.base = 0;
garyservin 0:a906bb7c7831 271 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 272 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 273 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 274 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 275 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 276 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 277 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 278 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 279 this->ixz = u_ixz.real;
garyservin 0:a906bb7c7831 280 offset += sizeof(this->ixz);
garyservin 0:a906bb7c7831 281 union {
garyservin 0:a906bb7c7831 282 double real;
garyservin 0:a906bb7c7831 283 uint64_t base;
garyservin 0:a906bb7c7831 284 } u_iyy;
garyservin 0:a906bb7c7831 285 u_iyy.base = 0;
garyservin 0:a906bb7c7831 286 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 287 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 288 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 289 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 290 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 291 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 292 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 293 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 294 this->iyy = u_iyy.real;
garyservin 0:a906bb7c7831 295 offset += sizeof(this->iyy);
garyservin 0:a906bb7c7831 296 union {
garyservin 0:a906bb7c7831 297 double real;
garyservin 0:a906bb7c7831 298 uint64_t base;
garyservin 0:a906bb7c7831 299 } u_iyz;
garyservin 0:a906bb7c7831 300 u_iyz.base = 0;
garyservin 0:a906bb7c7831 301 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 302 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 303 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 304 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 305 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 306 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 307 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 308 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 309 this->iyz = u_iyz.real;
garyservin 0:a906bb7c7831 310 offset += sizeof(this->iyz);
garyservin 0:a906bb7c7831 311 union {
garyservin 0:a906bb7c7831 312 double real;
garyservin 0:a906bb7c7831 313 uint64_t base;
garyservin 0:a906bb7c7831 314 } u_izz;
garyservin 0:a906bb7c7831 315 u_izz.base = 0;
garyservin 0:a906bb7c7831 316 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 317 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:a906bb7c7831 318 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:a906bb7c7831 319 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:a906bb7c7831 320 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:a906bb7c7831 321 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:a906bb7c7831 322 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:a906bb7c7831 323 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:a906bb7c7831 324 this->izz = u_izz.real;
garyservin 0:a906bb7c7831 325 offset += sizeof(this->izz);
garyservin 0:a906bb7c7831 326 union {
garyservin 0:a906bb7c7831 327 bool real;
garyservin 0:a906bb7c7831 328 uint8_t base;
garyservin 0:a906bb7c7831 329 } u_success;
garyservin 0:a906bb7c7831 330 u_success.base = 0;
garyservin 0:a906bb7c7831 331 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:a906bb7c7831 332 this->success = u_success.real;
garyservin 0:a906bb7c7831 333 offset += sizeof(this->success);
garyservin 0:a906bb7c7831 334 uint32_t length_status_message;
garyservin 0:a906bb7c7831 335 memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:a906bb7c7831 336 offset += 4;
garyservin 0:a906bb7c7831 337 for(unsigned int k= offset; k< offset+length_status_message; ++k){
garyservin 0:a906bb7c7831 338 inbuffer[k-1]=inbuffer[k];
garyservin 0:a906bb7c7831 339 }
garyservin 0:a906bb7c7831 340 inbuffer[offset+length_status_message-1]=0;
garyservin 0:a906bb7c7831 341 this->status_message = (char *)(inbuffer + offset-1);
garyservin 0:a906bb7c7831 342 offset += length_status_message;
garyservin 0:a906bb7c7831 343 return offset;
garyservin 0:a906bb7c7831 344 }
garyservin 0:a906bb7c7831 345
garyservin 0:a906bb7c7831 346 const char * getType(){ return GETLINKPROPERTIES; };
garyservin 0:a906bb7c7831 347 const char * getMD5(){ return "a8619f92d17cfcc3958c0fd13299443d"; };
garyservin 0:a906bb7c7831 348
garyservin 0:a906bb7c7831 349 };
garyservin 0:a906bb7c7831 350
garyservin 0:a906bb7c7831 351 class GetLinkProperties {
garyservin 0:a906bb7c7831 352 public:
garyservin 0:a906bb7c7831 353 typedef GetLinkPropertiesRequest Request;
garyservin 0:a906bb7c7831 354 typedef GetLinkPropertiesResponse Response;
garyservin 0:a906bb7c7831 355 };
garyservin 0:a906bb7c7831 356
garyservin 0:a906bb7c7831 357 }
garyservin 0:a906bb7c7831 358 #endif