transform_util.h
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
30 #ifndef TRANSFORM_UTIL_TRANSFORM_UTIL_H_
31 #define TRANSFORM_UTIL_TRANSFORM_UTIL_H_
32 
33 #include <string>
34 #include <boost/array.hpp>
35 
36 #include <tf/transform_datatypes.h>
37 
38 namespace swri_transform_util
39 {
41  double latitude,
42  double longitude,
43  double yaw,
44  double reference_latitude,
45  double reference_longitude,
46  double reference_yaw);
47 
58  double GreatCircleDistance(
59  double src_latitude,
60  double src_longitude,
61  double dst_latitude,
62  double dst_longitude);
63 
72  double GreatCircleDistance(const tf::Vector3& src, const tf::Vector3& dst);
73 
83  double GetBearing(
84  double source_latitude,
85  double source_longitude,
86  double destination_latitude,
87  double destination_longitude);
88 
99  void GetMidpointLatLon(
100  double latitude1,
101  double longitude1,
102  double latitude2,
103  double longitude2,
104  double& mid_latitude,
105  double& mid_longitude);
106 
120  double GetHeading(double src_x, double src_y, double dst_x, double dst_y);
121 
131  double ToHeading(double yaw);
132 
142  double ToYaw(double heading);
143 
152 
160  tf::Vector3 GetPrimaryAxis(const tf::Vector3& vector);
161 
169  bool IsRotation(tf::Matrix3x3 matrix);
170 
178  tf::Matrix3x3 GetUpperLeft(const boost::array<double, 36>& matrix);
179 
187  tf::Matrix3x3 GetLowerRight(const boost::array<double, 36>& matrix);
188 
196  tf::Matrix3x3 Get3x3Cov(const boost::array<double, 9>& matrix);
197 
206  void Set3x3Cov(const tf::Matrix3x3& matrix_in,
207  boost::array<double, 9>& matrix_out);
215  void SetUpperLeft(
216  const tf::Matrix3x3& sub_matrix,
217  boost::array<double, 36>& matrix);
218 
226  void SetLowerRight(
227  const tf::Matrix3x3& sub_matrix,
228  boost::array<double, 36>& matrix);
229 
241  double latitude,
242  double altitude,
243  double arc_length);
244 
255  double altitude,
256  double arc_length);
257 
266  std::string NormalizeFrameId(const std::string& frame_id);
267 
282  bool FrameIdsEqual(const std::string& frame1, const std::string& frame2);
283 }
284 
285 #endif // TRANSFORM_UTIL_TRANSFORM_UTIL_H_
286 
std::string NormalizeFrameId(const std::string &frame_id)
Normalize a TF frame ID by assuming that frames with relative paths are in the global namespace and a...
double GreatCircleDistance(double src_latitude, double src_longitude, double dst_latitude, double dst_longitude)
Calculates the great circle distance between two points.
tf::Transform GetRelativeTransform(double latitude, double longitude, double yaw, double reference_latitude, double reference_longitude, double reference_yaw)
tf::Matrix3x3 GetLowerRight(const boost::array< double, 36 > &matrix)
Gets the lower-right 3x3 sub-matrix of a 6x6 matrix.
double LatitudeDegreesFromMeters(double altitude, double arc_length)
Calculate the subtending angle of an arc (aligned with the latitudinal coordinate axis at the specifi...
tf::Quaternion SnapToRightAngle(const tf::Quaternion &rotation)
Snaps a quaternion rotation to the closest right angle rotation.
bool FrameIdsEqual(const std::string &frame1, const std::string &frame2)
Compare two TF frame IDs, assuming that frames with relative paths are in the global namespace...
double GetBearing(double source_latitude, double source_longitude, double destination_latitude, double destination_longitude)
Calculates the bearing between two points.
double GetHeading(double src_x, double src_y, double dst_x, double dst_y)
Calculates the heading in degrees from a source and destination point in a north-oriented (+y = north...
void SetLowerRight(const tf::Matrix3x3 &sub_matrix, boost::array< double, 36 > &matrix)
Sets the lower-right quadrant of a 6x6 matrix with the specified 3x3 sub-matrix.
tf::Matrix3x3 GetUpperLeft(const boost::array< double, 36 > &matrix)
Gets the upper-left 3x3 sub-matrix of a 6x6 matrix.
void GetMidpointLatLon(double latitude1, double longitude1, double latitude2, double longitude2, double &mid_latitude, double &mid_longitude)
Find the midpoint on the arc between two lat/lon points.
tf::Matrix3x3 Get3x3Cov(const boost::array< double, 9 > &matrix)
Converts the 3x3 covariance matrices from Imu messages to a Matrix3x3.
void SetUpperLeft(const tf::Matrix3x3 &sub_matrix, boost::array< double, 36 > &matrix)
Sets the upper-left quadrant of a 6x6 matrix with the specified 3x3 sub-matrix.
bool IsRotation(tf::Matrix3x3 matrix)
Validate that a 3x3 matrix is a rotation.
double ToHeading(double yaw)
Convert yaw to heading, where yaw is in radians, counter-clockwise, with 0 on the positive x-axis and...
void Set3x3Cov(const tf::Matrix3x3 &matrix_in, boost::array< double, 9 > &matrix_out)
Converts the Matrix3x3 matrix into a 9 element covariance matrix from Imu messages.
tf::Vector3 GetPrimaryAxis(const tf::Vector3 &vector)
Return an axis aligned unit vector that is nearest the provided vector.
double ToYaw(double heading)
Convert heading to yaw, where yaw is in radians, counter-clockwise, with 0 on the positive x-axis and...
double LongitudeDegreesFromMeters(double latitude, double altitude, double arc_length)
Calculate the subtending angle of an arc (aligned with the longitudinal coordinate axis at the specif...


swri_transform_util
Author(s): Marc Alban
autogenerated on Tue Apr 6 2021 02:50:46