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