00001
00002 #ifndef HRL_HAPTIC_MANIPULATION_IN_CLUTTER_MSGS_MESSAGE_MPCDYNFORMATTEDDATA_H
00003 #define HRL_HAPTIC_MANIPULATION_IN_CLUTTER_MSGS_MESSAGE_MPCDYNFORMATTEDDATA_H
00004 #include <string>
00005 #include <vector>
00006 #include <map>
00007 #include <ostream>
00008 #include "ros/serialization.h"
00009 #include "ros/builtin_message_traits.h"
00010 #include "ros/message_operations.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/macros.h"
00014
00015 #include "ros/assert.h"
00016
00017 #include "std_msgs/Header.h"
00018
00019 namespace hrl_haptic_manipulation_in_clutter_msgs
00020 {
00021 template <class ContainerAllocator>
00022 struct MpcDynFormattedData_ {
00023 typedef MpcDynFormattedData_<ContainerAllocator> Type;
00024
00025 MpcDynFormattedData_()
00026 : header()
00027 , alpha(0.0)
00028 , delta_x_d()
00029 , A_tl()
00030 , A_tr()
00031 , A_bl()
00032 , A_br()
00033 , B_tl()
00034 , B_tr()
00035 , B_bl()
00036 , B_br()
00037 , qd_max()
00038 , u_max()
00039 , q_min()
00040 , q_max()
00041 , delta_f_max()
00042 , n_K_J_all()
00043 , all_J_T_K_J()
00044 , J()
00045 , f_max_delta_t()
00046 , mass_n_J_com()
00047 , Kp()
00048 , Kd()
00049 , q_des_cur_0()
00050 , qd_0()
00051 , q_0()
00052 , tau_cont_sum_0()
00053 {
00054 }
00055
00056 MpcDynFormattedData_(const ContainerAllocator& _alloc)
00057 : header(_alloc)
00058 , alpha(0.0)
00059 , delta_x_d(_alloc)
00060 , A_tl(_alloc)
00061 , A_tr(_alloc)
00062 , A_bl(_alloc)
00063 , A_br(_alloc)
00064 , B_tl(_alloc)
00065 , B_tr(_alloc)
00066 , B_bl(_alloc)
00067 , B_br(_alloc)
00068 , qd_max(_alloc)
00069 , u_max(_alloc)
00070 , q_min(_alloc)
00071 , q_max(_alloc)
00072 , delta_f_max(_alloc)
00073 , n_K_J_all(_alloc)
00074 , all_J_T_K_J(_alloc)
00075 , J(_alloc)
00076 , f_max_delta_t(_alloc)
00077 , mass_n_J_com(_alloc)
00078 , Kp(_alloc)
00079 , Kd(_alloc)
00080 , q_des_cur_0(_alloc)
00081 , qd_0(_alloc)
00082 , q_0(_alloc)
00083 , tau_cont_sum_0(_alloc)
00084 {
00085 }
00086
00087 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00088 ::std_msgs::Header_<ContainerAllocator> header;
00089
00090 typedef double _alpha_type;
00091 double alpha;
00092
00093 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _delta_x_d_type;
00094 std::vector<double, typename ContainerAllocator::template rebind<double>::other > delta_x_d;
00095
00096 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _A_tl_type;
00097 std::vector<double, typename ContainerAllocator::template rebind<double>::other > A_tl;
00098
00099 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _A_tr_type;
00100 std::vector<double, typename ContainerAllocator::template rebind<double>::other > A_tr;
00101
00102 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _A_bl_type;
00103 std::vector<double, typename ContainerAllocator::template rebind<double>::other > A_bl;
00104
00105 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _A_br_type;
00106 std::vector<double, typename ContainerAllocator::template rebind<double>::other > A_br;
00107
00108 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _B_tl_type;
00109 std::vector<double, typename ContainerAllocator::template rebind<double>::other > B_tl;
00110
00111 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _B_tr_type;
00112 std::vector<double, typename ContainerAllocator::template rebind<double>::other > B_tr;
00113
00114 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _B_bl_type;
00115 std::vector<double, typename ContainerAllocator::template rebind<double>::other > B_bl;
00116
00117 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _B_br_type;
00118 std::vector<double, typename ContainerAllocator::template rebind<double>::other > B_br;
00119
00120 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _qd_max_type;
00121 std::vector<double, typename ContainerAllocator::template rebind<double>::other > qd_max;
00122
00123 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _u_max_type;
00124 std::vector<double, typename ContainerAllocator::template rebind<double>::other > u_max;
00125
00126 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _q_min_type;
00127 std::vector<double, typename ContainerAllocator::template rebind<double>::other > q_min;
00128
00129 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _q_max_type;
00130 std::vector<double, typename ContainerAllocator::template rebind<double>::other > q_max;
00131
00132 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _delta_f_max_type;
00133 std::vector<double, typename ContainerAllocator::template rebind<double>::other > delta_f_max;
00134
00135 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _n_K_J_all_type;
00136 std::vector<double, typename ContainerAllocator::template rebind<double>::other > n_K_J_all;
00137
00138 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _all_J_T_K_J_type;
00139 std::vector<double, typename ContainerAllocator::template rebind<double>::other > all_J_T_K_J;
00140
00141 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _J_type;
00142 std::vector<double, typename ContainerAllocator::template rebind<double>::other > J;
00143
00144 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _f_max_delta_t_type;
00145 std::vector<double, typename ContainerAllocator::template rebind<double>::other > f_max_delta_t;
00146
00147 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _mass_n_J_com_type;
00148 std::vector<double, typename ContainerAllocator::template rebind<double>::other > mass_n_J_com;
00149
00150 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _Kp_type;
00151 std::vector<double, typename ContainerAllocator::template rebind<double>::other > Kp;
00152
00153 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _Kd_type;
00154 std::vector<double, typename ContainerAllocator::template rebind<double>::other > Kd;
00155
00156 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _q_des_cur_0_type;
00157 std::vector<double, typename ContainerAllocator::template rebind<double>::other > q_des_cur_0;
00158
00159 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _qd_0_type;
00160 std::vector<double, typename ContainerAllocator::template rebind<double>::other > qd_0;
00161
00162 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _q_0_type;
00163 std::vector<double, typename ContainerAllocator::template rebind<double>::other > q_0;
00164
00165 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _tau_cont_sum_0_type;
00166 std::vector<double, typename ContainerAllocator::template rebind<double>::other > tau_cont_sum_0;
00167
00168
00169 typedef boost::shared_ptr< ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> > Ptr;
00170 typedef boost::shared_ptr< ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> const> ConstPtr;
00171 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00172 };
00173 typedef ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<std::allocator<void> > MpcDynFormattedData;
00174
00175 typedef boost::shared_ptr< ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData> MpcDynFormattedDataPtr;
00176 typedef boost::shared_ptr< ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData const> MpcDynFormattedDataConstPtr;
00177
00178
00179 template<typename ContainerAllocator>
00180 std::ostream& operator<<(std::ostream& s, const ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> & v)
00181 {
00182 ros::message_operations::Printer< ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> >::stream(s, "", v);
00183 return s;}
00184
00185 }
00186
00187 namespace ros
00188 {
00189 namespace message_traits
00190 {
00191 template<class ContainerAllocator> struct IsMessage< ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> > : public TrueType {};
00192 template<class ContainerAllocator> struct IsMessage< ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> const> : public TrueType {};
00193 template<class ContainerAllocator>
00194 struct MD5Sum< ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> > {
00195 static const char* value()
00196 {
00197 return "409d8cadc45ef90a32fdf8e0c0ed4e2d";
00198 }
00199
00200 static const char* value(const ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> &) { return value(); }
00201 static const uint64_t static_value1 = 0x409d8cadc45ef90aULL;
00202 static const uint64_t static_value2 = 0x32fdf8e0c0ed4e2dULL;
00203 };
00204
00205 template<class ContainerAllocator>
00206 struct DataType< ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> > {
00207 static const char* value()
00208 {
00209 return "hrl_haptic_manipulation_in_clutter_msgs/MpcDynFormattedData";
00210 }
00211
00212 static const char* value(const ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> &) { return value(); }
00213 };
00214
00215 template<class ContainerAllocator>
00216 struct Definition< ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> > {
00217 static const char* value()
00218 {
00219 return "\n\
00220 Header header\n\
00221 \n\
00222 float64 alpha\n\
00223 float64[] delta_x_d\n\
00224 float64[] A_tl\n\
00225 float64[] A_tr\n\
00226 float64[] A_bl\n\
00227 float64[] A_br\n\
00228 float64[] B_tl\n\
00229 float64[] B_tr\n\
00230 float64[] B_bl\n\
00231 float64[] B_br\n\
00232 float64[] qd_max\n\
00233 float64[] u_max\n\
00234 float64[] q_min\n\
00235 float64[] q_max\n\
00236 float64[] delta_f_max\n\
00237 float64[] n_K_J_all\n\
00238 float64[] all_J_T_K_J\n\
00239 float64[] J\n\
00240 float64[] f_max_delta_t\n\
00241 float64[] mass_n_J_com\n\
00242 float64[] Kp\n\
00243 float64[] Kd\n\
00244 float64[] q_des_cur_0\n\
00245 float64[] qd_0\n\
00246 float64[] q_0\n\
00247 float64[] tau_cont_sum_0\n\
00248 \n\
00249 ================================================================================\n\
00250 MSG: std_msgs/Header\n\
00251 # Standard metadata for higher-level stamped data types.\n\
00252 # This is generally used to communicate timestamped data \n\
00253 # in a particular coordinate frame.\n\
00254 # \n\
00255 # sequence ID: consecutively increasing ID \n\
00256 uint32 seq\n\
00257 #Two-integer timestamp that is expressed as:\n\
00258 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00259 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00260 # time-handling sugar is provided by the client library\n\
00261 time stamp\n\
00262 #Frame this data is associated with\n\
00263 # 0: no frame\n\
00264 # 1: global frame\n\
00265 string frame_id\n\
00266 \n\
00267 ";
00268 }
00269
00270 static const char* value(const ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> &) { return value(); }
00271 };
00272
00273 template<class ContainerAllocator> struct HasHeader< ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> > : public TrueType {};
00274 template<class ContainerAllocator> struct HasHeader< const ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> > : public TrueType {};
00275 }
00276 }
00277
00278 namespace ros
00279 {
00280 namespace serialization
00281 {
00282
00283 template<class ContainerAllocator> struct Serializer< ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> >
00284 {
00285 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00286 {
00287 stream.next(m.header);
00288 stream.next(m.alpha);
00289 stream.next(m.delta_x_d);
00290 stream.next(m.A_tl);
00291 stream.next(m.A_tr);
00292 stream.next(m.A_bl);
00293 stream.next(m.A_br);
00294 stream.next(m.B_tl);
00295 stream.next(m.B_tr);
00296 stream.next(m.B_bl);
00297 stream.next(m.B_br);
00298 stream.next(m.qd_max);
00299 stream.next(m.u_max);
00300 stream.next(m.q_min);
00301 stream.next(m.q_max);
00302 stream.next(m.delta_f_max);
00303 stream.next(m.n_K_J_all);
00304 stream.next(m.all_J_T_K_J);
00305 stream.next(m.J);
00306 stream.next(m.f_max_delta_t);
00307 stream.next(m.mass_n_J_com);
00308 stream.next(m.Kp);
00309 stream.next(m.Kd);
00310 stream.next(m.q_des_cur_0);
00311 stream.next(m.qd_0);
00312 stream.next(m.q_0);
00313 stream.next(m.tau_cont_sum_0);
00314 }
00315
00316 ROS_DECLARE_ALLINONE_SERIALIZER;
00317 };
00318 }
00319 }
00320
00321 namespace ros
00322 {
00323 namespace message_operations
00324 {
00325
00326 template<class ContainerAllocator>
00327 struct Printer< ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> >
00328 {
00329 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::hrl_haptic_manipulation_in_clutter_msgs::MpcDynFormattedData_<ContainerAllocator> & v)
00330 {
00331 s << indent << "header: ";
00332 s << std::endl;
00333 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00334 s << indent << "alpha: ";
00335 Printer<double>::stream(s, indent + " ", v.alpha);
00336 s << indent << "delta_x_d[]" << std::endl;
00337 for (size_t i = 0; i < v.delta_x_d.size(); ++i)
00338 {
00339 s << indent << " delta_x_d[" << i << "]: ";
00340 Printer<double>::stream(s, indent + " ", v.delta_x_d[i]);
00341 }
00342 s << indent << "A_tl[]" << std::endl;
00343 for (size_t i = 0; i < v.A_tl.size(); ++i)
00344 {
00345 s << indent << " A_tl[" << i << "]: ";
00346 Printer<double>::stream(s, indent + " ", v.A_tl[i]);
00347 }
00348 s << indent << "A_tr[]" << std::endl;
00349 for (size_t i = 0; i < v.A_tr.size(); ++i)
00350 {
00351 s << indent << " A_tr[" << i << "]: ";
00352 Printer<double>::stream(s, indent + " ", v.A_tr[i]);
00353 }
00354 s << indent << "A_bl[]" << std::endl;
00355 for (size_t i = 0; i < v.A_bl.size(); ++i)
00356 {
00357 s << indent << " A_bl[" << i << "]: ";
00358 Printer<double>::stream(s, indent + " ", v.A_bl[i]);
00359 }
00360 s << indent << "A_br[]" << std::endl;
00361 for (size_t i = 0; i < v.A_br.size(); ++i)
00362 {
00363 s << indent << " A_br[" << i << "]: ";
00364 Printer<double>::stream(s, indent + " ", v.A_br[i]);
00365 }
00366 s << indent << "B_tl[]" << std::endl;
00367 for (size_t i = 0; i < v.B_tl.size(); ++i)
00368 {
00369 s << indent << " B_tl[" << i << "]: ";
00370 Printer<double>::stream(s, indent + " ", v.B_tl[i]);
00371 }
00372 s << indent << "B_tr[]" << std::endl;
00373 for (size_t i = 0; i < v.B_tr.size(); ++i)
00374 {
00375 s << indent << " B_tr[" << i << "]: ";
00376 Printer<double>::stream(s, indent + " ", v.B_tr[i]);
00377 }
00378 s << indent << "B_bl[]" << std::endl;
00379 for (size_t i = 0; i < v.B_bl.size(); ++i)
00380 {
00381 s << indent << " B_bl[" << i << "]: ";
00382 Printer<double>::stream(s, indent + " ", v.B_bl[i]);
00383 }
00384 s << indent << "B_br[]" << std::endl;
00385 for (size_t i = 0; i < v.B_br.size(); ++i)
00386 {
00387 s << indent << " B_br[" << i << "]: ";
00388 Printer<double>::stream(s, indent + " ", v.B_br[i]);
00389 }
00390 s << indent << "qd_max[]" << std::endl;
00391 for (size_t i = 0; i < v.qd_max.size(); ++i)
00392 {
00393 s << indent << " qd_max[" << i << "]: ";
00394 Printer<double>::stream(s, indent + " ", v.qd_max[i]);
00395 }
00396 s << indent << "u_max[]" << std::endl;
00397 for (size_t i = 0; i < v.u_max.size(); ++i)
00398 {
00399 s << indent << " u_max[" << i << "]: ";
00400 Printer<double>::stream(s, indent + " ", v.u_max[i]);
00401 }
00402 s << indent << "q_min[]" << std::endl;
00403 for (size_t i = 0; i < v.q_min.size(); ++i)
00404 {
00405 s << indent << " q_min[" << i << "]: ";
00406 Printer<double>::stream(s, indent + " ", v.q_min[i]);
00407 }
00408 s << indent << "q_max[]" << std::endl;
00409 for (size_t i = 0; i < v.q_max.size(); ++i)
00410 {
00411 s << indent << " q_max[" << i << "]: ";
00412 Printer<double>::stream(s, indent + " ", v.q_max[i]);
00413 }
00414 s << indent << "delta_f_max[]" << std::endl;
00415 for (size_t i = 0; i < v.delta_f_max.size(); ++i)
00416 {
00417 s << indent << " delta_f_max[" << i << "]: ";
00418 Printer<double>::stream(s, indent + " ", v.delta_f_max[i]);
00419 }
00420 s << indent << "n_K_J_all[]" << std::endl;
00421 for (size_t i = 0; i < v.n_K_J_all.size(); ++i)
00422 {
00423 s << indent << " n_K_J_all[" << i << "]: ";
00424 Printer<double>::stream(s, indent + " ", v.n_K_J_all[i]);
00425 }
00426 s << indent << "all_J_T_K_J[]" << std::endl;
00427 for (size_t i = 0; i < v.all_J_T_K_J.size(); ++i)
00428 {
00429 s << indent << " all_J_T_K_J[" << i << "]: ";
00430 Printer<double>::stream(s, indent + " ", v.all_J_T_K_J[i]);
00431 }
00432 s << indent << "J[]" << std::endl;
00433 for (size_t i = 0; i < v.J.size(); ++i)
00434 {
00435 s << indent << " J[" << i << "]: ";
00436 Printer<double>::stream(s, indent + " ", v.J[i]);
00437 }
00438 s << indent << "f_max_delta_t[]" << std::endl;
00439 for (size_t i = 0; i < v.f_max_delta_t.size(); ++i)
00440 {
00441 s << indent << " f_max_delta_t[" << i << "]: ";
00442 Printer<double>::stream(s, indent + " ", v.f_max_delta_t[i]);
00443 }
00444 s << indent << "mass_n_J_com[]" << std::endl;
00445 for (size_t i = 0; i < v.mass_n_J_com.size(); ++i)
00446 {
00447 s << indent << " mass_n_J_com[" << i << "]: ";
00448 Printer<double>::stream(s, indent + " ", v.mass_n_J_com[i]);
00449 }
00450 s << indent << "Kp[]" << std::endl;
00451 for (size_t i = 0; i < v.Kp.size(); ++i)
00452 {
00453 s << indent << " Kp[" << i << "]: ";
00454 Printer<double>::stream(s, indent + " ", v.Kp[i]);
00455 }
00456 s << indent << "Kd[]" << std::endl;
00457 for (size_t i = 0; i < v.Kd.size(); ++i)
00458 {
00459 s << indent << " Kd[" << i << "]: ";
00460 Printer<double>::stream(s, indent + " ", v.Kd[i]);
00461 }
00462 s << indent << "q_des_cur_0[]" << std::endl;
00463 for (size_t i = 0; i < v.q_des_cur_0.size(); ++i)
00464 {
00465 s << indent << " q_des_cur_0[" << i << "]: ";
00466 Printer<double>::stream(s, indent + " ", v.q_des_cur_0[i]);
00467 }
00468 s << indent << "qd_0[]" << std::endl;
00469 for (size_t i = 0; i < v.qd_0.size(); ++i)
00470 {
00471 s << indent << " qd_0[" << i << "]: ";
00472 Printer<double>::stream(s, indent + " ", v.qd_0[i]);
00473 }
00474 s << indent << "q_0[]" << std::endl;
00475 for (size_t i = 0; i < v.q_0.size(); ++i)
00476 {
00477 s << indent << " q_0[" << i << "]: ";
00478 Printer<double>::stream(s, indent + " ", v.q_0[i]);
00479 }
00480 s << indent << "tau_cont_sum_0[]" << std::endl;
00481 for (size_t i = 0; i < v.tau_cont_sum_0.size(); ++i)
00482 {
00483 s << indent << " tau_cont_sum_0[" << i << "]: ";
00484 Printer<double>::stream(s, indent + " ", v.tau_cont_sum_0[i]);
00485 }
00486 }
00487 };
00488
00489
00490 }
00491 }
00492
00493 #endif // HRL_HAPTIC_MANIPULATION_IN_CLUTTER_MSGS_MESSAGE_MPCDYNFORMATTEDDATA_H
00494