ros2_control - jazzy
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 }
56 }
57
63 int8_t get_status() const
64 {
65 const auto data = state_interfaces_[0].get().get_optional();
66 if (data.has_value())
67 {
68 return static_cast<int8_t>(data.value());
69 }
70 return std::numeric_limits<int8_t>::max();
71 }
72
78 uint16_t get_service() const
79 {
80 const auto data = state_interfaces_[1].get().get_optional();
81 if (data.has_value())
82 {
83 return static_cast<uint16_t>(data.value());
84 }
85 return std::numeric_limits<uint16_t>::max();
86 }
87
93 double get_latitude() const
94 {
95 const auto data = state_interfaces_[2].get().get_optional();
96 if (data.has_value())
97 {
98 return data.value();
99 }
100 return std::numeric_limits<double>::quiet_NaN();
101 }
102
108 double get_longitude() const
109 {
110 const auto data = state_interfaces_[3].get().get_optional();
111 if (data.has_value())
112 {
113 return data.value();
114 }
115 return std::numeric_limits<double>::quiet_NaN();
116 }
117
123 double get_altitude() const
124 {
125 const auto data = state_interfaces_[4].get().get_optional();
126 if (data.has_value())
127 {
128 return data.value();
129 }
130 return std::numeric_limits<double>::quiet_NaN();
131 }
132
138 template <
139 typename U = void,
140 typename = std::enable_if_t<sensor_option == GPSSensorOption::WithCovariance, U>>
141 const std::array<double, 9> & get_covariance()
142 {
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())
147 {
148 covariance_[0] = data_1.value();
149 }
150 if (data_2.has_value())
151 {
152 covariance_[4] = data_2.value();
153 }
154 if (data_3.has_value())
155 {
156 covariance_[8] = data_3.value();
157 }
158 return covariance_;
159 }
160
164 bool get_values_as_message(sensor_msgs::msg::NavSatFix & message)
165 {
166 message.status.status = get_status();
167 message.status.service = get_service();
168 message.latitude = get_latitude();
169 message.longitude = get_longitude();
170 message.altitude = get_altitude();
171
172 if constexpr (sensor_option == GPSSensorOption::WithCovariance)
173 {
174 message.position_covariance = get_covariance();
175 }
176
177 return true;
178 }
179
180private:
181 std::array<double, 9> covariance_{{0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}};
182};
183
184} // namespace semantic_components
185
186#endif // SEMANTIC_COMPONENTS__GPS_SENSOR_HPP_
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