mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Rover: global-pos-int uses vel from EKF instead of GPS
This commit is contained in:
parent
dd6755f486
commit
24b8ed48b6
@ -102,21 +102,12 @@ void Rover::send_extended_status1(mavlink_channel_t chan)
|
|||||||
|
|
||||||
void Rover::send_location(mavlink_channel_t chan)
|
void Rover::send_location(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
uint32_t fix_time;
|
const uint32_t now = AP_HAL::millis();
|
||||||
// if we have a GPS fix, take the time as the last fix time. That
|
Vector3f vel;
|
||||||
// allows us to correctly calculate velocities and extrapolate
|
ahrs.get_velocity_NED(vel);
|
||||||
// positions.
|
|
||||||
// If we don't have a GPS fix then we are dead reckoning, and will
|
|
||||||
// use the current boot time as the fix time.
|
|
||||||
if (gps.status() >= AP_GPS::GPS_OK_FIX_2D) {
|
|
||||||
fix_time = gps.last_fix_time_ms();
|
|
||||||
} else {
|
|
||||||
fix_time = millis();
|
|
||||||
}
|
|
||||||
const Vector3f &vel = gps.velocity();
|
|
||||||
mavlink_msg_global_position_int_send(
|
mavlink_msg_global_position_int_send(
|
||||||
chan,
|
chan,
|
||||||
fix_time,
|
now,
|
||||||
current_loc.lat, // in 1E7 degrees
|
current_loc.lat, // in 1E7 degrees
|
||||||
current_loc.lng, // in 1E7 degrees
|
current_loc.lng, // in 1E7 degrees
|
||||||
current_loc.alt * 10UL, // millimeters above sea level
|
current_loc.alt * 10UL, // millimeters above sea level
|
||||||
|
Loading…
Reference in New Issue
Block a user