From c6413d51bf43ec62d2119889904706e3b987e9e5 Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Fri, 8 Sep 2023 18:34:15 +0200 Subject: [PATCH] Variance isn't supported in humble --- range_sensor_broadcaster/src/range_sensor_broadcaster.cpp | 1 - .../src/range_sensor_broadcaster_parameters.yaml | 1 - .../test/test_range_sensor_broadcaster.cpp | 5 ----- .../test/test_range_sensor_broadcaster.hpp | 1 - 4 files changed, 8 deletions(-) diff --git a/range_sensor_broadcaster/src/range_sensor_broadcaster.cpp b/range_sensor_broadcaster/src/range_sensor_broadcaster.cpp index b821da8c13..72fdac3a5e 100644 --- a/range_sensor_broadcaster/src/range_sensor_broadcaster.cpp +++ b/range_sensor_broadcaster/src/range_sensor_broadcaster.cpp @@ -79,7 +79,6 @@ controller_interface::CallbackReturn RangeSensorBroadcaster::on_configure( realtime_publisher_->msg_.field_of_view = params_.field_of_view; realtime_publisher_->msg_.min_range = params_.min_range; realtime_publisher_->msg_.max_range = params_.max_range; - realtime_publisher_->msg_.variance = params_.variance; realtime_publisher_->unlock(); RCLCPP_DEBUG(get_node()->get_logger(), "configure successful"); diff --git a/range_sensor_broadcaster/src/range_sensor_broadcaster_parameters.yaml b/range_sensor_broadcaster/src/range_sensor_broadcaster_parameters.yaml index 57d39d20c4..c869cc27f2 100644 --- a/range_sensor_broadcaster/src/range_sensor_broadcaster_parameters.yaml +++ b/range_sensor_broadcaster/src/range_sensor_broadcaster_parameters.yaml @@ -13,4 +13,3 @@ range_sensor_broadcaster: field_of_view: {type: double, default_value: 0.52, description: "The size of the arc that the distance reading is valid for [rad]",} min_range: {type: double, default_value: 0.52, description: "Minimum range value [m]",} max_range: {type: double, default_value: 4.0, description: "Maximum range value [m]",} - variance: {type: double, default_value: 0.0, description: "Variance of the range value",} diff --git a/range_sensor_broadcaster/test/test_range_sensor_broadcaster.cpp b/range_sensor_broadcaster/test/test_range_sensor_broadcaster.cpp index 855f7e037b..02d7de814e 100644 --- a/range_sensor_broadcaster/test/test_range_sensor_broadcaster.cpp +++ b/range_sensor_broadcaster/test/test_range_sensor_broadcaster.cpp @@ -173,7 +173,6 @@ TEST_F(RangeSensorBroadcasterTest, Publish_RangeBroadcaster_Success) EXPECT_THAT(range_msg.field_of_view, ::testing::FloatEq(field_of_view_)); EXPECT_THAT(range_msg.min_range, ::testing::FloatEq(min_range_)); EXPECT_THAT(range_msg.max_range, ::testing::FloatEq(max_range_)); - EXPECT_THAT(range_msg.variance, ::testing::FloatEq(variance_)); } TEST_F(RangeSensorBroadcasterTest, Publish_Bandaries_RangeBroadcaster_Success) @@ -194,7 +193,6 @@ TEST_F(RangeSensorBroadcasterTest, Publish_Bandaries_RangeBroadcaster_Success) EXPECT_THAT(range_msg.field_of_view, ::testing::FloatEq(field_of_view_)); EXPECT_THAT(range_msg.min_range, ::testing::FloatEq(min_range_)); EXPECT_THAT(range_msg.max_range, ::testing::FloatEq(max_range_)); - EXPECT_THAT(range_msg.variance, ::testing::FloatEq(variance_)); sensor_range_ = 4.0; subscribe_and_get_message(range_msg); @@ -205,7 +203,6 @@ TEST_F(RangeSensorBroadcasterTest, Publish_Bandaries_RangeBroadcaster_Success) EXPECT_THAT(range_msg.field_of_view, ::testing::FloatEq(field_of_view_)); EXPECT_THAT(range_msg.min_range, ::testing::FloatEq(min_range_)); EXPECT_THAT(range_msg.max_range, ::testing::FloatEq(max_range_)); - EXPECT_THAT(range_msg.variance, ::testing::FloatEq(variance_)); } TEST_F(RangeSensorBroadcasterTest, Publish_OutOfBandaries_RangeBroadcaster_Success) @@ -227,7 +224,6 @@ TEST_F(RangeSensorBroadcasterTest, Publish_OutOfBandaries_RangeBroadcaster_Succe EXPECT_THAT(range_msg.field_of_view, ::testing::FloatEq(field_of_view_)); EXPECT_THAT(range_msg.min_range, ::testing::FloatEq(min_range_)); EXPECT_THAT(range_msg.max_range, ::testing::FloatEq(max_range_)); - EXPECT_THAT(range_msg.variance, ::testing::FloatEq(variance_)); sensor_range_ = 6.0; subscribe_and_get_message(range_msg); @@ -239,7 +235,6 @@ TEST_F(RangeSensorBroadcasterTest, Publish_OutOfBandaries_RangeBroadcaster_Succe EXPECT_THAT(range_msg.field_of_view, ::testing::FloatEq(field_of_view_)); EXPECT_THAT(range_msg.min_range, ::testing::FloatEq(min_range_)); EXPECT_THAT(range_msg.max_range, ::testing::FloatEq(max_range_)); - EXPECT_THAT(range_msg.variance, ::testing::FloatEq(variance_)); } int main(int argc, char ** argv) diff --git a/range_sensor_broadcaster/test/test_range_sensor_broadcaster.hpp b/range_sensor_broadcaster/test/test_range_sensor_broadcaster.hpp index 10696d071f..2b38cfa53c 100644 --- a/range_sensor_broadcaster/test/test_range_sensor_broadcaster.hpp +++ b/range_sensor_broadcaster/test/test_range_sensor_broadcaster.hpp @@ -43,7 +43,6 @@ class RangeSensorBroadcasterTest : public ::testing::Test const int radiation_type_ = 1; const double min_range_ = 0.1; const double max_range_ = 7.0; - const double variance_ = 1.0; double sensor_range_ = 3.1; hardware_interface::StateInterface range_{sensor_name_, "range", &sensor_range_};