windows bring up, use ROS_DEPRECATED
James Xu authored 5 years ago
Tully Foote committed 5 years ago
40 | 40 | #include <geometry_msgs/Vector3.h> |
41 | 41 | #include <geometry_msgs/Wrench.h> |
42 | 42 | |
43 | #include <ros/macros.h> | |
43 | 44 | |
44 | 45 | namespace tf { |
45 | 46 | /// Conversion functions from/to the corresponding KDL and geometry_msgs types. |
89 | 90 | |
90 | 91 | //Deprecated methods use above: |
91 | 92 | /// Converts a Pose message into a KDL Frame |
92 | void PoseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)__attribute__((deprecated)); | |
93 | ROS_DEPRECATED void PoseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k); | |
93 | 94 | |
94 | 95 | /// Converts a KDL Frame into a Pose message |
95 | void PoseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m) __attribute__((deprecated)); | |
96 | ROS_DEPRECATED void PoseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m); | |
96 | 97 | |
97 | 98 | |
98 | 99 | |
99 | 100 | /// Converts a Twist message into a KDL Twist |
100 | void TwistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &k) __attribute__((deprecated)); | |
101 | ROS_DEPRECATED void TwistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &k); | |
101 | 102 | |
102 | 103 | /// Converts a KDL Twist into a Twist message |
103 | void TwistKDLToMsg(const KDL::Twist &k, geometry_msgs::Twist &m) __attribute__((deprecated)); | |
104 | ROS_DEPRECATED void TwistKDLToMsg(const KDL::Twist &k, geometry_msgs::Twist &m); | |
104 | 105 | |
105 | 106 | |
106 | 107 |
17 | 17 | |
18 | 18 | #include "Vector3.h" |
19 | 19 | #include "Quaternion.h" |
20 | ||
21 | #include <ros/macros.h> | |
20 | 22 | |
21 | 23 | namespace tf |
22 | 24 | { |
162 | 164 | * @param pitch Pitch about Y axis |
163 | 165 | * @param roll Roll about X axis |
164 | 166 | */ |
165 | void setEulerZYX(const tfScalar& yaw, const tfScalar& pitch, const tfScalar& roll) __attribute__((deprecated)) | |
167 | ROS_DEPRECATED void setEulerZYX(const tfScalar& yaw, const tfScalar& pitch, const tfScalar& roll) | |
166 | 168 | { |
167 | 169 | setEulerYPR(yaw, pitch, roll); |
168 | 170 | } |
278 | 280 | * @param pitch Pitch around Y axis |
279 | 281 | * @param roll around X axis |
280 | 282 | * @param solution_number Which solution of two possible solutions ( 1 or 2) are possible values*/ |
281 | __attribute__((deprecated)) void getEulerZYX(tfScalar& yaw, tfScalar& pitch, tfScalar& roll, unsigned int solution_number = 1) const | |
283 | ROS_DEPRECATED void getEulerZYX(tfScalar& yaw, tfScalar& pitch, tfScalar& roll, unsigned int solution_number = 1) const | |
282 | 284 | { |
283 | 285 | getEulerYPR(yaw, pitch, roll, solution_number); |
284 | 286 | }; |
19 | 19 | |
20 | 20 | #include "Vector3.h" |
21 | 21 | #include "QuadWord.h" |
22 | ||
23 | #include <ros/macros.h> | |
22 | 24 | |
23 | 25 | namespace tf |
24 | 26 | { |
47 | 49 | * @param yaw Angle around Y unless TF_EULER_DEFAULT_ZYX defined then Z |
48 | 50 | * @param pitch Angle around X unless TF_EULER_DEFAULT_ZYX defined then Y |
49 | 51 | * @param roll Angle around Z unless TF_EULER_DEFAULT_ZYX defined then X */ |
50 | Quaternion(const tfScalar& yaw, const tfScalar& pitch, const tfScalar& roll) __attribute__((deprecated)) | |
52 | ROS_DEPRECATED Quaternion(const tfScalar& yaw, const tfScalar& pitch, const tfScalar& roll) | |
51 | 53 | { |
52 | 54 | #ifndef TF_EULER_DEFAULT_ZYX |
53 | 55 | setEuler(yaw, pitch, roll); |
110 | 112 | * @param yaw Angle around Z |
111 | 113 | * @param pitch Angle around Y |
112 | 114 | * @param roll Angle around X */ |
113 | void setEulerZYX(const tfScalar& yaw, const tfScalar& pitch, const tfScalar& roll) __attribute__((deprecated)) | |
115 | ROS_DEPRECATED void setEulerZYX(const tfScalar& yaw, const tfScalar& pitch, const tfScalar& roll) | |
114 | 116 | { |
115 | 117 | setRPY(roll, pitch, yaw); |
116 | 118 | } |
34 | 34 | * It has an un-used w component to suit 16-byte alignment when Vector3 is stored in containers. This extra component can be used by derived classes (Quaternion?) or by user |
35 | 35 | * Ideally, this class should be replaced by a platform optimized SIMD version that keeps the data in registers |
36 | 36 | */ |
37 | class Vector3 | |
37 | ATTRIBUTE_ALIGNED16(class) Vector3 | |
38 | 38 | { |
39 | 39 | public: |
40 | 40 | |
346 | 346 | |
347 | 347 | TFSIMD_FORCE_INLINE void deSerializeDouble(const struct Vector3DoubleData& dataIn); |
348 | 348 | |
349 | } __attribute__ ((aligned(16))); | |
349 | }; | |
350 | 350 | |
351 | 351 | /**@brief Return the sum of two vectors (Point symantics)*/ |
352 | 352 | TFSIMD_FORCE_INLINE Vector3 |
46 | 46 | #include "geometry_msgs/TwistStamped.h" |
47 | 47 | |
48 | 48 | #include <tf2_ros/buffer.h> |
49 | #include <ros/macros.h> | |
49 | 50 | |
50 | 51 | namespace tf |
51 | 52 | { |
56 | 57 | std::string strip_leading_slash(const std::string& frame_name); |
57 | 58 | |
58 | 59 | /** \deprecated This has been renamed to tf::resolve */ |
59 | __attribute__((deprecated)) static inline std::string remap(const std::string& prefix, const std::string& frame_name) { return tf::resolve(prefix, frame_name);} ; | |
60 | ROS_DEPRECATED static inline std::string remap(const std::string& prefix, const std::string& frame_name) { return tf::resolve(prefix, frame_name);} ; | |
60 | 61 | |
61 | 62 | enum ErrorValues { NO_ERROR = 0, LOOKUP_ERROR, CONNECTIVITY_ERROR, EXTRAPOLATION_ERROR}; |
62 | 63 |
37 | 37 | #include "tf/tf.h" |
38 | 38 | #include "ros/ros.h" |
39 | 39 | #include "ros/callback_queue.h" |
40 | #include "ros/macros.h" | |
40 | 41 | |
41 | 42 | #include "tf/FrameGraph.h" //frame graph service |
42 | 43 | #include "boost/thread.hpp" |
62 | 63 | |
63 | 64 | /** \brief resolve names |
64 | 65 | * \deprecated Use TransformListener::remap instead */ |
65 | std::string remap(const std::string& frame_id) __attribute__((deprecated)); | |
66 | ROS_DEPRECATED std::string remap(const std::string& frame_id); | |
66 | 67 | |
67 | 68 | /** \brief This class inherits from Transformer and automatically subscribes to ROS transform messages */ |
68 | 69 | class TransformListener : public Transformer { //subscribes to message and automatically stores incoming data |
36 | 36 | #include <geometry_msgs/Pose.h> |
37 | 37 | #include <geometry_msgs/Twist.h> |
38 | 38 | |
39 | #include <ros/macros.h> | |
40 | ||
39 | 41 | namespace tf |
40 | 42 | { |
41 | 43 | |
65 | 67 | |
66 | 68 | /* DEPRECATED FUNCTIONS */ |
67 | 69 | /// Starting from a Pose from A to B, apply a Twist with reference frame A and reference point B, during a time t. |
68 | geometry_msgs::Pose addDelta(const geometry_msgs::Pose &pose, const geometry_msgs::Twist &twist, const double &t) __attribute__((deprecated)); | |
70 | ROS_DEPRECATED geometry_msgs::Pose addDelta(const geometry_msgs::Pose &pose, const geometry_msgs::Twist &twist, const double &t); | |
69 | 71 | |
70 | 72 | |
71 | 73 | /// Converts a tf Pose into a KDL Frame |
72 | void PoseTFToKDL(const tf::Pose &t, KDL::Frame &k) __attribute__((deprecated)); | |
74 | ROS_DEPRECATED void PoseTFToKDL(const tf::Pose &t, KDL::Frame &k); | |
73 | 75 | void inline PoseTFToKDL(const tf::Pose &t, KDL::Frame &k) {poseTFToKDL(t, k);}; |
74 | 76 | |
75 | 77 | /// Converts a KDL Frame into a tf Pose |
76 | void PoseKDLToTF(const KDL::Frame &k, tf::Pose &t) __attribute__((deprecated)); | |
78 | ROS_DEPRECATED void PoseKDLToTF(const KDL::Frame &k, tf::Pose &t); | |
77 | 79 | void inline PoseKDLToTF(const KDL::Frame &k, tf::Pose &t) {poseKDLToTF(k, t);}; |
78 | 80 | |
79 | 81 | /// Converts a tf Quaternion into a KDL Rotation |
80 | void QuaternionTFToKDL(const tf::Quaternion &t, KDL::Rotation &k) __attribute__((deprecated)); | |
82 | ROS_DEPRECATED void QuaternionTFToKDL(const tf::Quaternion &t, KDL::Rotation &k); | |
81 | 83 | void inline QuaternionTFToKDL(const tf::Quaternion &t, KDL::Rotation &k) {quaternionTFToKDL(t, k);}; |
82 | 84 | |
83 | 85 | /// Converts a tf Quaternion into a KDL Rotation |
84 | void QuaternionKDLToTF(const KDL::Rotation &k, tf::Quaternion &t) __attribute__((deprecated)); | |
86 | ROS_DEPRECATED void QuaternionKDLToTF(const KDL::Rotation &k, tf::Quaternion &t); | |
85 | 87 | void inline QuaternionKDLToTF(const KDL::Rotation &k, tf::Quaternion &t) {quaternionKDLToTF(k, t);}; |
86 | 88 | |
87 | 89 | /// Converts a tf Transform into a KDL Frame |
88 | void TransformTFToKDL(const tf::Transform &t, KDL::Frame &k) __attribute__((deprecated)); | |
90 | ROS_DEPRECATED void TransformTFToKDL(const tf::Transform &t, KDL::Frame &k); | |
89 | 91 | void inline TransformTFToKDL(const tf::Transform &t, KDL::Frame &k) {transformTFToKDL(t, k);}; |
90 | 92 | |
91 | 93 | /// Converts a KDL Frame into a tf Transform |
92 | void TransformKDLToTF(const KDL::Frame &k, tf::Transform &t) __attribute__((deprecated)); | |
94 | ROS_DEPRECATED void TransformKDLToTF(const KDL::Frame &k, tf::Transform &t); | |
93 | 95 | void inline TransformKDLToTF(const KDL::Frame &k, tf::Transform &t) {transformKDLToTF(k, t);}; |
94 | 96 | |
95 | 97 | /// Converts a tf Vector3 into a KDL Vector |
96 | void VectorTFToKDL(const tf::Vector3 &t, KDL::Vector &k) __attribute__((deprecated)); | |
98 | ROS_DEPRECATED void VectorTFToKDL(const tf::Vector3 &t, KDL::Vector &k); | |
97 | 99 | void inline VectorTFToKDL(const tf::Vector3 &t, KDL::Vector &k) {vectorTFToKDL(t, k);}; |
98 | 100 | |
99 | 101 | /// Converts a tf Vector3 into a KDL Vector |
100 | void VectorKDLToTF(const KDL::Vector &k, tf::Vector3 &t) __attribute__((deprecated)); | |
102 | ROS_DEPRECATED void VectorKDLToTF(const KDL::Vector &k, tf::Vector3 &t); | |
101 | 103 | void inline VectorKDLToTF(const KDL::Vector &k, tf::Vector3 &t) {vectorKDLToTF(k, t);}; |
102 | 104 | |
103 | 105 |