mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_Proximity: fix misleading variable name for TerraRangerTower
This commit is contained in:
parent
f91ea8a0dd
commit
e52ca87cbc
@ -92,14 +92,14 @@ bool AP_Proximity_TeraRangerTower::read_sensor_data()
|
||||
}
|
||||
|
||||
// process reply
|
||||
void AP_Proximity_TeraRangerTower::update_sector_data(int16_t angle_deg, uint16_t distance_cm)
|
||||
void AP_Proximity_TeraRangerTower::update_sector_data(int16_t angle_deg, uint16_t distance_mm)
|
||||
{
|
||||
// Get location on 3-D boundary based on angle to the object
|
||||
const AP_Proximity_Boundary_3D::Face face = boundary.get_face(angle_deg);
|
||||
if ((distance_cm != 0xffff) && !ignore_reading(angle_deg, distance_cm * 0.001f, false)) {
|
||||
boundary.set_face_attributes(face, angle_deg, ((float) distance_cm) / 1000);
|
||||
if ((distance_mm != 0xffff) && !ignore_reading(angle_deg, distance_mm * 0.001f, false)) {
|
||||
boundary.set_face_attributes(face, angle_deg, ((float) distance_mm) / 1000);
|
||||
// update OA database
|
||||
database_push(angle_deg, ((float) distance_cm) / 1000);
|
||||
database_push(angle_deg, ((float) distance_mm) / 1000);
|
||||
} else {
|
||||
boundary.reset_face(face);
|
||||
}
|
||||
|
@ -23,7 +23,7 @@ private:
|
||||
|
||||
// check and process replies from sensor
|
||||
bool read_sensor_data();
|
||||
void update_sector_data(int16_t angle_deg, uint16_t distance_cm);
|
||||
void update_sector_data(int16_t angle_deg, uint16_t distance_mm);
|
||||
|
||||
// reply related variables
|
||||
uint8_t buffer[20]; // buffer where to store data from serial
|
||||
|
@ -145,16 +145,16 @@ bool AP_Proximity_TeraRangerTowerEvo::read_sensor_data()
|
||||
}
|
||||
|
||||
// process reply
|
||||
void AP_Proximity_TeraRangerTowerEvo::update_sector_data(int16_t angle_deg, uint16_t distance_cm)
|
||||
void AP_Proximity_TeraRangerTowerEvo::update_sector_data(int16_t angle_deg, uint16_t distance_mm)
|
||||
{
|
||||
// Get location on 3-D boundary based on angle to the object
|
||||
const AP_Proximity_Boundary_3D::Face face = boundary.get_face(angle_deg);
|
||||
//check for target too far, target too close and sensor not connected
|
||||
const bool valid = (distance_cm != 0xffff) && (distance_cm > 0x0001);
|
||||
if (valid && !ignore_reading(angle_deg, distance_cm * 0.001f, false)) {
|
||||
boundary.set_face_attributes(face, angle_deg, ((float) distance_cm) / 1000);
|
||||
const bool valid = (distance_mm != 0xffff) && (distance_mm > 0x0001);
|
||||
if (valid && !ignore_reading(angle_deg, distance_mm * 0.001f, false)) {
|
||||
boundary.set_face_attributes(face, angle_deg, ((float) distance_mm) / 1000);
|
||||
// update OA database
|
||||
database_push(angle_deg, ((float) distance_cm) / 1000);
|
||||
database_push(angle_deg, ((float) distance_mm) / 1000);
|
||||
} else {
|
||||
boundary.reset_face(face);
|
||||
}
|
||||
|
@ -25,7 +25,7 @@ private:
|
||||
// check and process replies from sensor
|
||||
void initialise_modes();
|
||||
bool read_sensor_data();
|
||||
void update_sector_data(int16_t angle_deg, uint16_t distance_cm);
|
||||
void update_sector_data(int16_t angle_deg, uint16_t distance_mm);
|
||||
void set_mode(const uint8_t *c, int length);
|
||||
|
||||
enum InitState {
|
||||
|
Loading…
Reference in New Issue
Block a user