AP_RangeFinder: small NFC fixes

This commit is contained in:
rishabsingh3003 2023-07-19 13:30:46 +05:30 committed by Andrew Tridgell
parent 3f65d713c8
commit a8a8c96610
9 changed files with 24 additions and 23 deletions

View File

@ -86,7 +86,7 @@ bool AP_RangeFinder_Backend_CAN::is_correct_id(uint32_t id) const
void RangeFinder_MultiCAN::handle_frame(AP_HAL::CANFrame &frame)
{
WITH_SEMAPHORE(sem);
for (auto *d = drivers; d; d=d->next) {
for (auto *d = drivers; d != nullptr; d=d->next) {
if (d->handle_frame(frame)) {
break;
}

View File

@ -42,7 +42,7 @@ protected:
bool is_correct_id(uint32_t can_id) const;
// set distance and count
void set_distance_m(float distance_m) {
void accumulate_distance_m(float distance_m) {
_distance_sum += distance_m;
_distance_count++;
};

View File

@ -44,7 +44,7 @@ bool AP_RangeFinder_Benewake_CAN::handle_frame_H30(AP_HAL::CANFrame &frame)
//uint16_t target2 = be16toh_ptr(&frame.data[2]);
//uint16_t target3 = be16toh_ptr(&frame.data[4]);
set_distance_m(target1_cm * 0.01);
accumulate_distance_m(target1_cm * 0.01);
return true;
}
@ -74,7 +74,7 @@ bool AP_RangeFinder_Benewake_CAN::handle_frame(AP_HAL::CANFrame &frame)
return true;
}
set_distance_m(dist_cm * 0.01);
accumulate_distance_m(dist_cm * 0.01);
return true;
}

View File

@ -1,8 +1,8 @@
#include "AP_RangeFinder_NRA24_CAN.h"
#include <AP_BoardConfig/AP_BoardConfig.h>
#if AP_RANGEFINDER_NRA24_CAN_ENABLED
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_HAL/AP_HAL.h>
RangeFinder_MultiCAN *AP_RangeFinder_NRA24_CAN::multican_NRA24;
@ -73,7 +73,7 @@ bool AP_RangeFinder_NRA24_CAN::handle_frame(AP_HAL::CANFrame &frame)
// too low signal strength
return false;
}
set_distance_m(dist_m);
accumulate_distance_m(dist_m);
}
break;

View File

@ -1,12 +1,8 @@
#pragma once
#include "AP_RangeFinder_Backend_CAN.h"
#ifndef AP_RANGEFINDER_NRA24_CAN_ENABLED
#define AP_RANGEFINDER_NRA24_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
#endif
#include "AP_RangeFinder_config.h"
#if AP_RANGEFINDER_NRA24_CAN_ENABLED
#include "AP_RangeFinder_Backend_CAN.h"
class AP_RangeFinder_NRA24_CAN : public AP_RangeFinder_Backend_CAN {
public:

View File

@ -1,10 +1,10 @@
#include "AP_RangeFinder_TOFSenseP_CAN.h"
#include <GCS_MAVLink/GCS.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_HAL/utility/sparse-endian.h>
#if AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED
#include <GCS_MAVLink/GCS.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_HAL/utility/sparse-endian.h>
#include <AP_HAL/AP_HAL.h>
RangeFinder_MultiCAN *AP_RangeFinder_TOFSenseP_CAN::multican_TOFSenseP;
@ -51,7 +51,7 @@ bool AP_RangeFinder_TOFSenseP_CAN::handle_frame(AP_HAL::CANFrame &frame)
return false;
}
set_distance_m(dist_cm * 0.01);
accumulate_distance_m(dist_cm * 0.01);
return true;
}

View File

@ -1,13 +1,10 @@
#pragma once
#include "AP_RangeFinder_Backend_CAN.h"
#ifndef AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED
#define AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
#endif
#include "AP_RangeFinder_config.h"
#if AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED
#include "AP_RangeFinder_Backend_CAN.h"
class AP_RangeFinder_TOFSenseP_CAN : public AP_RangeFinder_Backend_CAN {
public:
AP_RangeFinder_TOFSenseP_CAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);

View File

@ -39,7 +39,7 @@ bool AP_RangeFinder_USD1_CAN::handle_frame(AP_HAL::CANFrame &frame)
}
const uint16_t dist_cm = (frame.data[0]<<8) | frame.data[1];
set_distance_m(dist_cm * 0.01);
accumulate_distance_m(dist_cm * 0.01);
return true;
}

View File

@ -156,3 +156,11 @@
#ifndef AP_RANGEFINDER_WASP_ENABLED
#define AP_RANGEFINDER_WASP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
#endif
#ifndef AP_RANGEFINDER_NRA24_CAN_ENABLED
#define AP_RANGEFINDER_NRA24_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
#endif
#ifndef AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED
#define AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
#endif