local_xy_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_LOCAL_XY_UTIL_H_
31 #define TRANSFORM_UTIL_LOCAL_XY_UTIL_H_
32 
33 #include <string>
34 
35 #include <boost/shared_ptr.hpp>
36 
37 #include <ros/ros.h>
40 
41 namespace swri_transform_util
42 {
54  void LocalXyFromWgs84(
55  double latitude,
56  double longitude,
57  double reference_latitude,
58  double reference_longitude,
59  double& x,
60  double& y);
61 
75  void Wgs84FromLocalXy(
76  double x,
77  double y,
78  double reference_latitude,
79  double reference_longitude,
80  double& latitude,
81  double& longitude);
82 
101  {
102  public:
114  double reference_latitude,
115  double reference_longitude,
116  double reference_angle = 0,
117  double reference_altitude = 0);
118 
127 
136  bool Initialized() const { return initialized_; }
137 
142  void ResetInitialization();
143 
149  double ReferenceLongitude() const;
150 
156  double ReferenceLatitude() const;
157 
161  double ReferenceAngle() const;
162 
168  double ReferenceAltitude() const;
169 
175  std::string Frame() const { return frame_; }
176 
182  std::string NormalizedFrame() const { return NormalizeFrameId(frame_); }
183 
194  bool ToLocalXy(
195  double latitude,
196  double longitude,
197  double& x,
198  double& y) const;
199 
210  bool ToWgs84(
211  double x,
212  double y,
213  double& latitude,
214  double& longitude) const;
215 
216  protected:
217  double reference_latitude_; //< Reference latitude in radians.
218  double reference_longitude_; //< Reference longitude in radians.
219  double reference_angle_; //< Reference angle in radians ENU.
220  double reference_altitude_; //< Reference altitude in meters.
221 
222  double rho_lat_;
223  double rho_lon_;
224  double cos_angle_;
225  double sin_angle_;
226 
227  std::string frame_;
228 
231 
232  void Initialize();
233 
235  };
237 }
238 
239 #endif // TRANSFORM_UTIL_LOCAL_XY_UTIL_H_
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...
std::string Frame() const
Return the TF frame ID corresponding to the local origin.
TFSIMD_FORCE_INLINE const tfScalar & y() const
bool Initialized() const
Return whether the object has been initialized.
LocalXyWgs84Util()
Zero-argument constructor.
double ReferenceLatitude() const
Return the latitude coordinate of the local origin.
boost::shared_ptr< LocalXyWgs84Util > LocalXyWgs84UtilPtr
bool ToLocalXy(double latitude, double longitude, double &x, double &y) const
Convert WGS84 latitude and longitude to LocalXY.
bool ToWgs84(double x, double y, double &latitude, double &longitude) const
Convert LocalXY to WGS84 latitude and longitude.
double ReferenceAngle() const
Return the reference angle in degrees ENU.
TFSIMD_FORCE_INLINE const tfScalar & x() const
void Wgs84FromLocalXy(double x, double y, double reference_latitude, double reference_longitude, double &latitude, double &longitude)
Transform a point from an ortho-rectified LocalXY coordinate system into WGS84 latitude and longitude...
void ResetInitialization()
Reset to "not Initialized".
Utility class for converting between WGS84 lat/lon and an ortho-rectified LocalXY coordinate system...
double ReferenceLongitude() const
Return the longitude coordinate of the local origin.
void LocalXyFromWgs84(double latitude, double longitude, double reference_latitude, double reference_longitude, double &x, double &y)
Transform a point from WGS84 lat/lon to an ortho-rectified LocalXY coordinate system.
void HandleOrigin(const topic_tools::ShapeShifter::ConstPtr origin)
std::string NormalizedFrame() const
Return the TF frame ID corresponding to the local origin with a leading slash.
double ReferenceAltitude() const
Return the altitude coordinate of the local origin.


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