Codebase list ros-geometry / ef828f0
windows bring up, use ROS_DEPRECATED James Xu authored 5 years ago Tully Foote committed 5 years ago
7 changed file(s) with 30 addition(s) and 21 deletion(s). Raw diff Collapse all Expand all
4040 #include <geometry_msgs/Vector3.h>
4141 #include <geometry_msgs/Wrench.h>
4242
43 #include <ros/macros.h>
4344
4445 namespace tf {
4546 /// Conversion functions from/to the corresponding KDL and geometry_msgs types.
8990
9091 //Deprecated methods use above:
9192 /// 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);
9394
9495 /// 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);
9697
9798
9899
99100 /// 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);
101102
102103 /// 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);
104105
105106
106107
1717
1818 #include "Vector3.h"
1919 #include "Quaternion.h"
20
21 #include <ros/macros.h>
2022
2123 namespace tf
2224 {
162164 * @param pitch Pitch about Y axis
163165 * @param roll Roll about X axis
164166 */
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)
166168 {
167169 setEulerYPR(yaw, pitch, roll);
168170 }
278280 * @param pitch Pitch around Y axis
279281 * @param roll around X axis
280282 * @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
282284 {
283285 getEulerYPR(yaw, pitch, roll, solution_number);
284286 };
1919
2020 #include "Vector3.h"
2121 #include "QuadWord.h"
22
23 #include <ros/macros.h>
2224
2325 namespace tf
2426 {
4749 * @param yaw Angle around Y unless TF_EULER_DEFAULT_ZYX defined then Z
4850 * @param pitch Angle around X unless TF_EULER_DEFAULT_ZYX defined then Y
4951 * @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)
5153 {
5254 #ifndef TF_EULER_DEFAULT_ZYX
5355 setEuler(yaw, pitch, roll);
110112 * @param yaw Angle around Z
111113 * @param pitch Angle around Y
112114 * @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)
114116 {
115117 setRPY(roll, pitch, yaw);
116118 }
3434 * 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
3535 * Ideally, this class should be replaced by a platform optimized SIMD version that keeps the data in registers
3636 */
37 class Vector3
37 ATTRIBUTE_ALIGNED16(class) Vector3
3838 {
3939 public:
4040
346346
347347 TFSIMD_FORCE_INLINE void deSerializeDouble(const struct Vector3DoubleData& dataIn);
348348
349 } __attribute__ ((aligned(16)));
349 };
350350
351351 /**@brief Return the sum of two vectors (Point symantics)*/
352352 TFSIMD_FORCE_INLINE Vector3
4646 #include "geometry_msgs/TwistStamped.h"
4747
4848 #include <tf2_ros/buffer.h>
49 #include <ros/macros.h>
4950
5051 namespace tf
5152 {
5657 std::string strip_leading_slash(const std::string& frame_name);
5758
5859 /** \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);} ;
6061
6162 enum ErrorValues { NO_ERROR = 0, LOOKUP_ERROR, CONNECTIVITY_ERROR, EXTRAPOLATION_ERROR};
6263
3737 #include "tf/tf.h"
3838 #include "ros/ros.h"
3939 #include "ros/callback_queue.h"
40 #include "ros/macros.h"
4041
4142 #include "tf/FrameGraph.h" //frame graph service
4243 #include "boost/thread.hpp"
6263
6364 /** \brief resolve names
6465 * \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);
6667
6768 /** \brief This class inherits from Transformer and automatically subscribes to ROS transform messages */
6869 class TransformListener : public Transformer { //subscribes to message and automatically stores incoming data
3636 #include <geometry_msgs/Pose.h>
3737 #include <geometry_msgs/Twist.h>
3838
39 #include <ros/macros.h>
40
3941 namespace tf
4042 {
4143
6567
6668 /* DEPRECATED FUNCTIONS */
6769 /// 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);
6971
7072
7173 /// 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);
7375 void inline PoseTFToKDL(const tf::Pose &t, KDL::Frame &k) {poseTFToKDL(t, k);};
7476
7577 /// 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);
7779 void inline PoseKDLToTF(const KDL::Frame &k, tf::Pose &t) {poseKDLToTF(k, t);};
7880
7981 /// 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);
8183 void inline QuaternionTFToKDL(const tf::Quaternion &t, KDL::Rotation &k) {quaternionTFToKDL(t, k);};
8284
8385 /// 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);
8587 void inline QuaternionKDLToTF(const KDL::Rotation &k, tf::Quaternion &t) {quaternionKDLToTF(k, t);};
8688
8789 /// 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);
8991 void inline TransformTFToKDL(const tf::Transform &t, KDL::Frame &k) {transformTFToKDL(t, k);};
9092
9193 /// 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);
9395 void inline TransformKDLToTF(const KDL::Frame &k, tf::Transform &t) {transformKDLToTF(k, t);};
9496
9597 /// 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);
9799 void inline VectorTFToKDL(const tf::Vector3 &t, KDL::Vector &k) {vectorTFToKDL(t, k);};
98100
99101 /// 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);
101103 void inline VectorKDLToTF(const KDL::Vector &k, tf::Vector3 &t) {vectorKDLToTF(k, t);};
102104
103105