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_SERVICE_QueryTrajectoryState_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_SERVICE_QueryTrajectoryState_h
Gary Servin 0:04ac6be8229a 3 #include <stdint.h>
Gary Servin 0:04ac6be8229a 4 #include <string.h>
Gary Servin 0:04ac6be8229a 5 #include <stdlib.h>
Gary Servin 0:04ac6be8229a 6 #include "ros/msg.h"
Gary Servin 0:04ac6be8229a 7 #include "ros/time.h"
Gary Servin 0:04ac6be8229a 8
Gary Servin 0:04ac6be8229a 9 namespace control_msgs
Gary Servin 0:04ac6be8229a 10 {
Gary Servin 0:04ac6be8229a 11
Gary Servin 0:04ac6be8229a 12 static const char QUERYTRAJECTORYSTATE[] = "control_msgs/QueryTrajectoryState";
Gary Servin 0:04ac6be8229a 13
Gary Servin 0:04ac6be8229a 14 class QueryTrajectoryStateRequest : public ros::Msg
Gary Servin 0:04ac6be8229a 15 {
Gary Servin 0:04ac6be8229a 16 public:
Gary Servin 0:04ac6be8229a 17 typedef ros::Time _time_type;
Gary Servin 0:04ac6be8229a 18 _time_type time;
Gary Servin 0:04ac6be8229a 19
Gary Servin 0:04ac6be8229a 20 QueryTrajectoryStateRequest():
Gary Servin 0:04ac6be8229a 21 time()
Gary Servin 0:04ac6be8229a 22 {
Gary Servin 0:04ac6be8229a 23 }
Gary Servin 0:04ac6be8229a 24
Gary Servin 0:04ac6be8229a 25 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 26 {
Gary Servin 0:04ac6be8229a 27 int offset = 0;
Gary Servin 0:04ac6be8229a 28 *(outbuffer + offset + 0) = (this->time.sec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 29 *(outbuffer + offset + 1) = (this->time.sec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 30 *(outbuffer + offset + 2) = (this->time.sec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 31 *(outbuffer + offset + 3) = (this->time.sec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 32 offset += sizeof(this->time.sec);
Gary Servin 0:04ac6be8229a 33 *(outbuffer + offset + 0) = (this->time.nsec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 34 *(outbuffer + offset + 1) = (this->time.nsec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 35 *(outbuffer + offset + 2) = (this->time.nsec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 36 *(outbuffer + offset + 3) = (this->time.nsec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 37 offset += sizeof(this->time.nsec);
Gary Servin 0:04ac6be8229a 38 return offset;
Gary Servin 0:04ac6be8229a 39 }
Gary Servin 0:04ac6be8229a 40
Gary Servin 0:04ac6be8229a 41 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 42 {
Gary Servin 0:04ac6be8229a 43 int offset = 0;
Gary Servin 0:04ac6be8229a 44 this->time.sec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 45 this->time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 46 this->time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 47 this->time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 48 offset += sizeof(this->time.sec);
Gary Servin 0:04ac6be8229a 49 this->time.nsec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 50 this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 51 this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 52 this->time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 53 offset += sizeof(this->time.nsec);
Gary Servin 0:04ac6be8229a 54 return offset;
Gary Servin 0:04ac6be8229a 55 }
Gary Servin 0:04ac6be8229a 56
Gary Servin 0:04ac6be8229a 57 const char * getType(){ return QUERYTRAJECTORYSTATE; };
Gary Servin 0:04ac6be8229a 58 const char * getMD5(){ return "556a4fb76023a469987922359d08a844"; };
Gary Servin 0:04ac6be8229a 59
Gary Servin 0:04ac6be8229a 60 };
Gary Servin 0:04ac6be8229a 61
Gary Servin 0:04ac6be8229a 62 class QueryTrajectoryStateResponse : public ros::Msg
Gary Servin 0:04ac6be8229a 63 {
Gary Servin 0:04ac6be8229a 64 public:
Gary Servin 0:04ac6be8229a 65 uint32_t name_length;
Gary Servin 0:04ac6be8229a 66 typedef char* _name_type;
Gary Servin 0:04ac6be8229a 67 _name_type st_name;
Gary Servin 0:04ac6be8229a 68 _name_type * name;
Gary Servin 0:04ac6be8229a 69 uint32_t position_length;
Gary Servin 0:04ac6be8229a 70 typedef double _position_type;
Gary Servin 0:04ac6be8229a 71 _position_type st_position;
Gary Servin 0:04ac6be8229a 72 _position_type * position;
Gary Servin 0:04ac6be8229a 73 uint32_t velocity_length;
Gary Servin 0:04ac6be8229a 74 typedef double _velocity_type;
Gary Servin 0:04ac6be8229a 75 _velocity_type st_velocity;
Gary Servin 0:04ac6be8229a 76 _velocity_type * velocity;
Gary Servin 0:04ac6be8229a 77 uint32_t acceleration_length;
Gary Servin 0:04ac6be8229a 78 typedef double _acceleration_type;
Gary Servin 0:04ac6be8229a 79 _acceleration_type st_acceleration;
Gary Servin 0:04ac6be8229a 80 _acceleration_type * acceleration;
Gary Servin 0:04ac6be8229a 81
Gary Servin 0:04ac6be8229a 82 QueryTrajectoryStateResponse():
Gary Servin 0:04ac6be8229a 83 name_length(0), name(NULL),
Gary Servin 0:04ac6be8229a 84 position_length(0), position(NULL),
Gary Servin 0:04ac6be8229a 85 velocity_length(0), velocity(NULL),
Gary Servin 0:04ac6be8229a 86 acceleration_length(0), acceleration(NULL)
Gary Servin 0:04ac6be8229a 87 {
Gary Servin 0:04ac6be8229a 88 }
Gary Servin 0:04ac6be8229a 89
Gary Servin 0:04ac6be8229a 90 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 91 {
Gary Servin 0:04ac6be8229a 92 int offset = 0;
Gary Servin 0:04ac6be8229a 93 *(outbuffer + offset + 0) = (this->name_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 94 *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 95 *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 96 *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 97 offset += sizeof(this->name_length);
Gary Servin 0:04ac6be8229a 98 for( uint32_t i = 0; i < name_length; i++){
Gary Servin 0:04ac6be8229a 99 uint32_t length_namei = strlen(this->name[i]);
Gary Servin 0:04ac6be8229a 100 varToArr(outbuffer + offset, length_namei);
Gary Servin 0:04ac6be8229a 101 offset += 4;
Gary Servin 0:04ac6be8229a 102 memcpy(outbuffer + offset, this->name[i], length_namei);
Gary Servin 0:04ac6be8229a 103 offset += length_namei;
Gary Servin 0:04ac6be8229a 104 }
Gary Servin 0:04ac6be8229a 105 *(outbuffer + offset + 0) = (this->position_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 106 *(outbuffer + offset + 1) = (this->position_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 107 *(outbuffer + offset + 2) = (this->position_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 108 *(outbuffer + offset + 3) = (this->position_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 109 offset += sizeof(this->position_length);
Gary Servin 0:04ac6be8229a 110 for( uint32_t i = 0; i < position_length; i++){
Gary Servin 0:04ac6be8229a 111 union {
Gary Servin 0:04ac6be8229a 112 double real;
Gary Servin 0:04ac6be8229a 113 uint64_t base;
Gary Servin 0:04ac6be8229a 114 } u_positioni;
Gary Servin 0:04ac6be8229a 115 u_positioni.real = this->position[i];
Gary Servin 0:04ac6be8229a 116 *(outbuffer + offset + 0) = (u_positioni.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 117 *(outbuffer + offset + 1) = (u_positioni.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 118 *(outbuffer + offset + 2) = (u_positioni.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 119 *(outbuffer + offset + 3) = (u_positioni.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 120 *(outbuffer + offset + 4) = (u_positioni.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 121 *(outbuffer + offset + 5) = (u_positioni.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 122 *(outbuffer + offset + 6) = (u_positioni.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 123 *(outbuffer + offset + 7) = (u_positioni.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 124 offset += sizeof(this->position[i]);
Gary Servin 0:04ac6be8229a 125 }
Gary Servin 0:04ac6be8229a 126 *(outbuffer + offset + 0) = (this->velocity_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 127 *(outbuffer + offset + 1) = (this->velocity_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 128 *(outbuffer + offset + 2) = (this->velocity_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 129 *(outbuffer + offset + 3) = (this->velocity_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 130 offset += sizeof(this->velocity_length);
Gary Servin 0:04ac6be8229a 131 for( uint32_t i = 0; i < velocity_length; i++){
Gary Servin 0:04ac6be8229a 132 union {
Gary Servin 0:04ac6be8229a 133 double real;
Gary Servin 0:04ac6be8229a 134 uint64_t base;
Gary Servin 0:04ac6be8229a 135 } u_velocityi;
Gary Servin 0:04ac6be8229a 136 u_velocityi.real = this->velocity[i];
Gary Servin 0:04ac6be8229a 137 *(outbuffer + offset + 0) = (u_velocityi.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 138 *(outbuffer + offset + 1) = (u_velocityi.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 139 *(outbuffer + offset + 2) = (u_velocityi.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 140 *(outbuffer + offset + 3) = (u_velocityi.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 141 *(outbuffer + offset + 4) = (u_velocityi.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 142 *(outbuffer + offset + 5) = (u_velocityi.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 143 *(outbuffer + offset + 6) = (u_velocityi.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 144 *(outbuffer + offset + 7) = (u_velocityi.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 145 offset += sizeof(this->velocity[i]);
Gary Servin 0:04ac6be8229a 146 }
Gary Servin 0:04ac6be8229a 147 *(outbuffer + offset + 0) = (this->acceleration_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 148 *(outbuffer + offset + 1) = (this->acceleration_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 149 *(outbuffer + offset + 2) = (this->acceleration_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 150 *(outbuffer + offset + 3) = (this->acceleration_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 151 offset += sizeof(this->acceleration_length);
Gary Servin 0:04ac6be8229a 152 for( uint32_t i = 0; i < acceleration_length; i++){
Gary Servin 0:04ac6be8229a 153 union {
Gary Servin 0:04ac6be8229a 154 double real;
Gary Servin 0:04ac6be8229a 155 uint64_t base;
Gary Servin 0:04ac6be8229a 156 } u_accelerationi;
Gary Servin 0:04ac6be8229a 157 u_accelerationi.real = this->acceleration[i];
Gary Servin 0:04ac6be8229a 158 *(outbuffer + offset + 0) = (u_accelerationi.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 159 *(outbuffer + offset + 1) = (u_accelerationi.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 160 *(outbuffer + offset + 2) = (u_accelerationi.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 161 *(outbuffer + offset + 3) = (u_accelerationi.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 162 *(outbuffer + offset + 4) = (u_accelerationi.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 163 *(outbuffer + offset + 5) = (u_accelerationi.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 164 *(outbuffer + offset + 6) = (u_accelerationi.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 165 *(outbuffer + offset + 7) = (u_accelerationi.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 166 offset += sizeof(this->acceleration[i]);
Gary Servin 0:04ac6be8229a 167 }
Gary Servin 0:04ac6be8229a 168 return offset;
Gary Servin 0:04ac6be8229a 169 }
Gary Servin 0:04ac6be8229a 170
Gary Servin 0:04ac6be8229a 171 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 172 {
Gary Servin 0:04ac6be8229a 173 int offset = 0;
Gary Servin 0:04ac6be8229a 174 uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 175 name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 176 name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 177 name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 178 offset += sizeof(this->name_length);
Gary Servin 0:04ac6be8229a 179 if(name_lengthT > name_length)
Gary Servin 0:04ac6be8229a 180 this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
Gary Servin 0:04ac6be8229a 181 name_length = name_lengthT;
Gary Servin 0:04ac6be8229a 182 for( uint32_t i = 0; i < name_length; i++){
Gary Servin 0:04ac6be8229a 183 uint32_t length_st_name;
Gary Servin 0:04ac6be8229a 184 arrToVar(length_st_name, (inbuffer + offset));
Gary Servin 0:04ac6be8229a 185 offset += 4;
Gary Servin 0:04ac6be8229a 186 for(unsigned int k= offset; k< offset+length_st_name; ++k){
Gary Servin 0:04ac6be8229a 187 inbuffer[k-1]=inbuffer[k];
Gary Servin 0:04ac6be8229a 188 }
Gary Servin 0:04ac6be8229a 189 inbuffer[offset+length_st_name-1]=0;
Gary Servin 0:04ac6be8229a 190 this->st_name = (char *)(inbuffer + offset-1);
Gary Servin 0:04ac6be8229a 191 offset += length_st_name;
Gary Servin 0:04ac6be8229a 192 memcpy( &(this->name[i]), &(this->st_name), sizeof(char*));
Gary Servin 0:04ac6be8229a 193 }
Gary Servin 0:04ac6be8229a 194 uint32_t position_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 195 position_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 196 position_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 197 position_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 198 offset += sizeof(this->position_length);
Gary Servin 0:04ac6be8229a 199 if(position_lengthT > position_length)
Gary Servin 0:04ac6be8229a 200 this->position = (double*)realloc(this->position, position_lengthT * sizeof(double));
Gary Servin 0:04ac6be8229a 201 position_length = position_lengthT;
Gary Servin 0:04ac6be8229a 202 for( uint32_t i = 0; i < position_length; i++){
Gary Servin 0:04ac6be8229a 203 union {
Gary Servin 0:04ac6be8229a 204 double real;
Gary Servin 0:04ac6be8229a 205 uint64_t base;
Gary Servin 0:04ac6be8229a 206 } u_st_position;
Gary Servin 0:04ac6be8229a 207 u_st_position.base = 0;
Gary Servin 0:04ac6be8229a 208 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 209 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 210 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 211 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 212 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 213 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 214 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 215 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 216 this->st_position = u_st_position.real;
Gary Servin 0:04ac6be8229a 217 offset += sizeof(this->st_position);
Gary Servin 0:04ac6be8229a 218 memcpy( &(this->position[i]), &(this->st_position), sizeof(double));
Gary Servin 0:04ac6be8229a 219 }
Gary Servin 0:04ac6be8229a 220 uint32_t velocity_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 221 velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 222 velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 223 velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 224 offset += sizeof(this->velocity_length);
Gary Servin 0:04ac6be8229a 225 if(velocity_lengthT > velocity_length)
Gary Servin 0:04ac6be8229a 226 this->velocity = (double*)realloc(this->velocity, velocity_lengthT * sizeof(double));
Gary Servin 0:04ac6be8229a 227 velocity_length = velocity_lengthT;
Gary Servin 0:04ac6be8229a 228 for( uint32_t i = 0; i < velocity_length; i++){
Gary Servin 0:04ac6be8229a 229 union {
Gary Servin 0:04ac6be8229a 230 double real;
Gary Servin 0:04ac6be8229a 231 uint64_t base;
Gary Servin 0:04ac6be8229a 232 } u_st_velocity;
Gary Servin 0:04ac6be8229a 233 u_st_velocity.base = 0;
Gary Servin 0:04ac6be8229a 234 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 235 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 236 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 237 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 238 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 239 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 240 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 241 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 242 this->st_velocity = u_st_velocity.real;
Gary Servin 0:04ac6be8229a 243 offset += sizeof(this->st_velocity);
Gary Servin 0:04ac6be8229a 244 memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(double));
Gary Servin 0:04ac6be8229a 245 }
Gary Servin 0:04ac6be8229a 246 uint32_t acceleration_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 247 acceleration_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 248 acceleration_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 249 acceleration_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 250 offset += sizeof(this->acceleration_length);
Gary Servin 0:04ac6be8229a 251 if(acceleration_lengthT > acceleration_length)
Gary Servin 0:04ac6be8229a 252 this->acceleration = (double*)realloc(this->acceleration, acceleration_lengthT * sizeof(double));
Gary Servin 0:04ac6be8229a 253 acceleration_length = acceleration_lengthT;
Gary Servin 0:04ac6be8229a 254 for( uint32_t i = 0; i < acceleration_length; i++){
Gary Servin 0:04ac6be8229a 255 union {
Gary Servin 0:04ac6be8229a 256 double real;
Gary Servin 0:04ac6be8229a 257 uint64_t base;
Gary Servin 0:04ac6be8229a 258 } u_st_acceleration;
Gary Servin 0:04ac6be8229a 259 u_st_acceleration.base = 0;
Gary Servin 0:04ac6be8229a 260 u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 261 u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 262 u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 263 u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 264 u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 265 u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 266 u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 267 u_st_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 268 this->st_acceleration = u_st_acceleration.real;
Gary Servin 0:04ac6be8229a 269 offset += sizeof(this->st_acceleration);
Gary Servin 0:04ac6be8229a 270 memcpy( &(this->acceleration[i]), &(this->st_acceleration), sizeof(double));
Gary Servin 0:04ac6be8229a 271 }
Gary Servin 0:04ac6be8229a 272 return offset;
Gary Servin 0:04ac6be8229a 273 }
Gary Servin 0:04ac6be8229a 274
Gary Servin 0:04ac6be8229a 275 const char * getType(){ return QUERYTRAJECTORYSTATE; };
Gary Servin 0:04ac6be8229a 276 const char * getMD5(){ return "1f1a6554ad060f44d013e71868403c1a"; };
Gary Servin 0:04ac6be8229a 277
Gary Servin 0:04ac6be8229a 278 };
Gary Servin 0:04ac6be8229a 279
Gary Servin 0:04ac6be8229a 280 class QueryTrajectoryState {
Gary Servin 0:04ac6be8229a 281 public:
Gary Servin 0:04ac6be8229a 282 typedef QueryTrajectoryStateRequest Request;
Gary Servin 0:04ac6be8229a 283 typedef QueryTrajectoryStateResponse Response;
Gary Servin 0:04ac6be8229a 284 };
Gary Servin 0:04ac6be8229a 285
Gary Servin 0:04ac6be8229a 286 }
Gary Servin 0:04ac6be8229a 287 #endif