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