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