mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
uncrustify libraries/AP_Navigation/examples/Navigation_simple/Navigation_simple.pde
This commit is contained in:
parent
841774f512
commit
b7425b9100
@ -4,23 +4,23 @@
|
||||
|
||||
|
||||
AP_GPS_IMU gps;
|
||||
Navigation nav((GPS *) & gps);
|
||||
Navigation nav((GPS *) & gps);
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(38400);
|
||||
Serial.println("Navigation test");
|
||||
|
||||
Waypoints::WP location_A = {0, 0, 38.579633 * T7, -122.566265 * T7, 10000};
|
||||
Waypoints::WP location_B = {0, 0, 38.578743 * T7, -122.572782 * T7, 5000};
|
||||
|
||||
long distance = nav.get_distance(&location_A, &location_B);
|
||||
long bearing = nav.get_bearing(&location_A, &location_B);
|
||||
Serial.begin(38400);
|
||||
Serial.println("Navigation test");
|
||||
|
||||
Serial.print("\tDistance = ");
|
||||
Serial.print(distance, DEC);
|
||||
Serial.print(" Bearing = ");
|
||||
Serial.println(bearing, DEC);
|
||||
Waypoints::WP location_A = {0, 0, 38.579633 * T7, -122.566265 * T7, 10000};
|
||||
Waypoints::WP location_B = {0, 0, 38.578743 * T7, -122.572782 * T7, 5000};
|
||||
|
||||
long distance = nav.get_distance(&location_A, &location_B);
|
||||
long bearing = nav.get_bearing(&location_A, &location_B);
|
||||
|
||||
Serial.print("\tDistance = ");
|
||||
Serial.print(distance, DEC);
|
||||
Serial.print(" Bearing = ");
|
||||
Serial.println(bearing, DEC);
|
||||
}
|
||||
|
||||
void loop()
|
||||
|
Loading…
Reference in New Issue
Block a user