From 5f76e1f313d3fa3f21d1d64ed183db7f55ef5ded Mon Sep 17 00:00:00 2001 From: Ryan howard Date: Wed, 6 Mar 2024 15:48:19 -0500 Subject: [PATCH] format --- include/can/core/messages.hpp | 1 + .../core/tasks/capacitive_sensor_task.hpp | 7 +--- .../core/tasks/environmental_sensor_task.hpp | 6 +-- .../sensors/core/tasks/pressure_driver.hpp | 40 ++++++++++--------- .../core/tasks/pressure_sensor_task.hpp | 7 ++-- 5 files changed, 28 insertions(+), 33 deletions(-) diff --git a/include/can/core/messages.hpp b/include/can/core/messages.hpp index 0be445fdd..6fab3098c 100644 --- a/include/can/core/messages.hpp +++ b/include/can/core/messages.hpp @@ -1693,6 +1693,7 @@ struct GetHepaUVStateResponse -> bool = default; }; +// NOLINTNEXTLINE(cppcoreguidelines-pro-type-member-init) struct AddSensorMoveRequest : BaseMessage { uint32_t message_index; uint8_t group_id; diff --git a/include/sensors/core/tasks/capacitive_sensor_task.hpp b/include/sensors/core/tasks/capacitive_sensor_task.hpp index 7aac91529..57c677d2a 100644 --- a/include/sensors/core/tasks/capacitive_sensor_task.hpp +++ b/include/sensors/core/tasks/capacitive_sensor_task.hpp @@ -65,13 +65,8 @@ class CapacitiveMessageHandler { } } - void visit(const can::messages::SendAccumulatedPressureDataRequest &m) { + void visit(const can::messages::SendAccumulatedPressureDataRequest &) { LOG("Received request to dump pressure data buffer %d", m.sensor_id); - - if (m.message_index == 0) - return; - else - return; } void visit(can::messages::ReadFromSensorRequest &m) { diff --git a/include/sensors/core/tasks/environmental_sensor_task.hpp b/include/sensors/core/tasks/environmental_sensor_task.hpp index 60f6684e6..8fd304c18 100644 --- a/include/sensors/core/tasks/environmental_sensor_task.hpp +++ b/include/sensors/core/tasks/environmental_sensor_task.hpp @@ -75,12 +75,8 @@ class EnvironmentSensorMessageHandler { driver.trigger_on_demand(); } - void visit(const can::messages::SendAccumulatedPressureDataRequest &m) { + void visit(const can::messages::SendAccumulatedPressureDataRequest &) { LOG("Received request to dump pressure data buffer %d", sensor_id); - if (m.message_index == 0) - return; - else - return; } void visit(const can::messages::BindSensorOutputRequest &m) { diff --git a/include/sensors/core/tasks/pressure_driver.hpp b/include/sensors/core/tasks/pressure_driver.hpp index d9f58ad87..801d17309 100644 --- a/include/sensors/core/tasks/pressure_driver.hpp +++ b/include/sensors/core/tasks/pressure_driver.hpp @@ -15,9 +15,9 @@ #include "sensors/core/utils.hpp" #if PIPETTE_TYPE_DEFINE == NINETY_SIX_CHANNEL -#define PRESSURE_SENSOR_BUFFER_SIZE 1800 +constexpr size_t PRESSURE_SENSOR_BUFFER_SIZE = 1800; #else -#define PRESSURE_SENSOR_BUFFER_SIZE 3000 +constexpr size_t PRESSURE_SENSOR_BUFFER_SIZE = 3000; #endif namespace sensors { @@ -42,14 +42,15 @@ class MMR920 { CanClient &can_client, OwnQueue &own_queue, sensors::hardware::SensorHardwareBase &hardware, const can::ids::SensorId &id, - const sensors::mmr920::SensorVersion version, std::array *p_buff) + const sensors::mmr920::SensorVersion version, + std::array *p_buff) : writer(writer), poller(poller), can_client(can_client), own_queue(own_queue), hardware(hardware), sensor_id(id), - sensor_version(version) {} + sensor_version(version), p_buff(p_buff) {} /** @@ -285,12 +286,12 @@ class MMR920 { void send_accumulated_pressure_data(uint32_t message_index) { can_client.send_can_message( - can::ids::NodeId::host, - can::messages::ReadFromSensorResponse{ - .message_index = pressure_buffer_index, - .sensor = can::ids::SensorType::pressure, - .sensor_id = sensor_id, - .sensor_data = 9999}); + can::ids::NodeId::host, + can::messages::ReadFromSensorResponse{ + .message_index = pressure_buffer_index, + .sensor = can::ids::SensorType::pressure, + .sensor_id = sensor_id, + .sensor_data = 9999}); for (int i = 0; i < pressure_buffer_index; i++) { // send over buffer adn then clear buffer values can_client.send_can_message( @@ -300,9 +301,12 @@ class MMR920 { .sensor = can::ids::SensorType::pressure, .sensor_id = sensor_id, .sensor_data = - mmr920C04::reading_to_fixed_point((*p_buff)[i])}); - if (i%10 == 0) { vTaskDelay(50); } // slow it down so the can buffer doesn't choke - (*p_buff)[i] = 0; + mmr920::reading_to_fixed_point((*p_buff).at(i))}); + if (i % 10 == 0) { + // slow it down so the can buffer doesn't choke + vTaskDelay(50); + } + (*p_buff).at(i) = 0; } } @@ -366,17 +370,15 @@ class MMR920 { // send a response with 9999 to make an overload of the buffer // visible if (pressure_buffer_index < PRESSURE_SENSOR_BUFFER_SIZE) { - (*p_buff)[pressure_buffer_index] = pressure; + (*p_buff).at(pressure_buffer_index) = pressure; pressure_buffer_index++; } else { can_client.send_can_message( can::ids::NodeId::host, can::messages::ErrorMessage{ - .message_index = 0, - .severity = can::ids::ErrorSeverity::warning, - .error_code = can::ids::ErrorCode::stop_requested - } - ); + .message_index = 0, + .severity = can::ids::ErrorSeverity::warning, + .error_code = can::ids::ErrorCode::stop_requested}); } } } diff --git a/include/sensors/core/tasks/pressure_sensor_task.hpp b/include/sensors/core/tasks/pressure_sensor_task.hpp index ca6160665..c17a44770 100644 --- a/include/sensors/core/tasks/pressure_sensor_task.hpp +++ b/include/sensors/core/tasks/pressure_sensor_task.hpp @@ -23,9 +23,10 @@ class PressureMessageHandler { CanClient &can_client, OwnQueue &own_queue, sensors::hardware::SensorHardwareBase &hardware, const can::ids::SensorId &id, - const sensors::mmr920::SensorVersion &version, std::array *p_buff) + const sensors::mmr920::SensorVersion &version, + std::array *p_buff) : driver{i2c_writer, i2c_poller, can_client, own_queue, - hardware, id, version, p_buff)} {} + hardware, id, version, p_buff} {} PressureMessageHandler(const PressureMessageHandler &) = delete; PressureMessageHandler(const PressureMessageHandler &&) = delete; auto operator=(const PressureMessageHandler &) @@ -205,7 +206,7 @@ class PressureSensorTask { sensors::mmr920::SensorVersion *sensor_version, std::array *p_buff) { auto handler = PressureMessageHandler{ - *writer, *poller, *can_client, get_queue(), + *writer, *poller, *can_client, get_queue(), *hardware, sensor_id, *sensor_version, p_buff}; handler.initialize(); utils::TaskMessage message{};