mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_GPS: added velocity_vector() method
This commit is contained in:
parent
468e55d425
commit
01c124d5f5
@ -10,6 +10,7 @@
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Math.h>
|
||||
|
||||
/// @class GPS
|
||||
/// @brief Abstract base class for GPS receiver drivers.
|
||||
@ -126,16 +127,21 @@ public:
|
||||
float ground_speed, float ground_course, float speed_3d, uint8_t num_sats);
|
||||
|
||||
// components of velocity in 2D, in m/s
|
||||
float velocity_north(void) {
|
||||
float velocity_north(void) const {
|
||||
return _status >= GPS_OK_FIX_2D ? _velocity_north : 0;
|
||||
}
|
||||
float velocity_east(void) {
|
||||
float velocity_east(void) const {
|
||||
return _status >= GPS_OK_FIX_2D ? _velocity_east : 0;
|
||||
}
|
||||
float velocity_down(void) {
|
||||
float velocity_down(void) const {
|
||||
return _status >= GPS_OK_FIX_3D ? _velocity_down : 0;
|
||||
}
|
||||
|
||||
// GPS velocity vector as NED in m/s
|
||||
Vector3f velocity_vector(void) const {
|
||||
return Vector3f(_velocity_north, _velocity_east, _velocity_down);
|
||||
}
|
||||
|
||||
// last ground speed in m/s. This can be used when we have no GPS
|
||||
// lock to return the last ground speed we had with lock
|
||||
float last_ground_speed(void) {
|
||||
|
Loading…
Reference in New Issue
Block a user