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