Skip to content

Commit

Permalink
Make covariance always available
Browse files Browse the repository at this point in the history
  • Loading branch information
Wiktor-99 committed Jan 14, 2025
1 parent d638af7 commit 165c3c3
Showing 1 changed file with 1 addition and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@ class GPSSensor : public SemanticComponentInterface<sensor_msgs::msg::NavSatFix>
interface_names_.emplace_back(name + "/" + "latitude_covariance");
interface_names_.emplace_back(name + "/" + "longitude_covariance");
interface_names_.emplace_back(name + "/" + "altitude_covariance");
covariance_.fill(0.0);
}
}

Expand Down Expand Up @@ -118,11 +117,7 @@ class GPSSensor : public SemanticComponentInterface<sensor_msgs::msg::NavSatFix>
}

private:
struct Empty
{
};
using CovarianceArray = std::conditional_t<use_covariance, std::array<double, 9>, Empty>;
CovarianceArray covariance_;
std::array<double, 9> covariance_{{0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}};
};

} // namespace semantic_components
Expand Down

0 comments on commit 165c3c3

Please sign in to comment.