Template Class GPSSensor
Defined in File gps_sensor.hpp
Inheritance Relationships
Base Type
public semantic_components::SemanticComponentInterface< sensor_msgs::msg::NavSatFix >
(Template Class SemanticComponentInterface)
Class Documentation
-
template<GPSSensorOption sensor_option>
class GPSSensor : public semantic_components::SemanticComponentInterface<sensor_msgs::msg::NavSatFix> Public Functions
-
inline explicit GPSSensor(const std::string &name)
-
inline int8_t get_status() const
Return GPS’s status e.g. fix/no_fix
- Returns:
Status
-
inline uint16_t get_service() const
Return service used by GPS e.g. fix/no_fix
- Returns:
Service
-
inline double get_latitude() const
Return latitude reported by a GPS
- Returns:
Latitude.
-
inline double get_longitude() const
Return longitude reported by a GPS
- Returns:
Longitude.
-
inline double get_altitude() const
Return altitude reported by a GPS
- Returns:
Altitude.
-
template<typename U = void, typename = std::enable_if_t<sensor_option == GPSSensorOption::WithCovariance, U>>
inline const std::array<double, 9> &get_covariance() Return covariance reported by a GPS.
- Returns:
Covariance array.
Fills a NavSatFix message from the current values.
-
inline explicit GPSSensor(const std::string &name)