mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Proximity: Change from method reference to macro
This commit is contained in:
parent
7340502f18
commit
fb544cab78
@ -98,23 +98,14 @@ bool AP_Proximity_TeraRangerTower::read_sensor_data()
|
||||
|
||||
// check if message has right CRC
|
||||
if (crc_crc8(buffer, 18) == buffer[18]){
|
||||
uint16_t d1 = process_distance(buffer[2], buffer[3]);
|
||||
uint16_t d2 = process_distance(buffer[4], buffer[5]);
|
||||
uint16_t d3 = process_distance(buffer[6], buffer[7]);
|
||||
uint16_t d4 = process_distance(buffer[8], buffer[9]);
|
||||
uint16_t d5 = process_distance(buffer[10], buffer[11]);
|
||||
uint16_t d6 = process_distance(buffer[12], buffer[13]);
|
||||
uint16_t d7 = process_distance(buffer[14], buffer[15]);
|
||||
uint16_t d8 = process_distance(buffer[16], buffer[17]);
|
||||
|
||||
update_sector_data(0, d1);
|
||||
update_sector_data(45, d8);
|
||||
update_sector_data(90, d7);
|
||||
update_sector_data(135, d6);
|
||||
update_sector_data(180, d5);
|
||||
update_sector_data(225, d4);
|
||||
update_sector_data(270, d3);
|
||||
update_sector_data(315, d2);
|
||||
update_sector_data(0, UINT16_VALUE(buffer[2], buffer[3])); // d1
|
||||
update_sector_data(45, UINT16_VALUE(buffer[16], buffer[17])); // d8
|
||||
update_sector_data(90, UINT16_VALUE(buffer[14], buffer[15])); // d7
|
||||
update_sector_data(135, UINT16_VALUE(buffer[12], buffer[13])); // d6
|
||||
update_sector_data(180, UINT16_VALUE(buffer[10], buffer[11])); // d5
|
||||
update_sector_data(225, UINT16_VALUE(buffer[8], buffer[9])); // d4
|
||||
update_sector_data(270, UINT16_VALUE(buffer[6], buffer[7])); // d3
|
||||
update_sector_data(315, UINT16_VALUE(buffer[4], buffer[5])); // d2
|
||||
|
||||
message_count++;
|
||||
}
|
||||
@ -123,11 +114,6 @@ bool AP_Proximity_TeraRangerTower::read_sensor_data()
|
||||
return (message_count > 0);
|
||||
}
|
||||
|
||||
uint16_t AP_Proximity_TeraRangerTower::process_distance(uint8_t buf1, uint8_t buf2)
|
||||
{
|
||||
return (buf1 << 8) + buf2;
|
||||
}
|
||||
|
||||
// process reply
|
||||
void AP_Proximity_TeraRangerTower::update_sector_data(int16_t angle_deg, uint16_t distance_cm)
|
||||
{
|
||||
|
@ -27,7 +27,6 @@ private:
|
||||
// check and process replies from sensor
|
||||
bool read_sensor_data();
|
||||
void update_sector_data(int16_t angle_deg, uint16_t distance_cm);
|
||||
uint16_t process_distance(uint8_t buf1, uint8_t buf2);
|
||||
|
||||
// reply related variables
|
||||
AP_HAL::UARTDriver *uart = nullptr;
|
||||
|
@ -150,24 +150,14 @@ bool AP_Proximity_TeraRangerTowerEvo::read_sensor_data()
|
||||
|
||||
//check if message has right CRC
|
||||
if (crc_crc8(buffer, 19) == buffer[19]){
|
||||
|
||||
uint16_t d1 = process_distance(buffer[2], buffer[3]);
|
||||
uint16_t d2 = process_distance(buffer[4], buffer[5]);
|
||||
uint16_t d3 = process_distance(buffer[6], buffer[7]);
|
||||
uint16_t d4 = process_distance(buffer[8], buffer[9]);
|
||||
uint16_t d5 = process_distance(buffer[10], buffer[11]);
|
||||
uint16_t d6 = process_distance(buffer[12], buffer[13]);
|
||||
uint16_t d7 = process_distance(buffer[14], buffer[15]);
|
||||
uint16_t d8 = process_distance(buffer[16], buffer[17]);
|
||||
|
||||
update_sector_data(0, d1);
|
||||
update_sector_data(45, d2);
|
||||
update_sector_data(90, d3);
|
||||
update_sector_data(135, d4);
|
||||
update_sector_data(180, d5);
|
||||
update_sector_data(225, d6);
|
||||
update_sector_data(270, d7);
|
||||
update_sector_data(315, d8);
|
||||
update_sector_data(0, UINT16_VALUE(buffer[2], buffer[3])); // d1
|
||||
update_sector_data(45, UINT16_VALUE(buffer[4], buffer[5])); // d2
|
||||
update_sector_data(90, UINT16_VALUE(buffer[6], buffer[7])); // d3
|
||||
update_sector_data(135, UINT16_VALUE(buffer[8], buffer[9])); // d4
|
||||
update_sector_data(180, UINT16_VALUE(buffer[10], buffer[11])); // d5
|
||||
update_sector_data(225, UINT16_VALUE(buffer[12], buffer[13])); // d6
|
||||
update_sector_data(270, UINT16_VALUE(buffer[14], buffer[15])); // d7
|
||||
update_sector_data(315, UINT16_VALUE(buffer[16], buffer[17])); // d8
|
||||
|
||||
message_count++;
|
||||
}
|
||||
@ -176,11 +166,6 @@ bool AP_Proximity_TeraRangerTowerEvo::read_sensor_data()
|
||||
return (message_count > 0);
|
||||
}
|
||||
|
||||
uint16_t AP_Proximity_TeraRangerTowerEvo::process_distance(uint8_t buf1, uint8_t buf2)
|
||||
{
|
||||
return (buf1 << 8) + buf2;
|
||||
}
|
||||
|
||||
// process reply
|
||||
void AP_Proximity_TeraRangerTowerEvo::update_sector_data(int16_t angle_deg, uint16_t distance_cm)
|
||||
{
|
||||
|
@ -27,7 +27,6 @@ private:
|
||||
void initialise_modes();
|
||||
bool read_sensor_data();
|
||||
void update_sector_data(int16_t angle_deg, uint16_t distance_cm);
|
||||
uint16_t process_distance(uint8_t buf1, uint8_t buf2);
|
||||
void set_mode(const uint8_t *c, int length);
|
||||
|
||||
enum InitState {
|
||||
|
Loading…
Reference in New Issue
Block a user