mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 08:23:56 -04:00
Tracker: Added vehicle position log
This commit is contained in:
parent
d151b4481a
commit
f3461d182f
@ -42,18 +42,44 @@ void Tracker::Log_Write_Vehicle_Baro(float pressure, float altitude)
|
|||||||
time_us : AP_HAL::micros64(),
|
time_us : AP_HAL::micros64(),
|
||||||
press : pressure,
|
press : pressure,
|
||||||
alt_diff : altitude
|
alt_diff : altitude
|
||||||
|
|
||||||
};
|
};
|
||||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
struct PACKED log_Vehicle_Pos {
|
||||||
|
LOG_PACKET_HEADER;
|
||||||
|
uint64_t time_us;
|
||||||
|
int32_t vehicle_lat;
|
||||||
|
int32_t vehicle_lng;
|
||||||
|
int32_t vehicle_alt;
|
||||||
|
float vehicle_heading;
|
||||||
|
float vehicle_speed;
|
||||||
|
};
|
||||||
|
|
||||||
|
// Write a vehicle pos packet
|
||||||
|
void Tracker::Log_Write_Vehicle_Pos(int32_t lat,int32_t lng,int32_t alt,float heading,float ground_speed){
|
||||||
|
|
||||||
|
struct log_Vehicle_Pos pkt = {
|
||||||
|
LOG_PACKET_HEADER_INIT(LOG_V_POS_MSG),
|
||||||
|
time_us : AP_HAL::micros64(),
|
||||||
|
vehicle_lat : lat,
|
||||||
|
vehicle_lng : lng,
|
||||||
|
vehicle_alt : alt,
|
||||||
|
vehicle_heading : heading,
|
||||||
|
vehicle_speed : ground_speed,
|
||||||
|
};
|
||||||
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||||
|
}
|
||||||
|
|
||||||
const struct LogStructure Tracker::log_structure[] = {
|
const struct LogStructure Tracker::log_structure[] = {
|
||||||
LOG_COMMON_STRUCTURES,
|
LOG_COMMON_STRUCTURES,
|
||||||
{LOG_V_BAR_MSG, sizeof(log_Vehicle_Baro),
|
{LOG_V_BAR_MSG, sizeof(log_Vehicle_Baro),
|
||||||
"VBAR", "Qff", "TimeUS,Press,AltDiff" },
|
"VBAR", "Qff", "TimeUS,Press,AltDiff" },
|
||||||
|
{LOG_V_POS_MSG, sizeof(log_Vehicle_Pos),
|
||||||
|
"VPOS", "QLLeff", "TimeUS,Lat,Lng,Alt,Heading,Speed" }
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
void Tracker::Log_Write_Vehicle_Startup_Messages()
|
void Tracker::Log_Write_Vehicle_Startup_Messages()
|
||||||
{
|
{
|
||||||
DataFlash.Log_Write_Mode(control_mode);
|
DataFlash.Log_Write_Mode(control_mode);
|
||||||
|
@ -255,6 +255,7 @@ private:
|
|||||||
void compass_cal_update();
|
void compass_cal_update();
|
||||||
void Log_Write_Attitude();
|
void Log_Write_Attitude();
|
||||||
void Log_Write_Baro(void);
|
void Log_Write_Baro(void);
|
||||||
|
void Log_Write_Vehicle_Pos(int32_t lat,int32_t lng,int32_t alt,float heading,float ground_speed);
|
||||||
void Log_Write_Vehicle_Baro(float pressure, float altitude);
|
void Log_Write_Vehicle_Baro(float pressure, float altitude);
|
||||||
void Log_Write_Vehicle_Startup_Messages();
|
void Log_Write_Vehicle_Startup_Messages();
|
||||||
void start_logging();
|
void start_logging();
|
||||||
|
@ -35,3 +35,4 @@ enum ServoType {
|
|||||||
|
|
||||||
// Logging messages
|
// Logging messages
|
||||||
#define LOG_V_BAR_MSG 0x04
|
#define LOG_V_BAR_MSG 0x04
|
||||||
|
#define LOG_V_POS_MSG 0x05
|
||||||
|
@ -131,7 +131,7 @@ void Tracker::tracking_update_position(const mavlink_global_position_int_t &msg)
|
|||||||
|
|
||||||
// log vehicle as GPS2
|
// log vehicle as GPS2
|
||||||
if (should_log(MASK_LOG_GPS)) {
|
if (should_log(MASK_LOG_GPS)) {
|
||||||
DataFlash.Log_Write_GPS(gps, 1);
|
Log_Write_Vehicle_Pos(vehicle.location.lat, vehicle.location.lng, vehicle.location.alt, vehicle.heading, vehicle.ground_speed);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user