global_reference.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2011, Johannes Meyer and Martin Nowara, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE 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 #ifndef HECTOR_POSE_ESTIMATION_GLOBAL_REFERENCE_H
30 #define HECTOR_POSE_ESTIMATION_GLOBAL_REFERENCE_H
31 
34 
35 #include <geographic_msgs/GeoPose.h>
36 #include <geometry_msgs/TransformStamped.h>
37 
38 #include <limits>
39 #include <boost/function.hpp>
40 
41 namespace hector_pose_estimation {
42 
43  class PoseEstimation;
44 
46  public:
47  struct Position {
48  Position() : latitude(std::numeric_limits<double>::quiet_NaN()), longitude(std::numeric_limits<double>::quiet_NaN()), altitude(std::numeric_limits<double>::quiet_NaN()) {}
49  double latitude;
50  double longitude;
51  double altitude;
52  };
53 
54  struct Heading {
55  Heading() : value(std::numeric_limits<double>::quiet_NaN()), cos(1.0), sin(0.0) {}
56  Heading(double heading);
57  double value;
58  double cos;
59  double sin;
60  operator double() const { return value; }
61  Quaternion quaternion() const;
62  };
63 
64  struct Radius {
65  Radius() : north(std::numeric_limits<double>::quiet_NaN()), east(std::numeric_limits<double>::quiet_NaN()) {}
66  Radius(double latitude);
67  double north;
68  double east;
69  };
70 
71  const Position& position() const { return position_; }
72  const Heading& heading() const { return heading_; }
73  const Radius& radius() const { return radius_; }
74 
75  void getGeoPose(geographic_msgs::GeoPose& geopose) const;
76  bool getWorldToNavTransform(geometry_msgs::TransformStamped& transform, const std::string &world_frame, const std::string &nav_frame, const ros::Time& stamp = ros::Time()) const;
77 
78  GlobalReference& setPosition(double latitude, double longitude, bool intermediate = false);
79  GlobalReference& setHeading(double heading, bool intermediate = false);
80  GlobalReference& setAltitude(double altitude, bool intermediate = false);
81 
82  GlobalReference& setCurrentPosition(const State& state, double latitude, double longitude);
83  GlobalReference& setCurrentHeading(const State& state, double heading);
84  GlobalReference& setCurrentAltitude(const State& state, double altitude);
85 
86  bool hasPosition() const { return !std::isnan(position_.latitude) && !std::isnan(position_.longitude); }
87  bool hasHeading() const { return !std::isnan(heading_.value); }
88  bool hasAltitude() const { return !std::isnan(position_.altitude); }
89 
90  void fromWGS84(double latitude, double longitude, double &x, double &y);
91  void toWGS84(double x, double y, double &latitude, double &longitude);
92  void fromNorthEast(double north, double east, double &x, double &y);
93  void toNorthEast(double x, double y, double &north, double &east);
94  void fromAltitude(double altitude, double &z);
95  void toAltitude(double z, double &altitude);
96 
98 
99  static const GlobalReferencePtr &Instance();
100 
101  void reset();
102  void updated(bool intermediate = false);
103 
104  typedef boost::function<void()> UpdateCallback;
105  void addUpdateCallback(const UpdateCallback &);
106 
107  private:
108  GlobalReference();
109 
113 
119 
120  std::list<UpdateCallback> update_callbacks_;
121  };
122 
123 } // namespace hector_pose_estimation
124 
125 #endif // HECTOR_POSE_ESTIMATION_GLOBAL_REFERENCE_H
bool getWorldToNavTransform(geometry_msgs::TransformStamped &transform, const std::string &world_frame, const std::string &nav_frame, const ros::Time &stamp=ros::Time()) const
Measurement_< HeadingModel > Heading
Definition: heading.h:53
void fromWGS84(double latitude, double longitude, double &x, double &y)
static const GlobalReferencePtr & Instance()
void toAltitude(double z, double &altitude)
void toWGS84(double x, double y, double &latitude, double &longitude)
std::list< UpdateCallback > update_callbacks_
void fromAltitude(double altitude, double &z)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void toNorthEast(double x, double y, double &north, double &east)
GlobalReference & setCurrentAltitude(const State &state, double altitude)
Eigen::Quaternion< ScalarType > Quaternion
Definition: matrix.h:49
void addUpdateCallback(const UpdateCallback &)
GlobalReference & setCurrentHeading(const State &state, double heading)
GlobalReference & setAltitude(double altitude, bool intermediate=false)
GlobalReference & setCurrentPosition(const State &state, double latitude, double longitude)
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
void getGeoPose(geographic_msgs::GeoPose &geopose) const
GlobalReference & setPosition(double latitude, double longitude, bool intermediate=false)
void fromNorthEast(double north, double east, double &x, double &y)
void updated(bool intermediate=false)
GlobalReference & setHeading(double heading, bool intermediate=false)


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Thu Feb 18 2021 03:29:30