From 15e9c65a8fac921873de58169f88dd8070d9024f Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 9 Sep 2024 15:22:09 +0200 Subject: [PATCH] dist-sensor: reduce enum names --- msg/DistanceSensor.msg | 8 ++++---- .../lightware_laser_i2c/lightware_laser_i2c.cpp | 4 ++-- src/lib/drivers/rangefinder/PX4Rangefinder.cpp | 2 +- src/lib/drivers/rangefinder/PX4Rangefinder.hpp | 2 +- .../HealthAndArmingChecks/checks/distanceSensorChecks.cpp | 2 +- 5 files changed, 9 insertions(+), 9 deletions(-) diff --git a/msg/DistanceSensor.msg b/msg/DistanceSensor.msg index 88bd8ca819..4b7cffefd0 100644 --- a/msg/DistanceSensor.msg +++ b/msg/DistanceSensor.msg @@ -41,7 +41,7 @@ uint8 ROTATION_DOWNWARD_FACING = 25 # MAV_SENSOR_ROTATION_PITCH_270 uint8 ROTATION_CUSTOM = 100 # MAV_SENSOR_ROTATION_CUSTOM -uint8 mode # mode of operation -uint8 DISTANCE_SENSOR_MODE_UNKNOWN = 0 # Unknown mode -uint8 DISTANCE_SENSOR_MODE_RUN = 1 # sensor is running continuosly -uint8 DISTANCE_SENSOR_MODE_DISABLED = 2 # sensor is disabled per request +uint8 mode +uint8 MODE_UNKNOWN = 0 +uint8 MODE_ENABLED = 1 +uint8 MODE_DISABLED = 2 diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp index 0bc0f55a77..6c1dfbcea0 100644 --- a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp +++ b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp @@ -499,7 +499,7 @@ void LightwareLaser::RunImpl() case State::Running: if (!_restriction) { - _px4_rangefinder.set_mode(distance_sensor_s::DISTANCE_SENSOR_MODE_RUN); + _px4_rangefinder.set_mode(distance_sensor_s::MODE_ENABLED); if (PX4_OK != collect()) { PX4_DEBUG("collection error"); @@ -511,7 +511,7 @@ void LightwareLaser::RunImpl() } } else { - _px4_rangefinder.set_mode(distance_sensor_s::DISTANCE_SENSOR_MODE_DISABLED); + _px4_rangefinder.set_mode(distance_sensor_s::MODE_DISABLED); if (!_prev_restriction) { // Publish disabled status once _px4_rangefinder.update(hrt_absolute_time(), -1.f, 0); diff --git a/src/lib/drivers/rangefinder/PX4Rangefinder.cpp b/src/lib/drivers/rangefinder/PX4Rangefinder.cpp index e26f3215fc..98c479efb1 100644 --- a/src/lib/drivers/rangefinder/PX4Rangefinder.cpp +++ b/src/lib/drivers/rangefinder/PX4Rangefinder.cpp @@ -40,7 +40,7 @@ PX4Rangefinder::PX4Rangefinder(const uint32_t device_id, const uint8_t device_or set_device_id(device_id); set_orientation(device_orientation); set_rangefinder_type(distance_sensor_s::MAV_DISTANCE_SENSOR_LASER); - set_mode(distance_sensor_s::DISTANCE_SENSOR_MODE_UNKNOWN); + set_mode(distance_sensor_s::MODE_UNKNOWN); } PX4Rangefinder::~PX4Rangefinder() diff --git a/src/lib/drivers/rangefinder/PX4Rangefinder.hpp b/src/lib/drivers/rangefinder/PX4Rangefinder.hpp index 1005242aba..725f03d321 100644 --- a/src/lib/drivers/rangefinder/PX4Rangefinder.hpp +++ b/src/lib/drivers/rangefinder/PX4Rangefinder.hpp @@ -60,7 +60,7 @@ public: void set_orientation(const uint8_t device_orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING); - void set_mode(const uint8_t mode) {_distance_sensor_pub.get().mode = mode; } + void set_mode(const uint8_t mode) { _distance_sensor_pub.get().mode = mode; } void update(const hrt_abstime ×tamp_sample, const float distance, const int8_t quality = -1); diff --git a/src/modules/commander/HealthAndArmingChecks/checks/distanceSensorChecks.cpp b/src/modules/commander/HealthAndArmingChecks/checks/distanceSensorChecks.cpp index 02b0a390fd..fceb5e740b 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/distanceSensorChecks.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/distanceSensorChecks.cpp @@ -49,7 +49,7 @@ void DistanceSensorChecks::checkAndReport(const Context &context, Report &report if (exists) { distance_sensor_s dist_sens; valid = _distance_sensor_sub[instance].copy(&dist_sens) && ((hrt_elapsed_time(&dist_sens.timestamp) < 1_s) - || (dist_sens.mode == distance_sensor_s::DISTANCE_SENSOR_MODE_DISABLED)); + || (dist_sens.mode == distance_sensor_s::MODE_DISABLED)); reporter.setIsPresent(health_component_t::distance_sensor); }