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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

ROSSerial_mbed for Indigo 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

rosserial_mbed Hello World

Running the Code

Now, launch the roscore in a new terminal window:

Quote:

$ roscore

Next, run the rosserial client application that forwards your MBED messages to the rest of ROS. Make sure to use the correct serial port:

Quote:

$ rosrun rosserial_python serial_node.py /dev/ttyACM0

Finally, watch the greetings come in from your MBED by launching a new terminal window and entering :

Quote:

$ rostopic echo chatter

See Also

More examples

Blink

/*
 * rosserial Subscriber Example
 * Blinks an LED on callback
 */
#include "mbed.h"
#include <ros.h>
#include <std_msgs/Empty.h>

ros::NodeHandle nh;
DigitalOut myled(LED1);

void messageCb(const std_msgs::Empty& toggle_msg){
    myled = !myled;   // blink the led
}

ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb);

int main() {
    nh.initNode();
    nh.subscribe(sub);

    while (1) {
        nh.spinOnce();
        wait_ms(1);
    }
}

Push

/*
 * Button Example for Rosserial
 */

#include "mbed.h"
#include <ros.h>
#include <std_msgs/Bool.h>

PinName button = p20;

ros::NodeHandle nh;

std_msgs::Bool pushed_msg;
ros::Publisher pub_button("pushed", &pushed_msg);

DigitalIn button_pin(button);
DigitalOut led_pin(LED1);

bool last_reading;
long last_debounce_time=0;
long debounce_delay=50;
bool published = true;

Timer t;
int main() {
    t.start();
    nh.initNode();
    nh.advertise(pub_button);

    //Enable the pullup resistor on the button
    button_pin.mode(PullUp);

    //The button is a normally button
    last_reading = ! button_pin;

    while (1) {
        bool reading = ! button_pin;

        if (last_reading!= reading) {
            last_debounce_time = t.read_ms();
            published = false;
        }

        //if the button value has not changed for the debounce delay, we know its stable
        if ( !published && (t.read_ms() - last_debounce_time)  > debounce_delay) {
            led_pin = reading;
            pushed_msg.data = reading;
            pub_button.publish(&pushed_msg);
            published = true;
        }

        last_reading = reading;

        nh.spinOnce();
    }
}
Committer:
garyservin
Date:
Thu Mar 31 14:22:59 2016 +0000
Revision:
0:fd24f7ca9688
Initial commit, generated based on a clean indigo-desktop-full

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:fd24f7ca9688 1 #ifndef _ROS_SERVICE_GetModelProperties_h
garyservin 0:fd24f7ca9688 2 #define _ROS_SERVICE_GetModelProperties_h
garyservin 0:fd24f7ca9688 3 #include <stdint.h>
garyservin 0:fd24f7ca9688 4 #include <string.h>
garyservin 0:fd24f7ca9688 5 #include <stdlib.h>
garyservin 0:fd24f7ca9688 6 #include "ros/msg.h"
garyservin 0:fd24f7ca9688 7
garyservin 0:fd24f7ca9688 8 namespace gazebo_msgs
garyservin 0:fd24f7ca9688 9 {
garyservin 0:fd24f7ca9688 10
garyservin 0:fd24f7ca9688 11 static const char GETMODELPROPERTIES[] = "gazebo_msgs/GetModelProperties";
garyservin 0:fd24f7ca9688 12
garyservin 0:fd24f7ca9688 13 class GetModelPropertiesRequest : public ros::Msg
garyservin 0:fd24f7ca9688 14 {
garyservin 0:fd24f7ca9688 15 public:
garyservin 0:fd24f7ca9688 16 const char* model_name;
garyservin 0:fd24f7ca9688 17
garyservin 0:fd24f7ca9688 18 GetModelPropertiesRequest():
garyservin 0:fd24f7ca9688 19 model_name("")
garyservin 0:fd24f7ca9688 20 {
garyservin 0:fd24f7ca9688 21 }
garyservin 0:fd24f7ca9688 22
garyservin 0:fd24f7ca9688 23 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 24 {
garyservin 0:fd24f7ca9688 25 int offset = 0;
garyservin 0:fd24f7ca9688 26 uint32_t length_model_name = strlen(this->model_name);
garyservin 0:fd24f7ca9688 27 memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 28 offset += 4;
garyservin 0:fd24f7ca9688 29 memcpy(outbuffer + offset, this->model_name, length_model_name);
garyservin 0:fd24f7ca9688 30 offset += length_model_name;
garyservin 0:fd24f7ca9688 31 return offset;
garyservin 0:fd24f7ca9688 32 }
garyservin 0:fd24f7ca9688 33
garyservin 0:fd24f7ca9688 34 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 35 {
garyservin 0:fd24f7ca9688 36 int offset = 0;
garyservin 0:fd24f7ca9688 37 uint32_t length_model_name;
garyservin 0:fd24f7ca9688 38 memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 39 offset += 4;
garyservin 0:fd24f7ca9688 40 for(unsigned int k= offset; k< offset+length_model_name; ++k){
garyservin 0:fd24f7ca9688 41 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 42 }
garyservin 0:fd24f7ca9688 43 inbuffer[offset+length_model_name-1]=0;
garyservin 0:fd24f7ca9688 44 this->model_name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 45 offset += length_model_name;
garyservin 0:fd24f7ca9688 46 return offset;
garyservin 0:fd24f7ca9688 47 }
garyservin 0:fd24f7ca9688 48
garyservin 0:fd24f7ca9688 49 const char * getType(){ return GETMODELPROPERTIES; };
garyservin 0:fd24f7ca9688 50 const char * getMD5(){ return "ea31c8eab6fc401383cf528a7c0984ba"; };
garyservin 0:fd24f7ca9688 51
garyservin 0:fd24f7ca9688 52 };
garyservin 0:fd24f7ca9688 53
garyservin 0:fd24f7ca9688 54 class GetModelPropertiesResponse : public ros::Msg
garyservin 0:fd24f7ca9688 55 {
garyservin 0:fd24f7ca9688 56 public:
garyservin 0:fd24f7ca9688 57 const char* parent_model_name;
garyservin 0:fd24f7ca9688 58 const char* canonical_body_name;
garyservin 0:fd24f7ca9688 59 uint8_t body_names_length;
garyservin 0:fd24f7ca9688 60 char* st_body_names;
garyservin 0:fd24f7ca9688 61 char* * body_names;
garyservin 0:fd24f7ca9688 62 uint8_t geom_names_length;
garyservin 0:fd24f7ca9688 63 char* st_geom_names;
garyservin 0:fd24f7ca9688 64 char* * geom_names;
garyservin 0:fd24f7ca9688 65 uint8_t joint_names_length;
garyservin 0:fd24f7ca9688 66 char* st_joint_names;
garyservin 0:fd24f7ca9688 67 char* * joint_names;
garyservin 0:fd24f7ca9688 68 uint8_t child_model_names_length;
garyservin 0:fd24f7ca9688 69 char* st_child_model_names;
garyservin 0:fd24f7ca9688 70 char* * child_model_names;
garyservin 0:fd24f7ca9688 71 bool is_static;
garyservin 0:fd24f7ca9688 72 bool success;
garyservin 0:fd24f7ca9688 73 const char* status_message;
garyservin 0:fd24f7ca9688 74
garyservin 0:fd24f7ca9688 75 GetModelPropertiesResponse():
garyservin 0:fd24f7ca9688 76 parent_model_name(""),
garyservin 0:fd24f7ca9688 77 canonical_body_name(""),
garyservin 0:fd24f7ca9688 78 body_names_length(0), body_names(NULL),
garyservin 0:fd24f7ca9688 79 geom_names_length(0), geom_names(NULL),
garyservin 0:fd24f7ca9688 80 joint_names_length(0), joint_names(NULL),
garyservin 0:fd24f7ca9688 81 child_model_names_length(0), child_model_names(NULL),
garyservin 0:fd24f7ca9688 82 is_static(0),
garyservin 0:fd24f7ca9688 83 success(0),
garyservin 0:fd24f7ca9688 84 status_message("")
garyservin 0:fd24f7ca9688 85 {
garyservin 0:fd24f7ca9688 86 }
garyservin 0:fd24f7ca9688 87
garyservin 0:fd24f7ca9688 88 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 89 {
garyservin 0:fd24f7ca9688 90 int offset = 0;
garyservin 0:fd24f7ca9688 91 uint32_t length_parent_model_name = strlen(this->parent_model_name);
garyservin 0:fd24f7ca9688 92 memcpy(outbuffer + offset, &length_parent_model_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 93 offset += 4;
garyservin 0:fd24f7ca9688 94 memcpy(outbuffer + offset, this->parent_model_name, length_parent_model_name);
garyservin 0:fd24f7ca9688 95 offset += length_parent_model_name;
garyservin 0:fd24f7ca9688 96 uint32_t length_canonical_body_name = strlen(this->canonical_body_name);
garyservin 0:fd24f7ca9688 97 memcpy(outbuffer + offset, &length_canonical_body_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 98 offset += 4;
garyservin 0:fd24f7ca9688 99 memcpy(outbuffer + offset, this->canonical_body_name, length_canonical_body_name);
garyservin 0:fd24f7ca9688 100 offset += length_canonical_body_name;
garyservin 0:fd24f7ca9688 101 *(outbuffer + offset++) = body_names_length;
garyservin 0:fd24f7ca9688 102 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 103 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 104 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 105 for( uint8_t i = 0; i < body_names_length; i++){
garyservin 0:fd24f7ca9688 106 uint32_t length_body_namesi = strlen(this->body_names[i]);
garyservin 0:fd24f7ca9688 107 memcpy(outbuffer + offset, &length_body_namesi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 108 offset += 4;
garyservin 0:fd24f7ca9688 109 memcpy(outbuffer + offset, this->body_names[i], length_body_namesi);
garyservin 0:fd24f7ca9688 110 offset += length_body_namesi;
garyservin 0:fd24f7ca9688 111 }
garyservin 0:fd24f7ca9688 112 *(outbuffer + offset++) = geom_names_length;
garyservin 0:fd24f7ca9688 113 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 114 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 115 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 116 for( uint8_t i = 0; i < geom_names_length; i++){
garyservin 0:fd24f7ca9688 117 uint32_t length_geom_namesi = strlen(this->geom_names[i]);
garyservin 0:fd24f7ca9688 118 memcpy(outbuffer + offset, &length_geom_namesi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 119 offset += 4;
garyservin 0:fd24f7ca9688 120 memcpy(outbuffer + offset, this->geom_names[i], length_geom_namesi);
garyservin 0:fd24f7ca9688 121 offset += length_geom_namesi;
garyservin 0:fd24f7ca9688 122 }
garyservin 0:fd24f7ca9688 123 *(outbuffer + offset++) = joint_names_length;
garyservin 0:fd24f7ca9688 124 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 125 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 126 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 127 for( uint8_t i = 0; i < joint_names_length; i++){
garyservin 0:fd24f7ca9688 128 uint32_t length_joint_namesi = strlen(this->joint_names[i]);
garyservin 0:fd24f7ca9688 129 memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 130 offset += 4;
garyservin 0:fd24f7ca9688 131 memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
garyservin 0:fd24f7ca9688 132 offset += length_joint_namesi;
garyservin 0:fd24f7ca9688 133 }
garyservin 0:fd24f7ca9688 134 *(outbuffer + offset++) = child_model_names_length;
garyservin 0:fd24f7ca9688 135 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 136 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 137 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 138 for( uint8_t i = 0; i < child_model_names_length; i++){
garyservin 0:fd24f7ca9688 139 uint32_t length_child_model_namesi = strlen(this->child_model_names[i]);
garyservin 0:fd24f7ca9688 140 memcpy(outbuffer + offset, &length_child_model_namesi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 141 offset += 4;
garyservin 0:fd24f7ca9688 142 memcpy(outbuffer + offset, this->child_model_names[i], length_child_model_namesi);
garyservin 0:fd24f7ca9688 143 offset += length_child_model_namesi;
garyservin 0:fd24f7ca9688 144 }
garyservin 0:fd24f7ca9688 145 union {
garyservin 0:fd24f7ca9688 146 bool real;
garyservin 0:fd24f7ca9688 147 uint8_t base;
garyservin 0:fd24f7ca9688 148 } u_is_static;
garyservin 0:fd24f7ca9688 149 u_is_static.real = this->is_static;
garyservin 0:fd24f7ca9688 150 *(outbuffer + offset + 0) = (u_is_static.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 151 offset += sizeof(this->is_static);
garyservin 0:fd24f7ca9688 152 union {
garyservin 0:fd24f7ca9688 153 bool real;
garyservin 0:fd24f7ca9688 154 uint8_t base;
garyservin 0:fd24f7ca9688 155 } u_success;
garyservin 0:fd24f7ca9688 156 u_success.real = this->success;
garyservin 0:fd24f7ca9688 157 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 158 offset += sizeof(this->success);
garyservin 0:fd24f7ca9688 159 uint32_t length_status_message = strlen(this->status_message);
garyservin 0:fd24f7ca9688 160 memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 161 offset += 4;
garyservin 0:fd24f7ca9688 162 memcpy(outbuffer + offset, this->status_message, length_status_message);
garyservin 0:fd24f7ca9688 163 offset += length_status_message;
garyservin 0:fd24f7ca9688 164 return offset;
garyservin 0:fd24f7ca9688 165 }
garyservin 0:fd24f7ca9688 166
garyservin 0:fd24f7ca9688 167 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 168 {
garyservin 0:fd24f7ca9688 169 int offset = 0;
garyservin 0:fd24f7ca9688 170 uint32_t length_parent_model_name;
garyservin 0:fd24f7ca9688 171 memcpy(&length_parent_model_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 172 offset += 4;
garyservin 0:fd24f7ca9688 173 for(unsigned int k= offset; k< offset+length_parent_model_name; ++k){
garyservin 0:fd24f7ca9688 174 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 175 }
garyservin 0:fd24f7ca9688 176 inbuffer[offset+length_parent_model_name-1]=0;
garyservin 0:fd24f7ca9688 177 this->parent_model_name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 178 offset += length_parent_model_name;
garyservin 0:fd24f7ca9688 179 uint32_t length_canonical_body_name;
garyservin 0:fd24f7ca9688 180 memcpy(&length_canonical_body_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 181 offset += 4;
garyservin 0:fd24f7ca9688 182 for(unsigned int k= offset; k< offset+length_canonical_body_name; ++k){
garyservin 0:fd24f7ca9688 183 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 184 }
garyservin 0:fd24f7ca9688 185 inbuffer[offset+length_canonical_body_name-1]=0;
garyservin 0:fd24f7ca9688 186 this->canonical_body_name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 187 offset += length_canonical_body_name;
garyservin 0:fd24f7ca9688 188 uint8_t body_names_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 189 if(body_names_lengthT > body_names_length)
garyservin 0:fd24f7ca9688 190 this->body_names = (char**)realloc(this->body_names, body_names_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 191 offset += 3;
garyservin 0:fd24f7ca9688 192 body_names_length = body_names_lengthT;
garyservin 0:fd24f7ca9688 193 for( uint8_t i = 0; i < body_names_length; i++){
garyservin 0:fd24f7ca9688 194 uint32_t length_st_body_names;
garyservin 0:fd24f7ca9688 195 memcpy(&length_st_body_names, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 196 offset += 4;
garyservin 0:fd24f7ca9688 197 for(unsigned int k= offset; k< offset+length_st_body_names; ++k){
garyservin 0:fd24f7ca9688 198 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 199 }
garyservin 0:fd24f7ca9688 200 inbuffer[offset+length_st_body_names-1]=0;
garyservin 0:fd24f7ca9688 201 this->st_body_names = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 202 offset += length_st_body_names;
garyservin 0:fd24f7ca9688 203 memcpy( &(this->body_names[i]), &(this->st_body_names), sizeof(char*));
garyservin 0:fd24f7ca9688 204 }
garyservin 0:fd24f7ca9688 205 uint8_t geom_names_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 206 if(geom_names_lengthT > geom_names_length)
garyservin 0:fd24f7ca9688 207 this->geom_names = (char**)realloc(this->geom_names, geom_names_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 208 offset += 3;
garyservin 0:fd24f7ca9688 209 geom_names_length = geom_names_lengthT;
garyservin 0:fd24f7ca9688 210 for( uint8_t i = 0; i < geom_names_length; i++){
garyservin 0:fd24f7ca9688 211 uint32_t length_st_geom_names;
garyservin 0:fd24f7ca9688 212 memcpy(&length_st_geom_names, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 213 offset += 4;
garyservin 0:fd24f7ca9688 214 for(unsigned int k= offset; k< offset+length_st_geom_names; ++k){
garyservin 0:fd24f7ca9688 215 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 216 }
garyservin 0:fd24f7ca9688 217 inbuffer[offset+length_st_geom_names-1]=0;
garyservin 0:fd24f7ca9688 218 this->st_geom_names = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 219 offset += length_st_geom_names;
garyservin 0:fd24f7ca9688 220 memcpy( &(this->geom_names[i]), &(this->st_geom_names), sizeof(char*));
garyservin 0:fd24f7ca9688 221 }
garyservin 0:fd24f7ca9688 222 uint8_t joint_names_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 223 if(joint_names_lengthT > joint_names_length)
garyservin 0:fd24f7ca9688 224 this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 225 offset += 3;
garyservin 0:fd24f7ca9688 226 joint_names_length = joint_names_lengthT;
garyservin 0:fd24f7ca9688 227 for( uint8_t i = 0; i < joint_names_length; i++){
garyservin 0:fd24f7ca9688 228 uint32_t length_st_joint_names;
garyservin 0:fd24f7ca9688 229 memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 230 offset += 4;
garyservin 0:fd24f7ca9688 231 for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
garyservin 0:fd24f7ca9688 232 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 233 }
garyservin 0:fd24f7ca9688 234 inbuffer[offset+length_st_joint_names-1]=0;
garyservin 0:fd24f7ca9688 235 this->st_joint_names = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 236 offset += length_st_joint_names;
garyservin 0:fd24f7ca9688 237 memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
garyservin 0:fd24f7ca9688 238 }
garyservin 0:fd24f7ca9688 239 uint8_t child_model_names_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 240 if(child_model_names_lengthT > child_model_names_length)
garyservin 0:fd24f7ca9688 241 this->child_model_names = (char**)realloc(this->child_model_names, child_model_names_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 242 offset += 3;
garyservin 0:fd24f7ca9688 243 child_model_names_length = child_model_names_lengthT;
garyservin 0:fd24f7ca9688 244 for( uint8_t i = 0; i < child_model_names_length; i++){
garyservin 0:fd24f7ca9688 245 uint32_t length_st_child_model_names;
garyservin 0:fd24f7ca9688 246 memcpy(&length_st_child_model_names, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 247 offset += 4;
garyservin 0:fd24f7ca9688 248 for(unsigned int k= offset; k< offset+length_st_child_model_names; ++k){
garyservin 0:fd24f7ca9688 249 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 250 }
garyservin 0:fd24f7ca9688 251 inbuffer[offset+length_st_child_model_names-1]=0;
garyservin 0:fd24f7ca9688 252 this->st_child_model_names = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 253 offset += length_st_child_model_names;
garyservin 0:fd24f7ca9688 254 memcpy( &(this->child_model_names[i]), &(this->st_child_model_names), sizeof(char*));
garyservin 0:fd24f7ca9688 255 }
garyservin 0:fd24f7ca9688 256 union {
garyservin 0:fd24f7ca9688 257 bool real;
garyservin 0:fd24f7ca9688 258 uint8_t base;
garyservin 0:fd24f7ca9688 259 } u_is_static;
garyservin 0:fd24f7ca9688 260 u_is_static.base = 0;
garyservin 0:fd24f7ca9688 261 u_is_static.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 262 this->is_static = u_is_static.real;
garyservin 0:fd24f7ca9688 263 offset += sizeof(this->is_static);
garyservin 0:fd24f7ca9688 264 union {
garyservin 0:fd24f7ca9688 265 bool real;
garyservin 0:fd24f7ca9688 266 uint8_t base;
garyservin 0:fd24f7ca9688 267 } u_success;
garyservin 0:fd24f7ca9688 268 u_success.base = 0;
garyservin 0:fd24f7ca9688 269 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 270 this->success = u_success.real;
garyservin 0:fd24f7ca9688 271 offset += sizeof(this->success);
garyservin 0:fd24f7ca9688 272 uint32_t length_status_message;
garyservin 0:fd24f7ca9688 273 memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 274 offset += 4;
garyservin 0:fd24f7ca9688 275 for(unsigned int k= offset; k< offset+length_status_message; ++k){
garyservin 0:fd24f7ca9688 276 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 277 }
garyservin 0:fd24f7ca9688 278 inbuffer[offset+length_status_message-1]=0;
garyservin 0:fd24f7ca9688 279 this->status_message = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 280 offset += length_status_message;
garyservin 0:fd24f7ca9688 281 return offset;
garyservin 0:fd24f7ca9688 282 }
garyservin 0:fd24f7ca9688 283
garyservin 0:fd24f7ca9688 284 const char * getType(){ return GETMODELPROPERTIES; };
garyservin 0:fd24f7ca9688 285 const char * getMD5(){ return "b7f370938ef77b464b95f1bab3ec5028"; };
garyservin 0:fd24f7ca9688 286
garyservin 0:fd24f7ca9688 287 };
garyservin 0:fd24f7ca9688 288
garyservin 0:fd24f7ca9688 289 class GetModelProperties {
garyservin 0:fd24f7ca9688 290 public:
garyservin 0:fd24f7ca9688 291 typedef GetModelPropertiesRequest Request;
garyservin 0:fd24f7ca9688 292 typedef GetModelPropertiesResponse Response;
garyservin 0:fd24f7ca9688 293 };
garyservin 0:fd24f7ca9688 294
garyservin 0:fd24f7ca9688 295 }
garyservin 0:fd24f7ca9688 296 #endif