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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_kinetic s-rov-firmware ROS_HCSR04 DISCO-F469NI_LCDTS_demo ... more

ROSSerial_mbed for Kinetic 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_kinetic

rosserial_mbed Hello World example for Kinetic Kame 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:
Sat Dec 31 00:59:58 2016 +0000
Revision:
1:a849bf78d77f
Parent:
0:9e9b7db60fd5
Add missing round() method

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 #ifndef _ROS_sensor_msgs_BatteryState_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_sensor_msgs_BatteryState_h
garyservin 0:9e9b7db60fd5 3
garyservin 0:9e9b7db60fd5 4 #include <stdint.h>
garyservin 0:9e9b7db60fd5 5 #include <string.h>
garyservin 0:9e9b7db60fd5 6 #include <stdlib.h>
garyservin 0:9e9b7db60fd5 7 #include "ros/msg.h"
garyservin 0:9e9b7db60fd5 8 #include "std_msgs/Header.h"
garyservin 0:9e9b7db60fd5 9
garyservin 0:9e9b7db60fd5 10 namespace sensor_msgs
garyservin 0:9e9b7db60fd5 11 {
garyservin 0:9e9b7db60fd5 12
garyservin 0:9e9b7db60fd5 13 class BatteryState : public ros::Msg
garyservin 0:9e9b7db60fd5 14 {
garyservin 0:9e9b7db60fd5 15 public:
garyservin 0:9e9b7db60fd5 16 typedef std_msgs::Header _header_type;
garyservin 0:9e9b7db60fd5 17 _header_type header;
garyservin 0:9e9b7db60fd5 18 typedef float _voltage_type;
garyservin 0:9e9b7db60fd5 19 _voltage_type voltage;
garyservin 0:9e9b7db60fd5 20 typedef float _current_type;
garyservin 0:9e9b7db60fd5 21 _current_type current;
garyservin 0:9e9b7db60fd5 22 typedef float _charge_type;
garyservin 0:9e9b7db60fd5 23 _charge_type charge;
garyservin 0:9e9b7db60fd5 24 typedef float _capacity_type;
garyservin 0:9e9b7db60fd5 25 _capacity_type capacity;
garyservin 0:9e9b7db60fd5 26 typedef float _design_capacity_type;
garyservin 0:9e9b7db60fd5 27 _design_capacity_type design_capacity;
garyservin 0:9e9b7db60fd5 28 typedef float _percentage_type;
garyservin 0:9e9b7db60fd5 29 _percentage_type percentage;
garyservin 0:9e9b7db60fd5 30 typedef uint8_t _power_supply_status_type;
garyservin 0:9e9b7db60fd5 31 _power_supply_status_type power_supply_status;
garyservin 0:9e9b7db60fd5 32 typedef uint8_t _power_supply_health_type;
garyservin 0:9e9b7db60fd5 33 _power_supply_health_type power_supply_health;
garyservin 0:9e9b7db60fd5 34 typedef uint8_t _power_supply_technology_type;
garyservin 0:9e9b7db60fd5 35 _power_supply_technology_type power_supply_technology;
garyservin 0:9e9b7db60fd5 36 typedef bool _present_type;
garyservin 0:9e9b7db60fd5 37 _present_type present;
garyservin 0:9e9b7db60fd5 38 uint32_t cell_voltage_length;
garyservin 0:9e9b7db60fd5 39 typedef float _cell_voltage_type;
garyservin 0:9e9b7db60fd5 40 _cell_voltage_type st_cell_voltage;
garyservin 0:9e9b7db60fd5 41 _cell_voltage_type * cell_voltage;
garyservin 0:9e9b7db60fd5 42 typedef const char* _location_type;
garyservin 0:9e9b7db60fd5 43 _location_type location;
garyservin 0:9e9b7db60fd5 44 typedef const char* _serial_number_type;
garyservin 0:9e9b7db60fd5 45 _serial_number_type serial_number;
garyservin 0:9e9b7db60fd5 46 enum { POWER_SUPPLY_STATUS_UNKNOWN = 0 };
garyservin 0:9e9b7db60fd5 47 enum { POWER_SUPPLY_STATUS_CHARGING = 1 };
garyservin 0:9e9b7db60fd5 48 enum { POWER_SUPPLY_STATUS_DISCHARGING = 2 };
garyservin 0:9e9b7db60fd5 49 enum { POWER_SUPPLY_STATUS_NOT_CHARGING = 3 };
garyservin 0:9e9b7db60fd5 50 enum { POWER_SUPPLY_STATUS_FULL = 4 };
garyservin 0:9e9b7db60fd5 51 enum { POWER_SUPPLY_HEALTH_UNKNOWN = 0 };
garyservin 0:9e9b7db60fd5 52 enum { POWER_SUPPLY_HEALTH_GOOD = 1 };
garyservin 0:9e9b7db60fd5 53 enum { POWER_SUPPLY_HEALTH_OVERHEAT = 2 };
garyservin 0:9e9b7db60fd5 54 enum { POWER_SUPPLY_HEALTH_DEAD = 3 };
garyservin 0:9e9b7db60fd5 55 enum { POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4 };
garyservin 0:9e9b7db60fd5 56 enum { POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5 };
garyservin 0:9e9b7db60fd5 57 enum { POWER_SUPPLY_HEALTH_COLD = 6 };
garyservin 0:9e9b7db60fd5 58 enum { POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7 };
garyservin 0:9e9b7db60fd5 59 enum { POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8 };
garyservin 0:9e9b7db60fd5 60 enum { POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0 };
garyservin 0:9e9b7db60fd5 61 enum { POWER_SUPPLY_TECHNOLOGY_NIMH = 1 };
garyservin 0:9e9b7db60fd5 62 enum { POWER_SUPPLY_TECHNOLOGY_LION = 2 };
garyservin 0:9e9b7db60fd5 63 enum { POWER_SUPPLY_TECHNOLOGY_LIPO = 3 };
garyservin 0:9e9b7db60fd5 64 enum { POWER_SUPPLY_TECHNOLOGY_LIFE = 4 };
garyservin 0:9e9b7db60fd5 65 enum { POWER_SUPPLY_TECHNOLOGY_NICD = 5 };
garyservin 0:9e9b7db60fd5 66 enum { POWER_SUPPLY_TECHNOLOGY_LIMN = 6 };
garyservin 0:9e9b7db60fd5 67
garyservin 0:9e9b7db60fd5 68 BatteryState():
garyservin 0:9e9b7db60fd5 69 header(),
garyservin 0:9e9b7db60fd5 70 voltage(0),
garyservin 0:9e9b7db60fd5 71 current(0),
garyservin 0:9e9b7db60fd5 72 charge(0),
garyservin 0:9e9b7db60fd5 73 capacity(0),
garyservin 0:9e9b7db60fd5 74 design_capacity(0),
garyservin 0:9e9b7db60fd5 75 percentage(0),
garyservin 0:9e9b7db60fd5 76 power_supply_status(0),
garyservin 0:9e9b7db60fd5 77 power_supply_health(0),
garyservin 0:9e9b7db60fd5 78 power_supply_technology(0),
garyservin 0:9e9b7db60fd5 79 present(0),
garyservin 0:9e9b7db60fd5 80 cell_voltage_length(0), cell_voltage(NULL),
garyservin 0:9e9b7db60fd5 81 location(""),
garyservin 0:9e9b7db60fd5 82 serial_number("")
garyservin 0:9e9b7db60fd5 83 {
garyservin 0:9e9b7db60fd5 84 }
garyservin 0:9e9b7db60fd5 85
garyservin 0:9e9b7db60fd5 86 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 87 {
garyservin 0:9e9b7db60fd5 88 int offset = 0;
garyservin 0:9e9b7db60fd5 89 offset += this->header.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 90 union {
garyservin 0:9e9b7db60fd5 91 float real;
garyservin 0:9e9b7db60fd5 92 uint32_t base;
garyservin 0:9e9b7db60fd5 93 } u_voltage;
garyservin 0:9e9b7db60fd5 94 u_voltage.real = this->voltage;
garyservin 0:9e9b7db60fd5 95 *(outbuffer + offset + 0) = (u_voltage.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 96 *(outbuffer + offset + 1) = (u_voltage.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 97 *(outbuffer + offset + 2) = (u_voltage.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 98 *(outbuffer + offset + 3) = (u_voltage.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 99 offset += sizeof(this->voltage);
garyservin 0:9e9b7db60fd5 100 union {
garyservin 0:9e9b7db60fd5 101 float real;
garyservin 0:9e9b7db60fd5 102 uint32_t base;
garyservin 0:9e9b7db60fd5 103 } u_current;
garyservin 0:9e9b7db60fd5 104 u_current.real = this->current;
garyservin 0:9e9b7db60fd5 105 *(outbuffer + offset + 0) = (u_current.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 106 *(outbuffer + offset + 1) = (u_current.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 107 *(outbuffer + offset + 2) = (u_current.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 108 *(outbuffer + offset + 3) = (u_current.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 109 offset += sizeof(this->current);
garyservin 0:9e9b7db60fd5 110 union {
garyservin 0:9e9b7db60fd5 111 float real;
garyservin 0:9e9b7db60fd5 112 uint32_t base;
garyservin 0:9e9b7db60fd5 113 } u_charge;
garyservin 0:9e9b7db60fd5 114 u_charge.real = this->charge;
garyservin 0:9e9b7db60fd5 115 *(outbuffer + offset + 0) = (u_charge.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 116 *(outbuffer + offset + 1) = (u_charge.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 117 *(outbuffer + offset + 2) = (u_charge.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 118 *(outbuffer + offset + 3) = (u_charge.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 119 offset += sizeof(this->charge);
garyservin 0:9e9b7db60fd5 120 union {
garyservin 0:9e9b7db60fd5 121 float real;
garyservin 0:9e9b7db60fd5 122 uint32_t base;
garyservin 0:9e9b7db60fd5 123 } u_capacity;
garyservin 0:9e9b7db60fd5 124 u_capacity.real = this->capacity;
garyservin 0:9e9b7db60fd5 125 *(outbuffer + offset + 0) = (u_capacity.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 126 *(outbuffer + offset + 1) = (u_capacity.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 127 *(outbuffer + offset + 2) = (u_capacity.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 128 *(outbuffer + offset + 3) = (u_capacity.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 129 offset += sizeof(this->capacity);
garyservin 0:9e9b7db60fd5 130 union {
garyservin 0:9e9b7db60fd5 131 float real;
garyservin 0:9e9b7db60fd5 132 uint32_t base;
garyservin 0:9e9b7db60fd5 133 } u_design_capacity;
garyservin 0:9e9b7db60fd5 134 u_design_capacity.real = this->design_capacity;
garyservin 0:9e9b7db60fd5 135 *(outbuffer + offset + 0) = (u_design_capacity.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 136 *(outbuffer + offset + 1) = (u_design_capacity.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 137 *(outbuffer + offset + 2) = (u_design_capacity.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 138 *(outbuffer + offset + 3) = (u_design_capacity.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 139 offset += sizeof(this->design_capacity);
garyservin 0:9e9b7db60fd5 140 union {
garyservin 0:9e9b7db60fd5 141 float real;
garyservin 0:9e9b7db60fd5 142 uint32_t base;
garyservin 0:9e9b7db60fd5 143 } u_percentage;
garyservin 0:9e9b7db60fd5 144 u_percentage.real = this->percentage;
garyservin 0:9e9b7db60fd5 145 *(outbuffer + offset + 0) = (u_percentage.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 146 *(outbuffer + offset + 1) = (u_percentage.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 147 *(outbuffer + offset + 2) = (u_percentage.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 148 *(outbuffer + offset + 3) = (u_percentage.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 149 offset += sizeof(this->percentage);
garyservin 0:9e9b7db60fd5 150 *(outbuffer + offset + 0) = (this->power_supply_status >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 151 offset += sizeof(this->power_supply_status);
garyservin 0:9e9b7db60fd5 152 *(outbuffer + offset + 0) = (this->power_supply_health >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 153 offset += sizeof(this->power_supply_health);
garyservin 0:9e9b7db60fd5 154 *(outbuffer + offset + 0) = (this->power_supply_technology >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 155 offset += sizeof(this->power_supply_technology);
garyservin 0:9e9b7db60fd5 156 union {
garyservin 0:9e9b7db60fd5 157 bool real;
garyservin 0:9e9b7db60fd5 158 uint8_t base;
garyservin 0:9e9b7db60fd5 159 } u_present;
garyservin 0:9e9b7db60fd5 160 u_present.real = this->present;
garyservin 0:9e9b7db60fd5 161 *(outbuffer + offset + 0) = (u_present.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 162 offset += sizeof(this->present);
garyservin 0:9e9b7db60fd5 163 *(outbuffer + offset + 0) = (this->cell_voltage_length >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 164 *(outbuffer + offset + 1) = (this->cell_voltage_length >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 165 *(outbuffer + offset + 2) = (this->cell_voltage_length >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 166 *(outbuffer + offset + 3) = (this->cell_voltage_length >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 167 offset += sizeof(this->cell_voltage_length);
garyservin 0:9e9b7db60fd5 168 for( uint32_t i = 0; i < cell_voltage_length; i++){
garyservin 0:9e9b7db60fd5 169 union {
garyservin 0:9e9b7db60fd5 170 float real;
garyservin 0:9e9b7db60fd5 171 uint32_t base;
garyservin 0:9e9b7db60fd5 172 } u_cell_voltagei;
garyservin 0:9e9b7db60fd5 173 u_cell_voltagei.real = this->cell_voltage[i];
garyservin 0:9e9b7db60fd5 174 *(outbuffer + offset + 0) = (u_cell_voltagei.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 175 *(outbuffer + offset + 1) = (u_cell_voltagei.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 176 *(outbuffer + offset + 2) = (u_cell_voltagei.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 177 *(outbuffer + offset + 3) = (u_cell_voltagei.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 178 offset += sizeof(this->cell_voltage[i]);
garyservin 0:9e9b7db60fd5 179 }
garyservin 0:9e9b7db60fd5 180 uint32_t length_location = strlen(this->location);
garyservin 0:9e9b7db60fd5 181 varToArr(outbuffer + offset, length_location);
garyservin 0:9e9b7db60fd5 182 offset += 4;
garyservin 0:9e9b7db60fd5 183 memcpy(outbuffer + offset, this->location, length_location);
garyservin 0:9e9b7db60fd5 184 offset += length_location;
garyservin 0:9e9b7db60fd5 185 uint32_t length_serial_number = strlen(this->serial_number);
garyservin 0:9e9b7db60fd5 186 varToArr(outbuffer + offset, length_serial_number);
garyservin 0:9e9b7db60fd5 187 offset += 4;
garyservin 0:9e9b7db60fd5 188 memcpy(outbuffer + offset, this->serial_number, length_serial_number);
garyservin 0:9e9b7db60fd5 189 offset += length_serial_number;
garyservin 0:9e9b7db60fd5 190 return offset;
garyservin 0:9e9b7db60fd5 191 }
garyservin 0:9e9b7db60fd5 192
garyservin 0:9e9b7db60fd5 193 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 194 {
garyservin 0:9e9b7db60fd5 195 int offset = 0;
garyservin 0:9e9b7db60fd5 196 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 197 union {
garyservin 0:9e9b7db60fd5 198 float real;
garyservin 0:9e9b7db60fd5 199 uint32_t base;
garyservin 0:9e9b7db60fd5 200 } u_voltage;
garyservin 0:9e9b7db60fd5 201 u_voltage.base = 0;
garyservin 0:9e9b7db60fd5 202 u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 203 u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 204 u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 205 u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 206 this->voltage = u_voltage.real;
garyservin 0:9e9b7db60fd5 207 offset += sizeof(this->voltage);
garyservin 0:9e9b7db60fd5 208 union {
garyservin 0:9e9b7db60fd5 209 float real;
garyservin 0:9e9b7db60fd5 210 uint32_t base;
garyservin 0:9e9b7db60fd5 211 } u_current;
garyservin 0:9e9b7db60fd5 212 u_current.base = 0;
garyservin 0:9e9b7db60fd5 213 u_current.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 214 u_current.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 215 u_current.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 216 u_current.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 217 this->current = u_current.real;
garyservin 0:9e9b7db60fd5 218 offset += sizeof(this->current);
garyservin 0:9e9b7db60fd5 219 union {
garyservin 0:9e9b7db60fd5 220 float real;
garyservin 0:9e9b7db60fd5 221 uint32_t base;
garyservin 0:9e9b7db60fd5 222 } u_charge;
garyservin 0:9e9b7db60fd5 223 u_charge.base = 0;
garyservin 0:9e9b7db60fd5 224 u_charge.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 225 u_charge.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 226 u_charge.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 227 u_charge.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 228 this->charge = u_charge.real;
garyservin 0:9e9b7db60fd5 229 offset += sizeof(this->charge);
garyservin 0:9e9b7db60fd5 230 union {
garyservin 0:9e9b7db60fd5 231 float real;
garyservin 0:9e9b7db60fd5 232 uint32_t base;
garyservin 0:9e9b7db60fd5 233 } u_capacity;
garyservin 0:9e9b7db60fd5 234 u_capacity.base = 0;
garyservin 0:9e9b7db60fd5 235 u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 236 u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 237 u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 238 u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 239 this->capacity = u_capacity.real;
garyservin 0:9e9b7db60fd5 240 offset += sizeof(this->capacity);
garyservin 0:9e9b7db60fd5 241 union {
garyservin 0:9e9b7db60fd5 242 float real;
garyservin 0:9e9b7db60fd5 243 uint32_t base;
garyservin 0:9e9b7db60fd5 244 } u_design_capacity;
garyservin 0:9e9b7db60fd5 245 u_design_capacity.base = 0;
garyservin 0:9e9b7db60fd5 246 u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 247 u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 248 u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 249 u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 250 this->design_capacity = u_design_capacity.real;
garyservin 0:9e9b7db60fd5 251 offset += sizeof(this->design_capacity);
garyservin 0:9e9b7db60fd5 252 union {
garyservin 0:9e9b7db60fd5 253 float real;
garyservin 0:9e9b7db60fd5 254 uint32_t base;
garyservin 0:9e9b7db60fd5 255 } u_percentage;
garyservin 0:9e9b7db60fd5 256 u_percentage.base = 0;
garyservin 0:9e9b7db60fd5 257 u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 258 u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 259 u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 260 u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 261 this->percentage = u_percentage.real;
garyservin 0:9e9b7db60fd5 262 offset += sizeof(this->percentage);
garyservin 0:9e9b7db60fd5 263 this->power_supply_status = ((uint8_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 264 offset += sizeof(this->power_supply_status);
garyservin 0:9e9b7db60fd5 265 this->power_supply_health = ((uint8_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 266 offset += sizeof(this->power_supply_health);
garyservin 0:9e9b7db60fd5 267 this->power_supply_technology = ((uint8_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 268 offset += sizeof(this->power_supply_technology);
garyservin 0:9e9b7db60fd5 269 union {
garyservin 0:9e9b7db60fd5 270 bool real;
garyservin 0:9e9b7db60fd5 271 uint8_t base;
garyservin 0:9e9b7db60fd5 272 } u_present;
garyservin 0:9e9b7db60fd5 273 u_present.base = 0;
garyservin 0:9e9b7db60fd5 274 u_present.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 275 this->present = u_present.real;
garyservin 0:9e9b7db60fd5 276 offset += sizeof(this->present);
garyservin 0:9e9b7db60fd5 277 uint32_t cell_voltage_lengthT = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 278 cell_voltage_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 279 cell_voltage_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 280 cell_voltage_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 281 offset += sizeof(this->cell_voltage_length);
garyservin 0:9e9b7db60fd5 282 if(cell_voltage_lengthT > cell_voltage_length)
garyservin 0:9e9b7db60fd5 283 this->cell_voltage = (float*)realloc(this->cell_voltage, cell_voltage_lengthT * sizeof(float));
garyservin 0:9e9b7db60fd5 284 cell_voltage_length = cell_voltage_lengthT;
garyservin 0:9e9b7db60fd5 285 for( uint32_t i = 0; i < cell_voltage_length; i++){
garyservin 0:9e9b7db60fd5 286 union {
garyservin 0:9e9b7db60fd5 287 float real;
garyservin 0:9e9b7db60fd5 288 uint32_t base;
garyservin 0:9e9b7db60fd5 289 } u_st_cell_voltage;
garyservin 0:9e9b7db60fd5 290 u_st_cell_voltage.base = 0;
garyservin 0:9e9b7db60fd5 291 u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 292 u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 293 u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 294 u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 295 this->st_cell_voltage = u_st_cell_voltage.real;
garyservin 0:9e9b7db60fd5 296 offset += sizeof(this->st_cell_voltage);
garyservin 0:9e9b7db60fd5 297 memcpy( &(this->cell_voltage[i]), &(this->st_cell_voltage), sizeof(float));
garyservin 0:9e9b7db60fd5 298 }
garyservin 0:9e9b7db60fd5 299 uint32_t length_location;
garyservin 0:9e9b7db60fd5 300 arrToVar(length_location, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 301 offset += 4;
garyservin 0:9e9b7db60fd5 302 for(unsigned int k= offset; k< offset+length_location; ++k){
garyservin 0:9e9b7db60fd5 303 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 304 }
garyservin 0:9e9b7db60fd5 305 inbuffer[offset+length_location-1]=0;
garyservin 0:9e9b7db60fd5 306 this->location = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 307 offset += length_location;
garyservin 0:9e9b7db60fd5 308 uint32_t length_serial_number;
garyservin 0:9e9b7db60fd5 309 arrToVar(length_serial_number, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 310 offset += 4;
garyservin 0:9e9b7db60fd5 311 for(unsigned int k= offset; k< offset+length_serial_number; ++k){
garyservin 0:9e9b7db60fd5 312 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 313 }
garyservin 0:9e9b7db60fd5 314 inbuffer[offset+length_serial_number-1]=0;
garyservin 0:9e9b7db60fd5 315 this->serial_number = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 316 offset += length_serial_number;
garyservin 0:9e9b7db60fd5 317 return offset;
garyservin 0:9e9b7db60fd5 318 }
garyservin 0:9e9b7db60fd5 319
garyservin 0:9e9b7db60fd5 320 const char * getType(){ return "sensor_msgs/BatteryState"; };
garyservin 0:9e9b7db60fd5 321 const char * getMD5(){ return "476f837fa6771f6e16e3bf4ef96f8770"; };
garyservin 0:9e9b7db60fd5 322
garyservin 0:9e9b7db60fd5 323 };
garyservin 0:9e9b7db60fd5 324
garyservin 0:9e9b7db60fd5 325 }
garyservin 0:9e9b7db60fd5 326 #endif