00001
00002 #ifndef TELEOP_CONTROLLERS_MESSAGE_JINVTELEOPCONTROLLERSTATE_H
00003 #define TELEOP_CONTROLLERS_MESSAGE_JINVTELEOPCONTROLLERSTATE_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "std_msgs/Header.h"
00014 #include "geometry_msgs/PoseStamped.h"
00015 #include "geometry_msgs/PoseStamped.h"
00016 #include "geometry_msgs/PoseStamped.h"
00017 #include "geometry_msgs/Twist.h"
00018 #include "geometry_msgs/Twist.h"
00019 #include "geometry_msgs/Twist.h"
00020 #include "geometry_msgs/Wrench.h"
00021 #include "std_msgs/Float64MultiArray.h"
00022 #include "std_msgs/Float64MultiArray.h"
00023
00024 namespace teleop_controllers
00025 {
00026 template <class ContainerAllocator>
00027 struct JinvTeleopControllerState_ : public ros::Message
00028 {
00029 typedef JinvTeleopControllerState_<ContainerAllocator> Type;
00030
00031 JinvTeleopControllerState_()
00032 : header()
00033 , x()
00034 , x_desi()
00035 , x_desi_filtered()
00036 , x_err()
00037 , xd()
00038 , xd_desi()
00039 , F()
00040 , q_proxy()
00041 , qd_pose()
00042 , qd_posture()
00043 , qd_posture_raw()
00044 , qd_desi()
00045 , tau()
00046 , J()
00047 , N()
00048 , df(0.0)
00049 , dx(0.0)
00050 , Df(0.0)
00051 , Dx(0.0)
00052 , stiffness(0.0)
00053 , compliance(0.0)
00054 {
00055 }
00056
00057 JinvTeleopControllerState_(const ContainerAllocator& _alloc)
00058 : header(_alloc)
00059 , x(_alloc)
00060 , x_desi(_alloc)
00061 , x_desi_filtered(_alloc)
00062 , x_err(_alloc)
00063 , xd(_alloc)
00064 , xd_desi(_alloc)
00065 , F(_alloc)
00066 , q_proxy(_alloc)
00067 , qd_pose(_alloc)
00068 , qd_posture(_alloc)
00069 , qd_posture_raw(_alloc)
00070 , qd_desi(_alloc)
00071 , tau(_alloc)
00072 , J(_alloc)
00073 , N(_alloc)
00074 , df(0.0)
00075 , dx(0.0)
00076 , Df(0.0)
00077 , Dx(0.0)
00078 , stiffness(0.0)
00079 , compliance(0.0)
00080 {
00081 }
00082
00083 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00084 ::std_msgs::Header_<ContainerAllocator> header;
00085
00086 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _x_type;
00087 ::geometry_msgs::PoseStamped_<ContainerAllocator> x;
00088
00089 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _x_desi_type;
00090 ::geometry_msgs::PoseStamped_<ContainerAllocator> x_desi;
00091
00092 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _x_desi_filtered_type;
00093 ::geometry_msgs::PoseStamped_<ContainerAllocator> x_desi_filtered;
00094
00095 typedef ::geometry_msgs::Twist_<ContainerAllocator> _x_err_type;
00096 ::geometry_msgs::Twist_<ContainerAllocator> x_err;
00097
00098 typedef ::geometry_msgs::Twist_<ContainerAllocator> _xd_type;
00099 ::geometry_msgs::Twist_<ContainerAllocator> xd;
00100
00101 typedef ::geometry_msgs::Twist_<ContainerAllocator> _xd_desi_type;
00102 ::geometry_msgs::Twist_<ContainerAllocator> xd_desi;
00103
00104 typedef ::geometry_msgs::Wrench_<ContainerAllocator> _F_type;
00105 ::geometry_msgs::Wrench_<ContainerAllocator> F;
00106
00107 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _q_proxy_type;
00108 std::vector<double, typename ContainerAllocator::template rebind<double>::other > q_proxy;
00109
00110 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _qd_pose_type;
00111 std::vector<double, typename ContainerAllocator::template rebind<double>::other > qd_pose;
00112
00113 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _qd_posture_type;
00114 std::vector<double, typename ContainerAllocator::template rebind<double>::other > qd_posture;
00115
00116 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _qd_posture_raw_type;
00117 std::vector<double, typename ContainerAllocator::template rebind<double>::other > qd_posture_raw;
00118
00119 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _qd_desi_type;
00120 std::vector<double, typename ContainerAllocator::template rebind<double>::other > qd_desi;
00121
00122 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _tau_type;
00123 std::vector<double, typename ContainerAllocator::template rebind<double>::other > tau;
00124
00125 typedef ::std_msgs::Float64MultiArray_<ContainerAllocator> _J_type;
00126 ::std_msgs::Float64MultiArray_<ContainerAllocator> J;
00127
00128 typedef ::std_msgs::Float64MultiArray_<ContainerAllocator> _N_type;
00129 ::std_msgs::Float64MultiArray_<ContainerAllocator> N;
00130
00131 typedef double _df_type;
00132 double df;
00133
00134 typedef double _dx_type;
00135 double dx;
00136
00137 typedef double _Df_type;
00138 double Df;
00139
00140 typedef double _Dx_type;
00141 double Dx;
00142
00143 typedef double _stiffness_type;
00144 double stiffness;
00145
00146 typedef double _compliance_type;
00147 double compliance;
00148
00149
00150 ROS_DEPRECATED uint32_t get_q_proxy_size() const { return (uint32_t)q_proxy.size(); }
00151 ROS_DEPRECATED void set_q_proxy_size(uint32_t size) { q_proxy.resize((size_t)size); }
00152 ROS_DEPRECATED void get_q_proxy_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->q_proxy; }
00153 ROS_DEPRECATED void set_q_proxy_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->q_proxy = vec; }
00154 ROS_DEPRECATED uint32_t get_qd_pose_size() const { return (uint32_t)qd_pose.size(); }
00155 ROS_DEPRECATED void set_qd_pose_size(uint32_t size) { qd_pose.resize((size_t)size); }
00156 ROS_DEPRECATED void get_qd_pose_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->qd_pose; }
00157 ROS_DEPRECATED void set_qd_pose_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->qd_pose = vec; }
00158 ROS_DEPRECATED uint32_t get_qd_posture_size() const { return (uint32_t)qd_posture.size(); }
00159 ROS_DEPRECATED void set_qd_posture_size(uint32_t size) { qd_posture.resize((size_t)size); }
00160 ROS_DEPRECATED void get_qd_posture_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->qd_posture; }
00161 ROS_DEPRECATED void set_qd_posture_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->qd_posture = vec; }
00162 ROS_DEPRECATED uint32_t get_qd_posture_raw_size() const { return (uint32_t)qd_posture_raw.size(); }
00163 ROS_DEPRECATED void set_qd_posture_raw_size(uint32_t size) { qd_posture_raw.resize((size_t)size); }
00164 ROS_DEPRECATED void get_qd_posture_raw_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->qd_posture_raw; }
00165 ROS_DEPRECATED void set_qd_posture_raw_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->qd_posture_raw = vec; }
00166 ROS_DEPRECATED uint32_t get_qd_desi_size() const { return (uint32_t)qd_desi.size(); }
00167 ROS_DEPRECATED void set_qd_desi_size(uint32_t size) { qd_desi.resize((size_t)size); }
00168 ROS_DEPRECATED void get_qd_desi_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->qd_desi; }
00169 ROS_DEPRECATED void set_qd_desi_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->qd_desi = vec; }
00170 ROS_DEPRECATED uint32_t get_tau_size() const { return (uint32_t)tau.size(); }
00171 ROS_DEPRECATED void set_tau_size(uint32_t size) { tau.resize((size_t)size); }
00172 ROS_DEPRECATED void get_tau_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->tau; }
00173 ROS_DEPRECATED void set_tau_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->tau = vec; }
00174 private:
00175 static const char* __s_getDataType_() { return "teleop_controllers/JinvTeleopControllerState"; }
00176 public:
00177 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00178
00179 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00180
00181 private:
00182 static const char* __s_getMD5Sum_() { return "1456444fe71f72390283aef7aca2934d"; }
00183 public:
00184 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00185
00186 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00187
00188 private:
00189 static const char* __s_getMessageDefinition_() { return "Header header\n\
00190 geometry_msgs/PoseStamped x\n\
00191 geometry_msgs/PoseStamped x_desi\n\
00192 geometry_msgs/PoseStamped x_desi_filtered\n\
00193 geometry_msgs/Twist x_err\n\
00194 geometry_msgs/Twist xd\n\
00195 geometry_msgs/Twist xd_desi\n\
00196 geometry_msgs/Wrench F\n\
00197 float64[] q_proxy\n\
00198 float64[] qd_pose\n\
00199 float64[] qd_posture\n\
00200 float64[] qd_posture_raw\n\
00201 float64[] qd_desi\n\
00202 float64[] tau\n\
00203 std_msgs/Float64MultiArray J\n\
00204 std_msgs/Float64MultiArray N\n\
00205 \n\
00206 # Environmental stiffness\n\
00207 float64 df\n\
00208 float64 dx\n\
00209 float64 Df\n\
00210 float64 Dx\n\
00211 float64 stiffness\n\
00212 float64 compliance\n\
00213 \n\
00214 ================================================================================\n\
00215 MSG: std_msgs/Header\n\
00216 # Standard metadata for higher-level stamped data types.\n\
00217 # This is generally used to communicate timestamped data \n\
00218 # in a particular coordinate frame.\n\
00219 # \n\
00220 # sequence ID: consecutively increasing ID \n\
00221 uint32 seq\n\
00222 #Two-integer timestamp that is expressed as:\n\
00223 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00224 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00225 # time-handling sugar is provided by the client library\n\
00226 time stamp\n\
00227 #Frame this data is associated with\n\
00228 # 0: no frame\n\
00229 # 1: global frame\n\
00230 string frame_id\n\
00231 \n\
00232 ================================================================================\n\
00233 MSG: geometry_msgs/PoseStamped\n\
00234 # A Pose with reference coordinate frame and timestamp\n\
00235 Header header\n\
00236 Pose pose\n\
00237 \n\
00238 ================================================================================\n\
00239 MSG: geometry_msgs/Pose\n\
00240 # A representation of pose in free space, composed of postion and orientation. \n\
00241 Point position\n\
00242 Quaternion orientation\n\
00243 \n\
00244 ================================================================================\n\
00245 MSG: geometry_msgs/Point\n\
00246 # This contains the position of a point in free space\n\
00247 float64 x\n\
00248 float64 y\n\
00249 float64 z\n\
00250 \n\
00251 ================================================================================\n\
00252 MSG: geometry_msgs/Quaternion\n\
00253 # This represents an orientation in free space in quaternion form.\n\
00254 \n\
00255 float64 x\n\
00256 float64 y\n\
00257 float64 z\n\
00258 float64 w\n\
00259 \n\
00260 ================================================================================\n\
00261 MSG: geometry_msgs/Twist\n\
00262 # This expresses velocity in free space broken into it's linear and angular parts. \n\
00263 Vector3 linear\n\
00264 Vector3 angular\n\
00265 \n\
00266 ================================================================================\n\
00267 MSG: geometry_msgs/Vector3\n\
00268 # This represents a vector in free space. \n\
00269 \n\
00270 float64 x\n\
00271 float64 y\n\
00272 float64 z\n\
00273 ================================================================================\n\
00274 MSG: geometry_msgs/Wrench\n\
00275 # This represents force in free space, seperated into \n\
00276 # it's linear and angular parts. \n\
00277 Vector3 force\n\
00278 Vector3 torque\n\
00279 \n\
00280 ================================================================================\n\
00281 MSG: std_msgs/Float64MultiArray\n\
00282 # Please look at the MultiArrayLayout message definition for\n\
00283 # documentation on all multiarrays.\n\
00284 \n\
00285 MultiArrayLayout layout # specification of data layout\n\
00286 float64[] data # array of data\n\
00287 \n\
00288 \n\
00289 ================================================================================\n\
00290 MSG: std_msgs/MultiArrayLayout\n\
00291 # The multiarray declares a generic multi-dimensional array of a\n\
00292 # particular data type. Dimensions are ordered from outer most\n\
00293 # to inner most.\n\
00294 \n\
00295 MultiArrayDimension[] dim # Array of dimension properties\n\
00296 uint32 data_offset # padding bytes at front of data\n\
00297 \n\
00298 # Accessors should ALWAYS be written in terms of dimension stride\n\
00299 # and specified outer-most dimension first.\n\
00300 # \n\
00301 # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\
00302 #\n\
00303 # A standard, 3-channel 640x480 image with interleaved color channels\n\
00304 # would be specified as:\n\
00305 #\n\
00306 # dim[0].label = \"height\"\n\
00307 # dim[0].size = 480\n\
00308 # dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\
00309 # dim[1].label = \"width\"\n\
00310 # dim[1].size = 640\n\
00311 # dim[1].stride = 3*640 = 1920\n\
00312 # dim[2].label = \"channel\"\n\
00313 # dim[2].size = 3\n\
00314 # dim[2].stride = 3\n\
00315 #\n\
00316 # multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\
00317 ================================================================================\n\
00318 MSG: std_msgs/MultiArrayDimension\n\
00319 string label # label of given dimension\n\
00320 uint32 size # size of given dimension (in type units)\n\
00321 uint32 stride # stride of given dimension\n\
00322 "; }
00323 public:
00324 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00325
00326 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00327
00328 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00329 {
00330 ros::serialization::OStream stream(write_ptr, 1000000000);
00331 ros::serialization::serialize(stream, header);
00332 ros::serialization::serialize(stream, x);
00333 ros::serialization::serialize(stream, x_desi);
00334 ros::serialization::serialize(stream, x_desi_filtered);
00335 ros::serialization::serialize(stream, x_err);
00336 ros::serialization::serialize(stream, xd);
00337 ros::serialization::serialize(stream, xd_desi);
00338 ros::serialization::serialize(stream, F);
00339 ros::serialization::serialize(stream, q_proxy);
00340 ros::serialization::serialize(stream, qd_pose);
00341 ros::serialization::serialize(stream, qd_posture);
00342 ros::serialization::serialize(stream, qd_posture_raw);
00343 ros::serialization::serialize(stream, qd_desi);
00344 ros::serialization::serialize(stream, tau);
00345 ros::serialization::serialize(stream, J);
00346 ros::serialization::serialize(stream, N);
00347 ros::serialization::serialize(stream, df);
00348 ros::serialization::serialize(stream, dx);
00349 ros::serialization::serialize(stream, Df);
00350 ros::serialization::serialize(stream, Dx);
00351 ros::serialization::serialize(stream, stiffness);
00352 ros::serialization::serialize(stream, compliance);
00353 return stream.getData();
00354 }
00355
00356 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00357 {
00358 ros::serialization::IStream stream(read_ptr, 1000000000);
00359 ros::serialization::deserialize(stream, header);
00360 ros::serialization::deserialize(stream, x);
00361 ros::serialization::deserialize(stream, x_desi);
00362 ros::serialization::deserialize(stream, x_desi_filtered);
00363 ros::serialization::deserialize(stream, x_err);
00364 ros::serialization::deserialize(stream, xd);
00365 ros::serialization::deserialize(stream, xd_desi);
00366 ros::serialization::deserialize(stream, F);
00367 ros::serialization::deserialize(stream, q_proxy);
00368 ros::serialization::deserialize(stream, qd_pose);
00369 ros::serialization::deserialize(stream, qd_posture);
00370 ros::serialization::deserialize(stream, qd_posture_raw);
00371 ros::serialization::deserialize(stream, qd_desi);
00372 ros::serialization::deserialize(stream, tau);
00373 ros::serialization::deserialize(stream, J);
00374 ros::serialization::deserialize(stream, N);
00375 ros::serialization::deserialize(stream, df);
00376 ros::serialization::deserialize(stream, dx);
00377 ros::serialization::deserialize(stream, Df);
00378 ros::serialization::deserialize(stream, Dx);
00379 ros::serialization::deserialize(stream, stiffness);
00380 ros::serialization::deserialize(stream, compliance);
00381 return stream.getData();
00382 }
00383
00384 ROS_DEPRECATED virtual uint32_t serializationLength() const
00385 {
00386 uint32_t size = 0;
00387 size += ros::serialization::serializationLength(header);
00388 size += ros::serialization::serializationLength(x);
00389 size += ros::serialization::serializationLength(x_desi);
00390 size += ros::serialization::serializationLength(x_desi_filtered);
00391 size += ros::serialization::serializationLength(x_err);
00392 size += ros::serialization::serializationLength(xd);
00393 size += ros::serialization::serializationLength(xd_desi);
00394 size += ros::serialization::serializationLength(F);
00395 size += ros::serialization::serializationLength(q_proxy);
00396 size += ros::serialization::serializationLength(qd_pose);
00397 size += ros::serialization::serializationLength(qd_posture);
00398 size += ros::serialization::serializationLength(qd_posture_raw);
00399 size += ros::serialization::serializationLength(qd_desi);
00400 size += ros::serialization::serializationLength(tau);
00401 size += ros::serialization::serializationLength(J);
00402 size += ros::serialization::serializationLength(N);
00403 size += ros::serialization::serializationLength(df);
00404 size += ros::serialization::serializationLength(dx);
00405 size += ros::serialization::serializationLength(Df);
00406 size += ros::serialization::serializationLength(Dx);
00407 size += ros::serialization::serializationLength(stiffness);
00408 size += ros::serialization::serializationLength(compliance);
00409 return size;
00410 }
00411
00412 typedef boost::shared_ptr< ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> > Ptr;
00413 typedef boost::shared_ptr< ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> const> ConstPtr;
00414 };
00415 typedef ::teleop_controllers::JinvTeleopControllerState_<std::allocator<void> > JinvTeleopControllerState;
00416
00417 typedef boost::shared_ptr< ::teleop_controllers::JinvTeleopControllerState> JinvTeleopControllerStatePtr;
00418 typedef boost::shared_ptr< ::teleop_controllers::JinvTeleopControllerState const> JinvTeleopControllerStateConstPtr;
00419
00420
00421 template<typename ContainerAllocator>
00422 std::ostream& operator<<(std::ostream& s, const ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> & v)
00423 {
00424 ros::message_operations::Printer< ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> >::stream(s, "", v);
00425 return s;}
00426
00427 }
00428
00429 namespace ros
00430 {
00431 namespace message_traits
00432 {
00433 template<class ContainerAllocator>
00434 struct MD5Sum< ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> > {
00435 static const char* value()
00436 {
00437 return "1456444fe71f72390283aef7aca2934d";
00438 }
00439
00440 static const char* value(const ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> &) { return value(); }
00441 static const uint64_t static_value1 = 0x1456444fe71f7239ULL;
00442 static const uint64_t static_value2 = 0x0283aef7aca2934dULL;
00443 };
00444
00445 template<class ContainerAllocator>
00446 struct DataType< ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> > {
00447 static const char* value()
00448 {
00449 return "teleop_controllers/JinvTeleopControllerState";
00450 }
00451
00452 static const char* value(const ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> &) { return value(); }
00453 };
00454
00455 template<class ContainerAllocator>
00456 struct Definition< ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> > {
00457 static const char* value()
00458 {
00459 return "Header header\n\
00460 geometry_msgs/PoseStamped x\n\
00461 geometry_msgs/PoseStamped x_desi\n\
00462 geometry_msgs/PoseStamped x_desi_filtered\n\
00463 geometry_msgs/Twist x_err\n\
00464 geometry_msgs/Twist xd\n\
00465 geometry_msgs/Twist xd_desi\n\
00466 geometry_msgs/Wrench F\n\
00467 float64[] q_proxy\n\
00468 float64[] qd_pose\n\
00469 float64[] qd_posture\n\
00470 float64[] qd_posture_raw\n\
00471 float64[] qd_desi\n\
00472 float64[] tau\n\
00473 std_msgs/Float64MultiArray J\n\
00474 std_msgs/Float64MultiArray N\n\
00475 \n\
00476 # Environmental stiffness\n\
00477 float64 df\n\
00478 float64 dx\n\
00479 float64 Df\n\
00480 float64 Dx\n\
00481 float64 stiffness\n\
00482 float64 compliance\n\
00483 \n\
00484 ================================================================================\n\
00485 MSG: std_msgs/Header\n\
00486 # Standard metadata for higher-level stamped data types.\n\
00487 # This is generally used to communicate timestamped data \n\
00488 # in a particular coordinate frame.\n\
00489 # \n\
00490 # sequence ID: consecutively increasing ID \n\
00491 uint32 seq\n\
00492 #Two-integer timestamp that is expressed as:\n\
00493 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00494 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00495 # time-handling sugar is provided by the client library\n\
00496 time stamp\n\
00497 #Frame this data is associated with\n\
00498 # 0: no frame\n\
00499 # 1: global frame\n\
00500 string frame_id\n\
00501 \n\
00502 ================================================================================\n\
00503 MSG: geometry_msgs/PoseStamped\n\
00504 # A Pose with reference coordinate frame and timestamp\n\
00505 Header header\n\
00506 Pose pose\n\
00507 \n\
00508 ================================================================================\n\
00509 MSG: geometry_msgs/Pose\n\
00510 # A representation of pose in free space, composed of postion and orientation. \n\
00511 Point position\n\
00512 Quaternion orientation\n\
00513 \n\
00514 ================================================================================\n\
00515 MSG: geometry_msgs/Point\n\
00516 # This contains the position of a point in free space\n\
00517 float64 x\n\
00518 float64 y\n\
00519 float64 z\n\
00520 \n\
00521 ================================================================================\n\
00522 MSG: geometry_msgs/Quaternion\n\
00523 # This represents an orientation in free space in quaternion form.\n\
00524 \n\
00525 float64 x\n\
00526 float64 y\n\
00527 float64 z\n\
00528 float64 w\n\
00529 \n\
00530 ================================================================================\n\
00531 MSG: geometry_msgs/Twist\n\
00532 # This expresses velocity in free space broken into it's linear and angular parts. \n\
00533 Vector3 linear\n\
00534 Vector3 angular\n\
00535 \n\
00536 ================================================================================\n\
00537 MSG: geometry_msgs/Vector3\n\
00538 # This represents a vector in free space. \n\
00539 \n\
00540 float64 x\n\
00541 float64 y\n\
00542 float64 z\n\
00543 ================================================================================\n\
00544 MSG: geometry_msgs/Wrench\n\
00545 # This represents force in free space, seperated into \n\
00546 # it's linear and angular parts. \n\
00547 Vector3 force\n\
00548 Vector3 torque\n\
00549 \n\
00550 ================================================================================\n\
00551 MSG: std_msgs/Float64MultiArray\n\
00552 # Please look at the MultiArrayLayout message definition for\n\
00553 # documentation on all multiarrays.\n\
00554 \n\
00555 MultiArrayLayout layout # specification of data layout\n\
00556 float64[] data # array of data\n\
00557 \n\
00558 \n\
00559 ================================================================================\n\
00560 MSG: std_msgs/MultiArrayLayout\n\
00561 # The multiarray declares a generic multi-dimensional array of a\n\
00562 # particular data type. Dimensions are ordered from outer most\n\
00563 # to inner most.\n\
00564 \n\
00565 MultiArrayDimension[] dim # Array of dimension properties\n\
00566 uint32 data_offset # padding bytes at front of data\n\
00567 \n\
00568 # Accessors should ALWAYS be written in terms of dimension stride\n\
00569 # and specified outer-most dimension first.\n\
00570 # \n\
00571 # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\
00572 #\n\
00573 # A standard, 3-channel 640x480 image with interleaved color channels\n\
00574 # would be specified as:\n\
00575 #\n\
00576 # dim[0].label = \"height\"\n\
00577 # dim[0].size = 480\n\
00578 # dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\
00579 # dim[1].label = \"width\"\n\
00580 # dim[1].size = 640\n\
00581 # dim[1].stride = 3*640 = 1920\n\
00582 # dim[2].label = \"channel\"\n\
00583 # dim[2].size = 3\n\
00584 # dim[2].stride = 3\n\
00585 #\n\
00586 # multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\
00587 ================================================================================\n\
00588 MSG: std_msgs/MultiArrayDimension\n\
00589 string label # label of given dimension\n\
00590 uint32 size # size of given dimension (in type units)\n\
00591 uint32 stride # stride of given dimension\n\
00592 ";
00593 }
00594
00595 static const char* value(const ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> &) { return value(); }
00596 };
00597
00598 template<class ContainerAllocator> struct HasHeader< ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> > : public TrueType {};
00599 template<class ContainerAllocator> struct HasHeader< const ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> > : public TrueType {};
00600 }
00601 }
00602
00603 namespace ros
00604 {
00605 namespace serialization
00606 {
00607
00608 template<class ContainerAllocator> struct Serializer< ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> >
00609 {
00610 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00611 {
00612 stream.next(m.header);
00613 stream.next(m.x);
00614 stream.next(m.x_desi);
00615 stream.next(m.x_desi_filtered);
00616 stream.next(m.x_err);
00617 stream.next(m.xd);
00618 stream.next(m.xd_desi);
00619 stream.next(m.F);
00620 stream.next(m.q_proxy);
00621 stream.next(m.qd_pose);
00622 stream.next(m.qd_posture);
00623 stream.next(m.qd_posture_raw);
00624 stream.next(m.qd_desi);
00625 stream.next(m.tau);
00626 stream.next(m.J);
00627 stream.next(m.N);
00628 stream.next(m.df);
00629 stream.next(m.dx);
00630 stream.next(m.Df);
00631 stream.next(m.Dx);
00632 stream.next(m.stiffness);
00633 stream.next(m.compliance);
00634 }
00635
00636 ROS_DECLARE_ALLINONE_SERIALIZER;
00637 };
00638 }
00639 }
00640
00641 namespace ros
00642 {
00643 namespace message_operations
00644 {
00645
00646 template<class ContainerAllocator>
00647 struct Printer< ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> >
00648 {
00649 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::teleop_controllers::JinvTeleopControllerState_<ContainerAllocator> & v)
00650 {
00651 s << indent << "header: ";
00652 s << std::endl;
00653 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00654 s << indent << "x: ";
00655 s << std::endl;
00656 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.x);
00657 s << indent << "x_desi: ";
00658 s << std::endl;
00659 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.x_desi);
00660 s << indent << "x_desi_filtered: ";
00661 s << std::endl;
00662 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.x_desi_filtered);
00663 s << indent << "x_err: ";
00664 s << std::endl;
00665 Printer< ::geometry_msgs::Twist_<ContainerAllocator> >::stream(s, indent + " ", v.x_err);
00666 s << indent << "xd: ";
00667 s << std::endl;
00668 Printer< ::geometry_msgs::Twist_<ContainerAllocator> >::stream(s, indent + " ", v.xd);
00669 s << indent << "xd_desi: ";
00670 s << std::endl;
00671 Printer< ::geometry_msgs::Twist_<ContainerAllocator> >::stream(s, indent + " ", v.xd_desi);
00672 s << indent << "F: ";
00673 s << std::endl;
00674 Printer< ::geometry_msgs::Wrench_<ContainerAllocator> >::stream(s, indent + " ", v.F);
00675 s << indent << "q_proxy[]" << std::endl;
00676 for (size_t i = 0; i < v.q_proxy.size(); ++i)
00677 {
00678 s << indent << " q_proxy[" << i << "]: ";
00679 Printer<double>::stream(s, indent + " ", v.q_proxy[i]);
00680 }
00681 s << indent << "qd_pose[]" << std::endl;
00682 for (size_t i = 0; i < v.qd_pose.size(); ++i)
00683 {
00684 s << indent << " qd_pose[" << i << "]: ";
00685 Printer<double>::stream(s, indent + " ", v.qd_pose[i]);
00686 }
00687 s << indent << "qd_posture[]" << std::endl;
00688 for (size_t i = 0; i < v.qd_posture.size(); ++i)
00689 {
00690 s << indent << " qd_posture[" << i << "]: ";
00691 Printer<double>::stream(s, indent + " ", v.qd_posture[i]);
00692 }
00693 s << indent << "qd_posture_raw[]" << std::endl;
00694 for (size_t i = 0; i < v.qd_posture_raw.size(); ++i)
00695 {
00696 s << indent << " qd_posture_raw[" << i << "]: ";
00697 Printer<double>::stream(s, indent + " ", v.qd_posture_raw[i]);
00698 }
00699 s << indent << "qd_desi[]" << std::endl;
00700 for (size_t i = 0; i < v.qd_desi.size(); ++i)
00701 {
00702 s << indent << " qd_desi[" << i << "]: ";
00703 Printer<double>::stream(s, indent + " ", v.qd_desi[i]);
00704 }
00705 s << indent << "tau[]" << std::endl;
00706 for (size_t i = 0; i < v.tau.size(); ++i)
00707 {
00708 s << indent << " tau[" << i << "]: ";
00709 Printer<double>::stream(s, indent + " ", v.tau[i]);
00710 }
00711 s << indent << "J: ";
00712 s << std::endl;
00713 Printer< ::std_msgs::Float64MultiArray_<ContainerAllocator> >::stream(s, indent + " ", v.J);
00714 s << indent << "N: ";
00715 s << std::endl;
00716 Printer< ::std_msgs::Float64MultiArray_<ContainerAllocator> >::stream(s, indent + " ", v.N);
00717 s << indent << "df: ";
00718 Printer<double>::stream(s, indent + " ", v.df);
00719 s << indent << "dx: ";
00720 Printer<double>::stream(s, indent + " ", v.dx);
00721 s << indent << "Df: ";
00722 Printer<double>::stream(s, indent + " ", v.Df);
00723 s << indent << "Dx: ";
00724 Printer<double>::stream(s, indent + " ", v.Dx);
00725 s << indent << "stiffness: ";
00726 Printer<double>::stream(s, indent + " ", v.stiffness);
00727 s << indent << "compliance: ";
00728 Printer<double>::stream(s, indent + " ", v.compliance);
00729 }
00730 };
00731
00732
00733 }
00734 }
00735
00736 #endif // TELEOP_CONTROLLERS_MESSAGE_JINVTELEOPCONTROLLERSTATE_H
00737