Skip to content

Commit

Permalink
Add GPSSensorOption enum
Browse files Browse the repository at this point in the history
  • Loading branch information
Wiktor-99 committed Jan 18, 2025
1 parent b4a1ee7 commit a052502
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 10 deletions.
17 changes: 12 additions & 5 deletions controller_interface/include/semantic_components/gps_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,15 +17,20 @@

#include <array>
#include <string>
#include <vector>

#include "semantic_components/semantic_component_interface.hpp"
#include "sensor_msgs/msg/nav_sat_fix.hpp"

namespace semantic_components
{

template <bool use_covariance>
enum class GPSSensorOption
{
WithCovariance,
WithoutCovariance
};

template <GPSSensorOption sensor_option>
class GPSSensor : public SemanticComponentInterface<sensor_msgs::msg::NavSatFix>
{
public:
Expand All @@ -37,7 +42,7 @@ class GPSSensor : public SemanticComponentInterface<sensor_msgs::msg::NavSatFix>
{name + "/" + "longitude"},
{name + "/" + "altitude"}})
{
if constexpr (use_covariance)
if constexpr (sensor_option == GPSSensorOption::WithCovariance)
{
interface_names_.emplace_back(name + "/" + "latitude_covariance");
interface_names_.emplace_back(name + "/" + "longitude_covariance");
Expand Down Expand Up @@ -88,7 +93,9 @@ class GPSSensor : public SemanticComponentInterface<sensor_msgs::msg::NavSatFix>
*
* \return Covariance array.
*/
template <typename U = void, typename = std::enable_if_t<use_covariance, U>>
template <
typename U = void,
typename = std::enable_if_t<sensor_option == GPSSensorOption::WithCovariance, U>>
const std::array<double, 9> & get_covariance()
{
covariance_[0] = state_interfaces_[5].get().get_value();
Expand All @@ -108,7 +115,7 @@ class GPSSensor : public SemanticComponentInterface<sensor_msgs::msg::NavSatFix>
message.longitude = get_longitude();
message.altitude = get_altitude();

if constexpr (use_covariance)
if constexpr (sensor_option == GPSSensorOption::WithCovariance)
{
message.position_covariance = get_covariance();
}
Expand Down
10 changes: 5 additions & 5 deletions controller_interface/test/test_gps_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
#include <gtest/gtest.h>
#include <algorithm>
#include <array>
#include <iterator>
#include <string>
#include <vector>
#include "hardware_interface/handle.hpp"
#include "hardware_interface/loaned_state_interface.hpp"
#include "semantic_components/gps_sensor.hpp"
Expand All @@ -42,8 +42,8 @@ struct GPSSensorTest : public testing::Test
const std::array<std::string, 5> gps_interface_names{
{"status", "service", "latitude", "longitude", "altitude"}};
std::array<double, 5> gps_states{};
static constexpr bool use_covariance{false};
semantic_components::GPSSensor<use_covariance> sut{gps_sensor_name};
semantic_components::GPSSensor<semantic_components::GPSSensorOption::WithoutCovariance> sut{
gps_sensor_name};
std::vector<std::string> full_interface_names;

hardware_interface::StateInterface gps_state{
Expand Down Expand Up @@ -140,8 +140,8 @@ struct GPSSensorWithCovarianceTest : public testing::Test
{"status", "service", "latitude", "longitude", "altitude", "latitude_covariance",
"longitude_covariance", "altitude_covariance"}};
std::array<double, 8> gps_states{};
static constexpr bool use_covariance{true};
semantic_components::GPSSensor<use_covariance> sut{gps_sensor_name};
semantic_components::GPSSensor<semantic_components::GPSSensorOption::WithCovariance> sut{
gps_sensor_name};
std::vector<std::string> full_interface_names;

hardware_interface::StateInterface gps_state{
Expand Down

0 comments on commit a052502

Please sign in to comment.