15#ifndef SEMANTIC_COMPONENTS__GPS_SENSOR_HPP_
16#define SEMANTIC_COMPONENTS__GPS_SENSOR_HPP_
22#include "semantic_components/semantic_component_interface.hpp"
23#include "sensor_msgs/msg/nav_sat_fix.hpp"
25namespace semantic_components
28enum class GPSSensorOption
34template <GPSSensorOption sensor_option>
39 sensor_option == GPSSensorOption::WithCovariance ||
40 sensor_option == GPSSensorOption::WithoutCovariance,
41 "Invalid GPSSensorOption");
42 explicit GPSSensor(
const std::string & name)
44 name, {{name +
"/" +
"status"},
45 {name +
"/" +
"service"},
46 {name +
"/" +
"latitude"},
47 {name +
"/" +
"longitude"},
48 {name +
"/" +
"altitude"}})
50 if constexpr (sensor_option == GPSSensorOption::WithCovariance)
52 interface_names_.emplace_back(name +
"/" +
"latitude_covariance");
53 interface_names_.emplace_back(name +
"/" +
"longitude_covariance");
54 interface_names_.emplace_back(name +
"/" +
"altitude_covariance");
65 const auto data = state_interfaces_[0].get().get_optional();
68 return static_cast<int8_t
>(data.value());
70 return std::numeric_limits<int8_t>::max();
80 const auto data = state_interfaces_[1].get().get_optional();
83 return static_cast<uint16_t
>(data.value());
85 return std::numeric_limits<uint16_t>::max();
95 const auto data = state_interfaces_[2].get().get_optional();
100 return std::numeric_limits<double>::quiet_NaN();
110 const auto data = state_interfaces_[3].get().get_optional();
111 if (data.has_value())
115 return std::numeric_limits<double>::quiet_NaN();
125 const auto data = state_interfaces_[4].get().get_optional();
126 if (data.has_value())
130 return std::numeric_limits<double>::quiet_NaN();
140 typename = std::enable_if_t<sensor_option == GPSSensorOption::WithCovariance, U>>
143 const auto data_1 = state_interfaces_[5].get().get_optional();
144 const auto data_2 = state_interfaces_[6].get().get_optional();
145 const auto data_3 = state_interfaces_[7].get().get_optional();
146 if (data_1.has_value())
148 covariance_[0] = data_1.value();
150 if (data_2.has_value())
152 covariance_[4] = data_2.value();
154 if (data_3.has_value())
156 covariance_[8] = data_3.value();
172 if constexpr (sensor_option == GPSSensorOption::WithCovariance)
181 std::array<double, 9> covariance_{{0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}};
Definition gps_sensor.hpp:36
double get_latitude() const
Definition gps_sensor.hpp:93
double get_longitude() const
Definition gps_sensor.hpp:108
int8_t get_status() const
Definition gps_sensor.hpp:63
bool get_values_as_message(sensor_msgs::msg::NavSatFix &message)
Definition gps_sensor.hpp:164
const std::array< double, 9 > & get_covariance()
Definition gps_sensor.hpp:141
double get_altitude() const
Definition gps_sensor.hpp:123
uint16_t get_service() const
Definition gps_sensor.hpp:78
Definition semantic_component_interface.hpp:28