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 <string>
20
21#include "semantic_components/semantic_component_interface.hpp"
22#include "sensor_msgs/msg/nav_sat_fix.hpp"
23
24namespace semantic_components
25{
26
27enum class GPSSensorOption
28{
29 WithCovariance,
30 WithoutCovariance
31};
32
33template <GPSSensorOption sensor_option>
34class GPSSensor : public SemanticComponentInterface<sensor_msgs::msg::NavSatFix>
35{
36public:
37 static_assert(
38 sensor_option == GPSSensorOption::WithCovariance ||
39 sensor_option == GPSSensorOption::WithoutCovariance,
40 "Invalid GPSSensorOption");
41 explicit GPSSensor(const std::string & name)
43 name, {{name + "/" + "status"},
44 {name + "/" + "service"},
45 {name + "/" + "latitude"},
46 {name + "/" + "longitude"},
47 {name + "/" + "altitude"}})
48 {
49 if constexpr (sensor_option == GPSSensorOption::WithCovariance)
50 {
51 interface_names_.emplace_back(name + "/" + "latitude_covariance");
52 interface_names_.emplace_back(name + "/" + "longitude_covariance");
53 interface_names_.emplace_back(name + "/" + "altitude_covariance");
54 }
55 }
56
62 int8_t get_status() const { return static_cast<int8_t>(state_interfaces_[0].get().get_value()); }
63
69 uint16_t get_service() const
70 {
71 return static_cast<uint16_t>(state_interfaces_[1].get().get_value());
72 }
73
79 double get_latitude() const { return state_interfaces_[2].get().get_value(); }
80
86 double get_longitude() const { return state_interfaces_[3].get().get_value(); }
87
93 double get_altitude() const { return state_interfaces_[4].get().get_value(); }
94
100 template <
101 typename U = void,
102 typename = std::enable_if_t<sensor_option == GPSSensorOption::WithCovariance, U>>
103 const std::array<double, 9> & get_covariance()
104 {
105 covariance_[0] = state_interfaces_[5].get().get_value();
106 covariance_[4] = state_interfaces_[6].get().get_value();
107 covariance_[8] = state_interfaces_[7].get().get_value();
108 return covariance_;
109 }
110
114 bool get_values_as_message(sensor_msgs::msg::NavSatFix & message)
115 {
116 message.status.status = get_status();
117 message.status.service = get_service();
118 message.latitude = get_latitude();
119 message.longitude = get_longitude();
120 message.altitude = get_altitude();
121
122 if constexpr (sensor_option == GPSSensorOption::WithCovariance)
123 {
124 message.position_covariance = get_covariance();
125 }
126
127 return true;
128 }
129
130private:
131 std::array<double, 9> covariance_{{0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}};
132};
133
134} // namespace semantic_components
135
136#endif // SEMANTIC_COMPONENTS__GPS_SENSOR_HPP_
Definition gps_sensor.hpp:35
double get_latitude() const
Definition gps_sensor.hpp:79
double get_longitude() const
Definition gps_sensor.hpp:86
int8_t get_status() const
Definition gps_sensor.hpp:62
bool get_values_as_message(sensor_msgs::msg::NavSatFix &message)
Definition gps_sensor.hpp:114
const std::array< double, 9 > & get_covariance()
Definition gps_sensor.hpp:103
double get_altitude() const
Definition gps_sensor.hpp:93
uint16_t get_service() const
Definition gps_sensor.hpp:69
Definition semantic_component_interface.hpp:28