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_trajectory_msgs_JointTrajectoryPoint_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_trajectory_msgs_JointTrajectoryPoint_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 trajectory_msgs
Gary Servin 0:04ac6be8229a 11 {
Gary Servin 0:04ac6be8229a 12
Gary Servin 0:04ac6be8229a 13 class JointTrajectoryPoint : public ros::Msg
Gary Servin 0:04ac6be8229a 14 {
Gary Servin 0:04ac6be8229a 15 public:
Gary Servin 0:04ac6be8229a 16 uint32_t positions_length;
Gary Servin 0:04ac6be8229a 17 typedef double _positions_type;
Gary Servin 0:04ac6be8229a 18 _positions_type st_positions;
Gary Servin 0:04ac6be8229a 19 _positions_type * positions;
Gary Servin 0:04ac6be8229a 20 uint32_t velocities_length;
Gary Servin 0:04ac6be8229a 21 typedef double _velocities_type;
Gary Servin 0:04ac6be8229a 22 _velocities_type st_velocities;
Gary Servin 0:04ac6be8229a 23 _velocities_type * velocities;
Gary Servin 0:04ac6be8229a 24 uint32_t accelerations_length;
Gary Servin 0:04ac6be8229a 25 typedef double _accelerations_type;
Gary Servin 0:04ac6be8229a 26 _accelerations_type st_accelerations;
Gary Servin 0:04ac6be8229a 27 _accelerations_type * accelerations;
Gary Servin 0:04ac6be8229a 28 uint32_t effort_length;
Gary Servin 0:04ac6be8229a 29 typedef double _effort_type;
Gary Servin 0:04ac6be8229a 30 _effort_type st_effort;
Gary Servin 0:04ac6be8229a 31 _effort_type * effort;
Gary Servin 0:04ac6be8229a 32 typedef ros::Duration _time_from_start_type;
Gary Servin 0:04ac6be8229a 33 _time_from_start_type time_from_start;
Gary Servin 0:04ac6be8229a 34
Gary Servin 0:04ac6be8229a 35 JointTrajectoryPoint():
Gary Servin 0:04ac6be8229a 36 positions_length(0), positions(NULL),
Gary Servin 0:04ac6be8229a 37 velocities_length(0), velocities(NULL),
Gary Servin 0:04ac6be8229a 38 accelerations_length(0), accelerations(NULL),
Gary Servin 0:04ac6be8229a 39 effort_length(0), effort(NULL),
Gary Servin 0:04ac6be8229a 40 time_from_start()
Gary Servin 0:04ac6be8229a 41 {
Gary Servin 0:04ac6be8229a 42 }
Gary Servin 0:04ac6be8229a 43
Gary Servin 0:04ac6be8229a 44 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 45 {
Gary Servin 0:04ac6be8229a 46 int offset = 0;
Gary Servin 0:04ac6be8229a 47 *(outbuffer + offset + 0) = (this->positions_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 48 *(outbuffer + offset + 1) = (this->positions_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 49 *(outbuffer + offset + 2) = (this->positions_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 50 *(outbuffer + offset + 3) = (this->positions_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 51 offset += sizeof(this->positions_length);
Gary Servin 0:04ac6be8229a 52 for( uint32_t i = 0; i < positions_length; i++){
Gary Servin 0:04ac6be8229a 53 union {
Gary Servin 0:04ac6be8229a 54 double real;
Gary Servin 0:04ac6be8229a 55 uint64_t base;
Gary Servin 0:04ac6be8229a 56 } u_positionsi;
Gary Servin 0:04ac6be8229a 57 u_positionsi.real = this->positions[i];
Gary Servin 0:04ac6be8229a 58 *(outbuffer + offset + 0) = (u_positionsi.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 59 *(outbuffer + offset + 1) = (u_positionsi.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 60 *(outbuffer + offset + 2) = (u_positionsi.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 61 *(outbuffer + offset + 3) = (u_positionsi.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 62 *(outbuffer + offset + 4) = (u_positionsi.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 63 *(outbuffer + offset + 5) = (u_positionsi.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 64 *(outbuffer + offset + 6) = (u_positionsi.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 65 *(outbuffer + offset + 7) = (u_positionsi.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 66 offset += sizeof(this->positions[i]);
Gary Servin 0:04ac6be8229a 67 }
Gary Servin 0:04ac6be8229a 68 *(outbuffer + offset + 0) = (this->velocities_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 69 *(outbuffer + offset + 1) = (this->velocities_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 70 *(outbuffer + offset + 2) = (this->velocities_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 71 *(outbuffer + offset + 3) = (this->velocities_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 72 offset += sizeof(this->velocities_length);
Gary Servin 0:04ac6be8229a 73 for( uint32_t i = 0; i < velocities_length; i++){
Gary Servin 0:04ac6be8229a 74 union {
Gary Servin 0:04ac6be8229a 75 double real;
Gary Servin 0:04ac6be8229a 76 uint64_t base;
Gary Servin 0:04ac6be8229a 77 } u_velocitiesi;
Gary Servin 0:04ac6be8229a 78 u_velocitiesi.real = this->velocities[i];
Gary Servin 0:04ac6be8229a 79 *(outbuffer + offset + 0) = (u_velocitiesi.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 80 *(outbuffer + offset + 1) = (u_velocitiesi.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 81 *(outbuffer + offset + 2) = (u_velocitiesi.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 82 *(outbuffer + offset + 3) = (u_velocitiesi.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 83 *(outbuffer + offset + 4) = (u_velocitiesi.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 84 *(outbuffer + offset + 5) = (u_velocitiesi.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 85 *(outbuffer + offset + 6) = (u_velocitiesi.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 86 *(outbuffer + offset + 7) = (u_velocitiesi.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 87 offset += sizeof(this->velocities[i]);
Gary Servin 0:04ac6be8229a 88 }
Gary Servin 0:04ac6be8229a 89 *(outbuffer + offset + 0) = (this->accelerations_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 90 *(outbuffer + offset + 1) = (this->accelerations_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 91 *(outbuffer + offset + 2) = (this->accelerations_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 92 *(outbuffer + offset + 3) = (this->accelerations_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 93 offset += sizeof(this->accelerations_length);
Gary Servin 0:04ac6be8229a 94 for( uint32_t i = 0; i < accelerations_length; i++){
Gary Servin 0:04ac6be8229a 95 union {
Gary Servin 0:04ac6be8229a 96 double real;
Gary Servin 0:04ac6be8229a 97 uint64_t base;
Gary Servin 0:04ac6be8229a 98 } u_accelerationsi;
Gary Servin 0:04ac6be8229a 99 u_accelerationsi.real = this->accelerations[i];
Gary Servin 0:04ac6be8229a 100 *(outbuffer + offset + 0) = (u_accelerationsi.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 101 *(outbuffer + offset + 1) = (u_accelerationsi.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 102 *(outbuffer + offset + 2) = (u_accelerationsi.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 103 *(outbuffer + offset + 3) = (u_accelerationsi.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 104 *(outbuffer + offset + 4) = (u_accelerationsi.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 105 *(outbuffer + offset + 5) = (u_accelerationsi.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 106 *(outbuffer + offset + 6) = (u_accelerationsi.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 107 *(outbuffer + offset + 7) = (u_accelerationsi.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 108 offset += sizeof(this->accelerations[i]);
Gary Servin 0:04ac6be8229a 109 }
Gary Servin 0:04ac6be8229a 110 *(outbuffer + offset + 0) = (this->effort_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 111 *(outbuffer + offset + 1) = (this->effort_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 112 *(outbuffer + offset + 2) = (this->effort_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 113 *(outbuffer + offset + 3) = (this->effort_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 114 offset += sizeof(this->effort_length);
Gary Servin 0:04ac6be8229a 115 for( uint32_t i = 0; i < effort_length; i++){
Gary Servin 0:04ac6be8229a 116 union {
Gary Servin 0:04ac6be8229a 117 double real;
Gary Servin 0:04ac6be8229a 118 uint64_t base;
Gary Servin 0:04ac6be8229a 119 } u_efforti;
Gary Servin 0:04ac6be8229a 120 u_efforti.real = this->effort[i];
Gary Servin 0:04ac6be8229a 121 *(outbuffer + offset + 0) = (u_efforti.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 122 *(outbuffer + offset + 1) = (u_efforti.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 123 *(outbuffer + offset + 2) = (u_efforti.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 124 *(outbuffer + offset + 3) = (u_efforti.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 125 *(outbuffer + offset + 4) = (u_efforti.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 126 *(outbuffer + offset + 5) = (u_efforti.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 127 *(outbuffer + offset + 6) = (u_efforti.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 128 *(outbuffer + offset + 7) = (u_efforti.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 129 offset += sizeof(this->effort[i]);
Gary Servin 0:04ac6be8229a 130 }
Gary Servin 0:04ac6be8229a 131 *(outbuffer + offset + 0) = (this->time_from_start.sec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 132 *(outbuffer + offset + 1) = (this->time_from_start.sec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 133 *(outbuffer + offset + 2) = (this->time_from_start.sec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 134 *(outbuffer + offset + 3) = (this->time_from_start.sec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 135 offset += sizeof(this->time_from_start.sec);
Gary Servin 0:04ac6be8229a 136 *(outbuffer + offset + 0) = (this->time_from_start.nsec >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 137 *(outbuffer + offset + 1) = (this->time_from_start.nsec >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 138 *(outbuffer + offset + 2) = (this->time_from_start.nsec >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 139 *(outbuffer + offset + 3) = (this->time_from_start.nsec >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 140 offset += sizeof(this->time_from_start.nsec);
Gary Servin 0:04ac6be8229a 141 return offset;
Gary Servin 0:04ac6be8229a 142 }
Gary Servin 0:04ac6be8229a 143
Gary Servin 0:04ac6be8229a 144 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 145 {
Gary Servin 0:04ac6be8229a 146 int offset = 0;
Gary Servin 0:04ac6be8229a 147 uint32_t positions_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 148 positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 149 positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 150 positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 151 offset += sizeof(this->positions_length);
Gary Servin 0:04ac6be8229a 152 if(positions_lengthT > positions_length)
Gary Servin 0:04ac6be8229a 153 this->positions = (double*)realloc(this->positions, positions_lengthT * sizeof(double));
Gary Servin 0:04ac6be8229a 154 positions_length = positions_lengthT;
Gary Servin 0:04ac6be8229a 155 for( uint32_t i = 0; i < positions_length; i++){
Gary Servin 0:04ac6be8229a 156 union {
Gary Servin 0:04ac6be8229a 157 double real;
Gary Servin 0:04ac6be8229a 158 uint64_t base;
Gary Servin 0:04ac6be8229a 159 } u_st_positions;
Gary Servin 0:04ac6be8229a 160 u_st_positions.base = 0;
Gary Servin 0:04ac6be8229a 161 u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 162 u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 163 u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 164 u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 165 u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 166 u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 167 u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 168 u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 169 this->st_positions = u_st_positions.real;
Gary Servin 0:04ac6be8229a 170 offset += sizeof(this->st_positions);
Gary Servin 0:04ac6be8229a 171 memcpy( &(this->positions[i]), &(this->st_positions), sizeof(double));
Gary Servin 0:04ac6be8229a 172 }
Gary Servin 0:04ac6be8229a 173 uint32_t velocities_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 174 velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 175 velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 176 velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 177 offset += sizeof(this->velocities_length);
Gary Servin 0:04ac6be8229a 178 if(velocities_lengthT > velocities_length)
Gary Servin 0:04ac6be8229a 179 this->velocities = (double*)realloc(this->velocities, velocities_lengthT * sizeof(double));
Gary Servin 0:04ac6be8229a 180 velocities_length = velocities_lengthT;
Gary Servin 0:04ac6be8229a 181 for( uint32_t i = 0; i < velocities_length; i++){
Gary Servin 0:04ac6be8229a 182 union {
Gary Servin 0:04ac6be8229a 183 double real;
Gary Servin 0:04ac6be8229a 184 uint64_t base;
Gary Servin 0:04ac6be8229a 185 } u_st_velocities;
Gary Servin 0:04ac6be8229a 186 u_st_velocities.base = 0;
Gary Servin 0:04ac6be8229a 187 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 188 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 189 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 190 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 191 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 192 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 193 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 194 u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 195 this->st_velocities = u_st_velocities.real;
Gary Servin 0:04ac6be8229a 196 offset += sizeof(this->st_velocities);
Gary Servin 0:04ac6be8229a 197 memcpy( &(this->velocities[i]), &(this->st_velocities), sizeof(double));
Gary Servin 0:04ac6be8229a 198 }
Gary Servin 0:04ac6be8229a 199 uint32_t accelerations_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 200 accelerations_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 201 accelerations_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 202 accelerations_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 203 offset += sizeof(this->accelerations_length);
Gary Servin 0:04ac6be8229a 204 if(accelerations_lengthT > accelerations_length)
Gary Servin 0:04ac6be8229a 205 this->accelerations = (double*)realloc(this->accelerations, accelerations_lengthT * sizeof(double));
Gary Servin 0:04ac6be8229a 206 accelerations_length = accelerations_lengthT;
Gary Servin 0:04ac6be8229a 207 for( uint32_t i = 0; i < accelerations_length; i++){
Gary Servin 0:04ac6be8229a 208 union {
Gary Servin 0:04ac6be8229a 209 double real;
Gary Servin 0:04ac6be8229a 210 uint64_t base;
Gary Servin 0:04ac6be8229a 211 } u_st_accelerations;
Gary Servin 0:04ac6be8229a 212 u_st_accelerations.base = 0;
Gary Servin 0:04ac6be8229a 213 u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 214 u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 215 u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 216 u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 217 u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 218 u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 219 u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 220 u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 221 this->st_accelerations = u_st_accelerations.real;
Gary Servin 0:04ac6be8229a 222 offset += sizeof(this->st_accelerations);
Gary Servin 0:04ac6be8229a 223 memcpy( &(this->accelerations[i]), &(this->st_accelerations), sizeof(double));
Gary Servin 0:04ac6be8229a 224 }
Gary Servin 0:04ac6be8229a 225 uint32_t effort_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 226 effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 227 effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 228 effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 229 offset += sizeof(this->effort_length);
Gary Servin 0:04ac6be8229a 230 if(effort_lengthT > effort_length)
Gary Servin 0:04ac6be8229a 231 this->effort = (double*)realloc(this->effort, effort_lengthT * sizeof(double));
Gary Servin 0:04ac6be8229a 232 effort_length = effort_lengthT;
Gary Servin 0:04ac6be8229a 233 for( uint32_t i = 0; i < effort_length; i++){
Gary Servin 0:04ac6be8229a 234 union {
Gary Servin 0:04ac6be8229a 235 double real;
Gary Servin 0:04ac6be8229a 236 uint64_t base;
Gary Servin 0:04ac6be8229a 237 } u_st_effort;
Gary Servin 0:04ac6be8229a 238 u_st_effort.base = 0;
Gary Servin 0:04ac6be8229a 239 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 240 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 241 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 242 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 243 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 244 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 245 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 246 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 247 this->st_effort = u_st_effort.real;
Gary Servin 0:04ac6be8229a 248 offset += sizeof(this->st_effort);
Gary Servin 0:04ac6be8229a 249 memcpy( &(this->effort[i]), &(this->st_effort), sizeof(double));
Gary Servin 0:04ac6be8229a 250 }
Gary Servin 0:04ac6be8229a 251 this->time_from_start.sec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 252 this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 253 this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 254 this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 255 offset += sizeof(this->time_from_start.sec);
Gary Servin 0:04ac6be8229a 256 this->time_from_start.nsec = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 257 this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 258 this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 259 this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 260 offset += sizeof(this->time_from_start.nsec);
Gary Servin 0:04ac6be8229a 261 return offset;
Gary Servin 0:04ac6be8229a 262 }
Gary Servin 0:04ac6be8229a 263
Gary Servin 0:04ac6be8229a 264 const char * getType(){ return "trajectory_msgs/JointTrajectoryPoint"; };
Gary Servin 0:04ac6be8229a 265 const char * getMD5(){ return "f3cd1e1c4d320c79d6985c904ae5dcd3"; };
Gary Servin 0:04ac6be8229a 266
Gary Servin 0:04ac6be8229a 267 };
Gary Servin 0:04ac6be8229a 268
Gary Servin 0:04ac6be8229a 269 }
Gary Servin 0:04ac6be8229a 270 #endif