Browse Source

AP_Beacon: replace location_offset() and get_distance() function calls with Location object member function calls

This allows removing duplicated code
master
Dr.-Ing. Amilcar do Carmo Lucas 6 years ago committed by Peter Barker
parent
commit
c977a646db
  1. 8
      libraries/AP_Beacon/AP_Beacon_SITL.cpp

8
libraries/AP_Beacon/AP_Beacon_SITL.cpp

@ -81,19 +81,19 @@ void AP_Beacon_SITL::update(void) @@ -81,19 +81,19 @@ void AP_Beacon_SITL::update(void)
switch (beacon_id) {
case 0:
// NE corner
location_offset(beacon_loc, ORIGIN_OFFSET_NORTH + BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST + BEACON_SPACING_EAST/2);
beacon_loc.offset(ORIGIN_OFFSET_NORTH + BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST + BEACON_SPACING_EAST/2);
break;
case 1:
// SE corner
location_offset(beacon_loc, ORIGIN_OFFSET_NORTH - BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST + BEACON_SPACING_EAST/2);
beacon_loc.offset(ORIGIN_OFFSET_NORTH - BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST + BEACON_SPACING_EAST/2);
break;
case 2:
// SW corner
location_offset(beacon_loc, ORIGIN_OFFSET_NORTH - BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST - BEACON_SPACING_EAST/2);
beacon_loc.offset(ORIGIN_OFFSET_NORTH - BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST - BEACON_SPACING_EAST/2);
break;
case 3:
// NW corner
location_offset(beacon_loc, ORIGIN_OFFSET_NORTH + BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST - BEACON_SPACING_EAST/2);
beacon_loc.offset(ORIGIN_OFFSET_NORTH + BEACON_SPACING_NORTH/2, ORIGIN_OFFSET_EAST - BEACON_SPACING_EAST/2);
break;
}

Loading…
Cancel
Save