rosserial library for mbed Inspired by nucho's rosserial library This library is still under development

Dependencies:   MODSERIAL mbed

Dependents:   mbed_roshydro_test

Library still under development!

Committer:
akashvibhute
Date:
Sun Feb 15 10:53:43 2015 +0000
Revision:
0:30537dec6e0b
First commit; Library still need to be debugged, compilation issues with new mbed and modserial updates.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
akashvibhute 0:30537dec6e0b 1 #ifndef _ROS_ur_msgs_RobotStateRTMsg_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_ur_msgs_RobotStateRTMsg_h
akashvibhute 0:30537dec6e0b 3
akashvibhute 0:30537dec6e0b 4 #include <stdint.h>
akashvibhute 0:30537dec6e0b 5 #include <string.h>
akashvibhute 0:30537dec6e0b 6 #include <stdlib.h>
akashvibhute 0:30537dec6e0b 7 #include "ros/msg.h"
akashvibhute 0:30537dec6e0b 8
akashvibhute 0:30537dec6e0b 9 namespace ur_msgs
akashvibhute 0:30537dec6e0b 10 {
akashvibhute 0:30537dec6e0b 11
akashvibhute 0:30537dec6e0b 12 class RobotStateRTMsg : public ros::Msg
akashvibhute 0:30537dec6e0b 13 {
akashvibhute 0:30537dec6e0b 14 public:
akashvibhute 0:30537dec6e0b 15 float time;
akashvibhute 0:30537dec6e0b 16 uint8_t q_target_length;
akashvibhute 0:30537dec6e0b 17 float st_q_target;
akashvibhute 0:30537dec6e0b 18 float * q_target;
akashvibhute 0:30537dec6e0b 19 uint8_t qd_target_length;
akashvibhute 0:30537dec6e0b 20 float st_qd_target;
akashvibhute 0:30537dec6e0b 21 float * qd_target;
akashvibhute 0:30537dec6e0b 22 uint8_t qdd_target_length;
akashvibhute 0:30537dec6e0b 23 float st_qdd_target;
akashvibhute 0:30537dec6e0b 24 float * qdd_target;
akashvibhute 0:30537dec6e0b 25 uint8_t i_target_length;
akashvibhute 0:30537dec6e0b 26 float st_i_target;
akashvibhute 0:30537dec6e0b 27 float * i_target;
akashvibhute 0:30537dec6e0b 28 uint8_t m_target_length;
akashvibhute 0:30537dec6e0b 29 float st_m_target;
akashvibhute 0:30537dec6e0b 30 float * m_target;
akashvibhute 0:30537dec6e0b 31 uint8_t q_actual_length;
akashvibhute 0:30537dec6e0b 32 float st_q_actual;
akashvibhute 0:30537dec6e0b 33 float * q_actual;
akashvibhute 0:30537dec6e0b 34 uint8_t qd_actual_length;
akashvibhute 0:30537dec6e0b 35 float st_qd_actual;
akashvibhute 0:30537dec6e0b 36 float * qd_actual;
akashvibhute 0:30537dec6e0b 37 uint8_t i_actual_length;
akashvibhute 0:30537dec6e0b 38 float st_i_actual;
akashvibhute 0:30537dec6e0b 39 float * i_actual;
akashvibhute 0:30537dec6e0b 40 uint8_t tool_acc_values_length;
akashvibhute 0:30537dec6e0b 41 float st_tool_acc_values;
akashvibhute 0:30537dec6e0b 42 float * tool_acc_values;
akashvibhute 0:30537dec6e0b 43 uint8_t tcp_force_length;
akashvibhute 0:30537dec6e0b 44 float st_tcp_force;
akashvibhute 0:30537dec6e0b 45 float * tcp_force;
akashvibhute 0:30537dec6e0b 46 uint8_t tool_vector_length;
akashvibhute 0:30537dec6e0b 47 float st_tool_vector;
akashvibhute 0:30537dec6e0b 48 float * tool_vector;
akashvibhute 0:30537dec6e0b 49 uint8_t tcp_speed_length;
akashvibhute 0:30537dec6e0b 50 float st_tcp_speed;
akashvibhute 0:30537dec6e0b 51 float * tcp_speed;
akashvibhute 0:30537dec6e0b 52 float digital_input_bits;
akashvibhute 0:30537dec6e0b 53 uint8_t motor_temperatures_length;
akashvibhute 0:30537dec6e0b 54 float st_motor_temperatures;
akashvibhute 0:30537dec6e0b 55 float * motor_temperatures;
akashvibhute 0:30537dec6e0b 56 float controller_timer;
akashvibhute 0:30537dec6e0b 57 float test_value;
akashvibhute 0:30537dec6e0b 58 float robot_mode;
akashvibhute 0:30537dec6e0b 59 uint8_t joint_modes_length;
akashvibhute 0:30537dec6e0b 60 float st_joint_modes;
akashvibhute 0:30537dec6e0b 61 float * joint_modes;
akashvibhute 0:30537dec6e0b 62
akashvibhute 0:30537dec6e0b 63 RobotStateRTMsg():
akashvibhute 0:30537dec6e0b 64 time(0),
akashvibhute 0:30537dec6e0b 65 q_target_length(0), q_target(NULL),
akashvibhute 0:30537dec6e0b 66 qd_target_length(0), qd_target(NULL),
akashvibhute 0:30537dec6e0b 67 qdd_target_length(0), qdd_target(NULL),
akashvibhute 0:30537dec6e0b 68 i_target_length(0), i_target(NULL),
akashvibhute 0:30537dec6e0b 69 m_target_length(0), m_target(NULL),
akashvibhute 0:30537dec6e0b 70 q_actual_length(0), q_actual(NULL),
akashvibhute 0:30537dec6e0b 71 qd_actual_length(0), qd_actual(NULL),
akashvibhute 0:30537dec6e0b 72 i_actual_length(0), i_actual(NULL),
akashvibhute 0:30537dec6e0b 73 tool_acc_values_length(0), tool_acc_values(NULL),
akashvibhute 0:30537dec6e0b 74 tcp_force_length(0), tcp_force(NULL),
akashvibhute 0:30537dec6e0b 75 tool_vector_length(0), tool_vector(NULL),
akashvibhute 0:30537dec6e0b 76 tcp_speed_length(0), tcp_speed(NULL),
akashvibhute 0:30537dec6e0b 77 digital_input_bits(0),
akashvibhute 0:30537dec6e0b 78 motor_temperatures_length(0), motor_temperatures(NULL),
akashvibhute 0:30537dec6e0b 79 controller_timer(0),
akashvibhute 0:30537dec6e0b 80 test_value(0),
akashvibhute 0:30537dec6e0b 81 robot_mode(0),
akashvibhute 0:30537dec6e0b 82 joint_modes_length(0), joint_modes(NULL)
akashvibhute 0:30537dec6e0b 83 {
akashvibhute 0:30537dec6e0b 84 }
akashvibhute 0:30537dec6e0b 85
akashvibhute 0:30537dec6e0b 86 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 87 {
akashvibhute 0:30537dec6e0b 88 int offset = 0;
akashvibhute 0:30537dec6e0b 89 offset += serializeAvrFloat64(outbuffer + offset, this->time);
akashvibhute 0:30537dec6e0b 90 *(outbuffer + offset++) = q_target_length;
akashvibhute 0:30537dec6e0b 91 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 92 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 93 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 94 for( uint8_t i = 0; i < q_target_length; i++){
akashvibhute 0:30537dec6e0b 95 offset += serializeAvrFloat64(outbuffer + offset, this->q_target[i]);
akashvibhute 0:30537dec6e0b 96 }
akashvibhute 0:30537dec6e0b 97 *(outbuffer + offset++) = qd_target_length;
akashvibhute 0:30537dec6e0b 98 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 99 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 100 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 101 for( uint8_t i = 0; i < qd_target_length; i++){
akashvibhute 0:30537dec6e0b 102 offset += serializeAvrFloat64(outbuffer + offset, this->qd_target[i]);
akashvibhute 0:30537dec6e0b 103 }
akashvibhute 0:30537dec6e0b 104 *(outbuffer + offset++) = qdd_target_length;
akashvibhute 0:30537dec6e0b 105 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 106 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 107 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 108 for( uint8_t i = 0; i < qdd_target_length; i++){
akashvibhute 0:30537dec6e0b 109 offset += serializeAvrFloat64(outbuffer + offset, this->qdd_target[i]);
akashvibhute 0:30537dec6e0b 110 }
akashvibhute 0:30537dec6e0b 111 *(outbuffer + offset++) = i_target_length;
akashvibhute 0:30537dec6e0b 112 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 113 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 114 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 115 for( uint8_t i = 0; i < i_target_length; i++){
akashvibhute 0:30537dec6e0b 116 offset += serializeAvrFloat64(outbuffer + offset, this->i_target[i]);
akashvibhute 0:30537dec6e0b 117 }
akashvibhute 0:30537dec6e0b 118 *(outbuffer + offset++) = m_target_length;
akashvibhute 0:30537dec6e0b 119 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 120 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 121 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 122 for( uint8_t i = 0; i < m_target_length; i++){
akashvibhute 0:30537dec6e0b 123 offset += serializeAvrFloat64(outbuffer + offset, this->m_target[i]);
akashvibhute 0:30537dec6e0b 124 }
akashvibhute 0:30537dec6e0b 125 *(outbuffer + offset++) = q_actual_length;
akashvibhute 0:30537dec6e0b 126 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 127 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 128 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 129 for( uint8_t i = 0; i < q_actual_length; i++){
akashvibhute 0:30537dec6e0b 130 offset += serializeAvrFloat64(outbuffer + offset, this->q_actual[i]);
akashvibhute 0:30537dec6e0b 131 }
akashvibhute 0:30537dec6e0b 132 *(outbuffer + offset++) = qd_actual_length;
akashvibhute 0:30537dec6e0b 133 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 134 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 135 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 136 for( uint8_t i = 0; i < qd_actual_length; i++){
akashvibhute 0:30537dec6e0b 137 offset += serializeAvrFloat64(outbuffer + offset, this->qd_actual[i]);
akashvibhute 0:30537dec6e0b 138 }
akashvibhute 0:30537dec6e0b 139 *(outbuffer + offset++) = i_actual_length;
akashvibhute 0:30537dec6e0b 140 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 141 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 142 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 143 for( uint8_t i = 0; i < i_actual_length; i++){
akashvibhute 0:30537dec6e0b 144 offset += serializeAvrFloat64(outbuffer + offset, this->i_actual[i]);
akashvibhute 0:30537dec6e0b 145 }
akashvibhute 0:30537dec6e0b 146 *(outbuffer + offset++) = tool_acc_values_length;
akashvibhute 0:30537dec6e0b 147 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 148 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 149 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 150 for( uint8_t i = 0; i < tool_acc_values_length; i++){
akashvibhute 0:30537dec6e0b 151 offset += serializeAvrFloat64(outbuffer + offset, this->tool_acc_values[i]);
akashvibhute 0:30537dec6e0b 152 }
akashvibhute 0:30537dec6e0b 153 *(outbuffer + offset++) = tcp_force_length;
akashvibhute 0:30537dec6e0b 154 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 155 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 156 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 157 for( uint8_t i = 0; i < tcp_force_length; i++){
akashvibhute 0:30537dec6e0b 158 offset += serializeAvrFloat64(outbuffer + offset, this->tcp_force[i]);
akashvibhute 0:30537dec6e0b 159 }
akashvibhute 0:30537dec6e0b 160 *(outbuffer + offset++) = tool_vector_length;
akashvibhute 0:30537dec6e0b 161 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 162 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 163 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 164 for( uint8_t i = 0; i < tool_vector_length; i++){
akashvibhute 0:30537dec6e0b 165 offset += serializeAvrFloat64(outbuffer + offset, this->tool_vector[i]);
akashvibhute 0:30537dec6e0b 166 }
akashvibhute 0:30537dec6e0b 167 *(outbuffer + offset++) = tcp_speed_length;
akashvibhute 0:30537dec6e0b 168 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 169 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 170 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 171 for( uint8_t i = 0; i < tcp_speed_length; i++){
akashvibhute 0:30537dec6e0b 172 offset += serializeAvrFloat64(outbuffer + offset, this->tcp_speed[i]);
akashvibhute 0:30537dec6e0b 173 }
akashvibhute 0:30537dec6e0b 174 offset += serializeAvrFloat64(outbuffer + offset, this->digital_input_bits);
akashvibhute 0:30537dec6e0b 175 *(outbuffer + offset++) = motor_temperatures_length;
akashvibhute 0:30537dec6e0b 176 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 177 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 178 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 179 for( uint8_t i = 0; i < motor_temperatures_length; i++){
akashvibhute 0:30537dec6e0b 180 offset += serializeAvrFloat64(outbuffer + offset, this->motor_temperatures[i]);
akashvibhute 0:30537dec6e0b 181 }
akashvibhute 0:30537dec6e0b 182 offset += serializeAvrFloat64(outbuffer + offset, this->controller_timer);
akashvibhute 0:30537dec6e0b 183 offset += serializeAvrFloat64(outbuffer + offset, this->test_value);
akashvibhute 0:30537dec6e0b 184 offset += serializeAvrFloat64(outbuffer + offset, this->robot_mode);
akashvibhute 0:30537dec6e0b 185 *(outbuffer + offset++) = joint_modes_length;
akashvibhute 0:30537dec6e0b 186 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 187 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 188 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 189 for( uint8_t i = 0; i < joint_modes_length; i++){
akashvibhute 0:30537dec6e0b 190 offset += serializeAvrFloat64(outbuffer + offset, this->joint_modes[i]);
akashvibhute 0:30537dec6e0b 191 }
akashvibhute 0:30537dec6e0b 192 return offset;
akashvibhute 0:30537dec6e0b 193 }
akashvibhute 0:30537dec6e0b 194
akashvibhute 0:30537dec6e0b 195 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 196 {
akashvibhute 0:30537dec6e0b 197 int offset = 0;
akashvibhute 0:30537dec6e0b 198 offset += deserializeAvrFloat64(inbuffer + offset, &(this->time));
akashvibhute 0:30537dec6e0b 199 uint8_t q_target_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 200 if(q_target_lengthT > q_target_length)
akashvibhute 0:30537dec6e0b 201 this->q_target = (float*)realloc(this->q_target, q_target_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 202 offset += 3;
akashvibhute 0:30537dec6e0b 203 q_target_length = q_target_lengthT;
akashvibhute 0:30537dec6e0b 204 for( uint8_t i = 0; i < q_target_length; i++){
akashvibhute 0:30537dec6e0b 205 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_q_target));
akashvibhute 0:30537dec6e0b 206 memcpy( &(this->q_target[i]), &(this->st_q_target), sizeof(float));
akashvibhute 0:30537dec6e0b 207 }
akashvibhute 0:30537dec6e0b 208 uint8_t qd_target_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 209 if(qd_target_lengthT > qd_target_length)
akashvibhute 0:30537dec6e0b 210 this->qd_target = (float*)realloc(this->qd_target, qd_target_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 211 offset += 3;
akashvibhute 0:30537dec6e0b 212 qd_target_length = qd_target_lengthT;
akashvibhute 0:30537dec6e0b 213 for( uint8_t i = 0; i < qd_target_length; i++){
akashvibhute 0:30537dec6e0b 214 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_qd_target));
akashvibhute 0:30537dec6e0b 215 memcpy( &(this->qd_target[i]), &(this->st_qd_target), sizeof(float));
akashvibhute 0:30537dec6e0b 216 }
akashvibhute 0:30537dec6e0b 217 uint8_t qdd_target_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 218 if(qdd_target_lengthT > qdd_target_length)
akashvibhute 0:30537dec6e0b 219 this->qdd_target = (float*)realloc(this->qdd_target, qdd_target_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 220 offset += 3;
akashvibhute 0:30537dec6e0b 221 qdd_target_length = qdd_target_lengthT;
akashvibhute 0:30537dec6e0b 222 for( uint8_t i = 0; i < qdd_target_length; i++){
akashvibhute 0:30537dec6e0b 223 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_qdd_target));
akashvibhute 0:30537dec6e0b 224 memcpy( &(this->qdd_target[i]), &(this->st_qdd_target), sizeof(float));
akashvibhute 0:30537dec6e0b 225 }
akashvibhute 0:30537dec6e0b 226 uint8_t i_target_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 227 if(i_target_lengthT > i_target_length)
akashvibhute 0:30537dec6e0b 228 this->i_target = (float*)realloc(this->i_target, i_target_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 229 offset += 3;
akashvibhute 0:30537dec6e0b 230 i_target_length = i_target_lengthT;
akashvibhute 0:30537dec6e0b 231 for( uint8_t i = 0; i < i_target_length; i++){
akashvibhute 0:30537dec6e0b 232 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_i_target));
akashvibhute 0:30537dec6e0b 233 memcpy( &(this->i_target[i]), &(this->st_i_target), sizeof(float));
akashvibhute 0:30537dec6e0b 234 }
akashvibhute 0:30537dec6e0b 235 uint8_t m_target_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 236 if(m_target_lengthT > m_target_length)
akashvibhute 0:30537dec6e0b 237 this->m_target = (float*)realloc(this->m_target, m_target_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 238 offset += 3;
akashvibhute 0:30537dec6e0b 239 m_target_length = m_target_lengthT;
akashvibhute 0:30537dec6e0b 240 for( uint8_t i = 0; i < m_target_length; i++){
akashvibhute 0:30537dec6e0b 241 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_m_target));
akashvibhute 0:30537dec6e0b 242 memcpy( &(this->m_target[i]), &(this->st_m_target), sizeof(float));
akashvibhute 0:30537dec6e0b 243 }
akashvibhute 0:30537dec6e0b 244 uint8_t q_actual_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 245 if(q_actual_lengthT > q_actual_length)
akashvibhute 0:30537dec6e0b 246 this->q_actual = (float*)realloc(this->q_actual, q_actual_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 247 offset += 3;
akashvibhute 0:30537dec6e0b 248 q_actual_length = q_actual_lengthT;
akashvibhute 0:30537dec6e0b 249 for( uint8_t i = 0; i < q_actual_length; i++){
akashvibhute 0:30537dec6e0b 250 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_q_actual));
akashvibhute 0:30537dec6e0b 251 memcpy( &(this->q_actual[i]), &(this->st_q_actual), sizeof(float));
akashvibhute 0:30537dec6e0b 252 }
akashvibhute 0:30537dec6e0b 253 uint8_t qd_actual_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 254 if(qd_actual_lengthT > qd_actual_length)
akashvibhute 0:30537dec6e0b 255 this->qd_actual = (float*)realloc(this->qd_actual, qd_actual_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 256 offset += 3;
akashvibhute 0:30537dec6e0b 257 qd_actual_length = qd_actual_lengthT;
akashvibhute 0:30537dec6e0b 258 for( uint8_t i = 0; i < qd_actual_length; i++){
akashvibhute 0:30537dec6e0b 259 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_qd_actual));
akashvibhute 0:30537dec6e0b 260 memcpy( &(this->qd_actual[i]), &(this->st_qd_actual), sizeof(float));
akashvibhute 0:30537dec6e0b 261 }
akashvibhute 0:30537dec6e0b 262 uint8_t i_actual_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 263 if(i_actual_lengthT > i_actual_length)
akashvibhute 0:30537dec6e0b 264 this->i_actual = (float*)realloc(this->i_actual, i_actual_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 265 offset += 3;
akashvibhute 0:30537dec6e0b 266 i_actual_length = i_actual_lengthT;
akashvibhute 0:30537dec6e0b 267 for( uint8_t i = 0; i < i_actual_length; i++){
akashvibhute 0:30537dec6e0b 268 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_i_actual));
akashvibhute 0:30537dec6e0b 269 memcpy( &(this->i_actual[i]), &(this->st_i_actual), sizeof(float));
akashvibhute 0:30537dec6e0b 270 }
akashvibhute 0:30537dec6e0b 271 uint8_t tool_acc_values_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 272 if(tool_acc_values_lengthT > tool_acc_values_length)
akashvibhute 0:30537dec6e0b 273 this->tool_acc_values = (float*)realloc(this->tool_acc_values, tool_acc_values_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 274 offset += 3;
akashvibhute 0:30537dec6e0b 275 tool_acc_values_length = tool_acc_values_lengthT;
akashvibhute 0:30537dec6e0b 276 for( uint8_t i = 0; i < tool_acc_values_length; i++){
akashvibhute 0:30537dec6e0b 277 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_tool_acc_values));
akashvibhute 0:30537dec6e0b 278 memcpy( &(this->tool_acc_values[i]), &(this->st_tool_acc_values), sizeof(float));
akashvibhute 0:30537dec6e0b 279 }
akashvibhute 0:30537dec6e0b 280 uint8_t tcp_force_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 281 if(tcp_force_lengthT > tcp_force_length)
akashvibhute 0:30537dec6e0b 282 this->tcp_force = (float*)realloc(this->tcp_force, tcp_force_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 283 offset += 3;
akashvibhute 0:30537dec6e0b 284 tcp_force_length = tcp_force_lengthT;
akashvibhute 0:30537dec6e0b 285 for( uint8_t i = 0; i < tcp_force_length; i++){
akashvibhute 0:30537dec6e0b 286 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_tcp_force));
akashvibhute 0:30537dec6e0b 287 memcpy( &(this->tcp_force[i]), &(this->st_tcp_force), sizeof(float));
akashvibhute 0:30537dec6e0b 288 }
akashvibhute 0:30537dec6e0b 289 uint8_t tool_vector_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 290 if(tool_vector_lengthT > tool_vector_length)
akashvibhute 0:30537dec6e0b 291 this->tool_vector = (float*)realloc(this->tool_vector, tool_vector_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 292 offset += 3;
akashvibhute 0:30537dec6e0b 293 tool_vector_length = tool_vector_lengthT;
akashvibhute 0:30537dec6e0b 294 for( uint8_t i = 0; i < tool_vector_length; i++){
akashvibhute 0:30537dec6e0b 295 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_tool_vector));
akashvibhute 0:30537dec6e0b 296 memcpy( &(this->tool_vector[i]), &(this->st_tool_vector), sizeof(float));
akashvibhute 0:30537dec6e0b 297 }
akashvibhute 0:30537dec6e0b 298 uint8_t tcp_speed_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 299 if(tcp_speed_lengthT > tcp_speed_length)
akashvibhute 0:30537dec6e0b 300 this->tcp_speed = (float*)realloc(this->tcp_speed, tcp_speed_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 301 offset += 3;
akashvibhute 0:30537dec6e0b 302 tcp_speed_length = tcp_speed_lengthT;
akashvibhute 0:30537dec6e0b 303 for( uint8_t i = 0; i < tcp_speed_length; i++){
akashvibhute 0:30537dec6e0b 304 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_tcp_speed));
akashvibhute 0:30537dec6e0b 305 memcpy( &(this->tcp_speed[i]), &(this->st_tcp_speed), sizeof(float));
akashvibhute 0:30537dec6e0b 306 }
akashvibhute 0:30537dec6e0b 307 offset += deserializeAvrFloat64(inbuffer + offset, &(this->digital_input_bits));
akashvibhute 0:30537dec6e0b 308 uint8_t motor_temperatures_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 309 if(motor_temperatures_lengthT > motor_temperatures_length)
akashvibhute 0:30537dec6e0b 310 this->motor_temperatures = (float*)realloc(this->motor_temperatures, motor_temperatures_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 311 offset += 3;
akashvibhute 0:30537dec6e0b 312 motor_temperatures_length = motor_temperatures_lengthT;
akashvibhute 0:30537dec6e0b 313 for( uint8_t i = 0; i < motor_temperatures_length; i++){
akashvibhute 0:30537dec6e0b 314 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_motor_temperatures));
akashvibhute 0:30537dec6e0b 315 memcpy( &(this->motor_temperatures[i]), &(this->st_motor_temperatures), sizeof(float));
akashvibhute 0:30537dec6e0b 316 }
akashvibhute 0:30537dec6e0b 317 offset += deserializeAvrFloat64(inbuffer + offset, &(this->controller_timer));
akashvibhute 0:30537dec6e0b 318 offset += deserializeAvrFloat64(inbuffer + offset, &(this->test_value));
akashvibhute 0:30537dec6e0b 319 offset += deserializeAvrFloat64(inbuffer + offset, &(this->robot_mode));
akashvibhute 0:30537dec6e0b 320 uint8_t joint_modes_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 321 if(joint_modes_lengthT > joint_modes_length)
akashvibhute 0:30537dec6e0b 322 this->joint_modes = (float*)realloc(this->joint_modes, joint_modes_lengthT * sizeof(float));
akashvibhute 0:30537dec6e0b 323 offset += 3;
akashvibhute 0:30537dec6e0b 324 joint_modes_length = joint_modes_lengthT;
akashvibhute 0:30537dec6e0b 325 for( uint8_t i = 0; i < joint_modes_length; i++){
akashvibhute 0:30537dec6e0b 326 offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_joint_modes));
akashvibhute 0:30537dec6e0b 327 memcpy( &(this->joint_modes[i]), &(this->st_joint_modes), sizeof(float));
akashvibhute 0:30537dec6e0b 328 }
akashvibhute 0:30537dec6e0b 329 return offset;
akashvibhute 0:30537dec6e0b 330 }
akashvibhute 0:30537dec6e0b 331
akashvibhute 0:30537dec6e0b 332 const char * getType(){ return "ur_msgs/RobotStateRTMsg"; };
akashvibhute 0:30537dec6e0b 333 const char * getMD5(){ return "ce6feddd3ccb4ca7dbcd0ff105b603c7"; };
akashvibhute 0:30537dec6e0b 334
akashvibhute 0:30537dec6e0b 335 };
akashvibhute 0:30537dec6e0b 336
akashvibhute 0:30537dec6e0b 337 }
akashvibhute 0:30537dec6e0b 338 #endif