mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
APMrover v2.0b - Special update for rover heading calculation if compass is enabled
Signed-off-by: Jean-Louis Naudin <jlnaudin@gmail.com>
This commit is contained in:
parent
53cbbfaaa4
commit
602fe6e55a
@ -14,6 +14,9 @@
|
||||
#define MAGNETOMETER ENABLED
|
||||
#define LOGGING_ENABLED ENABLED
|
||||
|
||||
#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_UP_PINS_FORWARD
|
||||
#define PARAM_DECLINATION 0.18 // Paris
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Serial port speeds.
|
||||
//
|
||||
|
@ -1,6 +1,6 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#define THISFIRMWARE "APMrover v2.0a JL NAUDIN" //New version of the APMrover for the APM v1 or APM v2 and magnetometer
|
||||
#define THISFIRMWARE "APMrover v2.0b JL NAUDIN" //New version of the APMrover for the APM v1 or APM v2 and magnetometer
|
||||
|
||||
// This is a full version of Arduplane v2.32 specially adapted for a Rover by Jean-Louis Naudin (JLN)
|
||||
|
||||
@ -24,6 +24,7 @@ version 2.1 of the License, or (at your option) any later version.
|
||||
//-------------------------------------------------------------------------------------------------------------------------
|
||||
// Dev Startup : 2012-04-21
|
||||
//
|
||||
// 2012-05-01: special update for rover about ground_course if compass is enabled
|
||||
// 2012-04-30: Successfully tested in autonomous nav with a waypoints list recorded in live mode
|
||||
// 2012-04-30: Now a full version for APM v1 or APM v2 with magnetometer
|
||||
// 2012-04-27: Cosmetic changes
|
||||
@ -1046,8 +1047,13 @@ static void update_GPS(void)
|
||||
current_loc.lng = g_gps->longitude; // Lon * 10**7
|
||||
current_loc.lat = g_gps->latitude; // Lat * 10**7
|
||||
current_loc.alt = max((g_gps->altitude - home.alt),0);
|
||||
ground_course = g_gps->ground_course;
|
||||
ground_speed = g_gps->ground_speed;
|
||||
if (g.compass_enabled) {
|
||||
ground_course = (wrap_360(ToDeg(compass.heading) * 100));
|
||||
} else {
|
||||
ground_course = g_gps->ground_course;
|
||||
}
|
||||
|
||||
|
||||
// see if we've breached the geo-fence
|
||||
geofence_check(false);
|
||||
|
@ -317,7 +317,9 @@ static void NOINLINE send_location(mavlink_channel_t chan)
|
||||
g_gps->ground_speed * rot.a.x, // X speed cm/s
|
||||
g_gps->ground_speed * rot.b.x, // Y speed cm/s
|
||||
g_gps->ground_speed * rot.c.x,
|
||||
g_gps->ground_course); // course in 1/100 degree
|
||||
//g_gps->ground_course); // course in 1/100 degree
|
||||
ground_course); // course in 1/100 degree
|
||||
|
||||
}
|
||||
|
||||
static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
||||
@ -355,7 +357,8 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
|
||||
g_gps->hdop,
|
||||
65535,
|
||||
g_gps->ground_speed, // cm/s
|
||||
g_gps->ground_course, // 1/100 degrees,
|
||||
//g_gps->ground_course, // 1/100 degrees,
|
||||
ground_course, // 1/100 degrees,
|
||||
g_gps->num_sats);
|
||||
|
||||
#else // MAVLINK10
|
||||
@ -369,7 +372,9 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
|
||||
g_gps->hdop,
|
||||
0.0,
|
||||
g_gps->ground_speed / 100.0,
|
||||
g_gps->ground_course / 100.0);
|
||||
//ground_course = (wrap_360(ToDeg(compass.heading) * 100));
|
||||
//g_gps->ground_course / 100.0);
|
||||
ground_course / 100.0);
|
||||
#endif // MAVLINK10
|
||||
}
|
||||
|
||||
|
@ -356,8 +356,8 @@ static void Log_Write_GPS( int32_t log_Time, int32_t log_Lattitude, int32_t log_
|
||||
DataFlash.WriteLong(log_gps_alt);
|
||||
DataFlash.WriteLong(log_Ground_Speed);
|
||||
DataFlash.WriteLong(log_Ground_Course);
|
||||
DataFlash.WriteInt((int16_t)Vz);
|
||||
DataFlash.WriteInt((int16_t)delta_Vz);
|
||||
DataFlash.WriteInt(0);
|
||||
DataFlash.WriteInt(0);
|
||||
DataFlash.WriteInt((int)airspeed);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user