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