ros2_control - rolling
Loading...
Searching...
No Matches
gps_sensor.hpp
1// Copyright 2025 ros2_control development team
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef SEMANTIC_COMPONENTS__GPS_SENSOR_HPP_
16#define SEMANTIC_COMPONENTS__GPS_SENSOR_HPP_
17
18#include <array>
19#include <limits>
20#include <string>
21
22#include "semantic_components/semantic_component_interface.hpp"
23#include "sensor_msgs/msg/nav_sat_fix.hpp"
24
25namespace semantic_components
26{
27
28enum class GPSSensorOption
29{
30 WithCovariance,
31 WithoutCovariance
32};
33
34template <GPSSensorOption sensor_option>
35class GPSSensor : public SemanticComponentInterface<sensor_msgs::msg::NavSatFix>
36{
37public:
38 static_assert(
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"}})
49 {
50 if constexpr (sensor_option == GPSSensorOption::WithCovariance)
51 {
52 interface_names_.emplace_back(name + "/" + "latitude_covariance");
53 interface_names_.emplace_back(name + "/" + "longitude_covariance");
54 interface_names_.emplace_back(name + "/" + "altitude_covariance");
55 state_interfaces_.reserve(state_interfaces_.capacity() + 3);
56 }
57 }
58
64 int8_t get_status() const
65 {
66 const auto data = state_interfaces_[0].get().get_optional();
67 if (data.has_value())
68 {
69 return static_cast<int8_t>(data.value());
70 }
71 return std::numeric_limits<int8_t>::max();
72 }
73
79 uint16_t get_service() const
80 {
81 const auto data = state_interfaces_[1].get().get_optional();
82 if (data.has_value())
83 {
84 return static_cast<uint16_t>(data.value());
85 }
86 return std::numeric_limits<uint16_t>::max();
87 }
88
94 double get_latitude() const
95 {
96 const auto data = state_interfaces_[2].get().get_optional();
97 if (data.has_value())
98 {
99 return data.value();
100 }
101 return std::numeric_limits<double>::quiet_NaN();
102 }
103
109 double get_longitude() const
110 {
111 const auto data = state_interfaces_[3].get().get_optional();
112 if (data.has_value())
113 {
114 return data.value();
115 }
116 return std::numeric_limits<double>::quiet_NaN();
117 }
118
124 double get_altitude() const
125 {
126 const auto data = state_interfaces_[4].get().get_optional();
127 if (data.has_value())
128 {
129 return data.value();
130 }
131 return std::numeric_limits<double>::quiet_NaN();
132 }
133
139 template <
140 typename U = void,
141 typename = std::enable_if_t<sensor_option == GPSSensorOption::WithCovariance, U>>
142 const std::array<double, 9> & get_covariance()
143 {
144 const auto data_1 = state_interfaces_[5].get().get_optional();
145 const auto data_2 = state_interfaces_[6].get().get_optional();
146 const auto data_3 = state_interfaces_[7].get().get_optional();
147 if (data_1.has_value())
148 {
149 covariance_[0] = data_1.value();
150 }
151 if (data_2.has_value())
152 {
153 covariance_[4] = data_2.value();
154 }
155 if (data_3.has_value())
156 {
157 covariance_[8] = data_3.value();
158 }
159 return covariance_;
160 }
161
165 bool get_values_as_message(sensor_msgs::msg::NavSatFix & message)
166 {
167 message.status.status = get_status();
168 message.status.service = get_service();
169 message.latitude = get_latitude();
170 message.longitude = get_longitude();
171 message.altitude = get_altitude();
172
173 if constexpr (sensor_option == GPSSensorOption::WithCovariance)
174 {
175 message.position_covariance = get_covariance();
176 }
177
178 return true;
179 }
180
181private:
182 std::array<double, 9> covariance_{{0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}};
183};
184
185} // namespace semantic_components
186
187#endif // SEMANTIC_COMPONENTS__GPS_SENSOR_HPP_
Definition gps_sensor.hpp:36
double get_latitude() const
Definition gps_sensor.hpp:94
double get_longitude() const
Definition gps_sensor.hpp:109
int8_t get_status() const
Definition gps_sensor.hpp:64
bool get_values_as_message(sensor_msgs::msg::NavSatFix &message)
Definition gps_sensor.hpp:165
const std::array< double, 9 > & get_covariance()
Definition gps_sensor.hpp:142
double get_altitude() const
Definition gps_sensor.hpp:124
uint16_t get_service() const
Definition gps_sensor.hpp:79
Definition semantic_component_interface.hpp:28