mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-06 07:53:57 -04:00
AP_Logger: log rally points into dataflash on upload
This commit is contained in:
parent
3bba981a00
commit
9108eeb8f5
@ -667,6 +667,13 @@ void AP_Logger::Write_Mission_Cmd(const AP_Mission &mission,
|
|||||||
FOR_EACH_BACKEND(Write_Mission_Cmd(mission, cmd));
|
FOR_EACH_BACKEND(Write_Mission_Cmd(mission, cmd));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void AP_Logger::Write_RallyPoint(uint8_t total,
|
||||||
|
uint8_t sequence,
|
||||||
|
const RallyLocation &rally_point)
|
||||||
|
{
|
||||||
|
FOR_EACH_BACKEND(Write_RallyPoint(total, sequence, rally_point));
|
||||||
|
}
|
||||||
|
|
||||||
uint32_t AP_Logger::num_dropped() const
|
uint32_t AP_Logger::num_dropped() const
|
||||||
{
|
{
|
||||||
if (_next_backend == 0) {
|
if (_next_backend == 0) {
|
||||||
|
@ -207,7 +207,9 @@ public:
|
|||||||
const AP_Motors &motors,
|
const AP_Motors &motors,
|
||||||
const AC_AttitudeControl &attitude_control,
|
const AC_AttitudeControl &attitude_control,
|
||||||
const AC_PosControl &pos_control);
|
const AC_PosControl &pos_control);
|
||||||
void Write_Rally();
|
void Write_RallyPoint(uint8_t total,
|
||||||
|
uint8_t sequence,
|
||||||
|
const RallyLocation &rally_point);
|
||||||
void Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence);
|
void Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence);
|
||||||
void Write_AOA_SSA(AP_AHRS &ahrs);
|
void Write_AOA_SSA(AP_AHRS &ahrs);
|
||||||
void Write_Beacon(AP_Beacon &beacon);
|
void Write_Beacon(AP_Beacon &beacon);
|
||||||
|
@ -416,3 +416,28 @@ bool AP_Logger_Backend::Write_MessageF(const char *fmt, ...)
|
|||||||
|
|
||||||
return Write_Message(msg);
|
return Write_Message(msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Write rally points
|
||||||
|
bool AP_Logger_Backend::Write_RallyPoint(uint8_t total,
|
||||||
|
uint8_t sequence,
|
||||||
|
const RallyLocation &rally_point)
|
||||||
|
{
|
||||||
|
struct log_Rally pkt_rally = {
|
||||||
|
LOG_PACKET_HEADER_INIT(LOG_RALLY_MSG),
|
||||||
|
time_us : AP_HAL::micros64(),
|
||||||
|
total : total,
|
||||||
|
sequence : sequence,
|
||||||
|
latitude : rally_point.lat,
|
||||||
|
longitude : rally_point.lng,
|
||||||
|
altitude : rally_point.alt
|
||||||
|
};
|
||||||
|
return WriteBlock(&pkt_rally, sizeof(pkt_rally));
|
||||||
|
}
|
||||||
|
|
||||||
|
// Write rally points
|
||||||
|
void AP_Logger_Backend::Write_Rally()
|
||||||
|
{
|
||||||
|
LoggerMessageWriter_WriteAllRallyPoints writer;
|
||||||
|
writer.set_dataflash_backend(this);
|
||||||
|
writer.process();
|
||||||
|
}
|
||||||
|
@ -1608,31 +1608,6 @@ void AP_Logger::Write_Rate(const AP_AHRS_View *ahrs,
|
|||||||
WriteBlock(&pkt_rate, sizeof(pkt_rate));
|
WriteBlock(&pkt_rate, sizeof(pkt_rate));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Write rally points
|
|
||||||
bool AP_Logger_Backend::Log_Write_RallyPoint(uint8_t total,
|
|
||||||
uint8_t sequence,
|
|
||||||
const RallyLocation &rally_point)
|
|
||||||
{
|
|
||||||
struct log_Rally pkt_rally = {
|
|
||||||
LOG_PACKET_HEADER_INIT(LOG_RALLY_MSG),
|
|
||||||
time_us : AP_HAL::micros64(),
|
|
||||||
total : total,
|
|
||||||
sequence : sequence,
|
|
||||||
latitude : rally_point.lat,
|
|
||||||
longitude : rally_point.lng,
|
|
||||||
altitude : rally_point.alt
|
|
||||||
};
|
|
||||||
return WriteBlock(&pkt_rally, sizeof(pkt_rally));
|
|
||||||
}
|
|
||||||
|
|
||||||
// Write rally points
|
|
||||||
void AP_Logger::Log_Write_Rally()
|
|
||||||
{
|
|
||||||
AP_Logger_WriteAllRallyPoints writer;
|
|
||||||
writer.set_dataflash_backend(this);
|
|
||||||
writer.process();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Write visual odometry sensor data
|
// Write visual odometry sensor data
|
||||||
void AP_Logger::Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence)
|
void AP_Logger::Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence)
|
||||||
{
|
{
|
||||||
|
@ -190,7 +190,8 @@ void LoggerMessageWriter_WriteSysInfo::process() {
|
|||||||
_finished = true; // all done!
|
_finished = true; // all done!
|
||||||
}
|
}
|
||||||
|
|
||||||
void LoggerMessageWriter_WriteAllRallyPoints::process() {
|
void LoggerMessageWriter_WriteAllRallyPoints::process()
|
||||||
|
{
|
||||||
const AP_Rally *_rally = AP::rally();
|
const AP_Rally *_rally = AP::rally();
|
||||||
if (_rally == nullptr) {
|
if (_rally == nullptr) {
|
||||||
_finished = true;
|
_finished = true;
|
||||||
@ -208,7 +209,7 @@ void LoggerMessageWriter_WriteAllRallyPoints::process() {
|
|||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
|
|
||||||
case ar_blockwriter_stage_write_new_rally_message:
|
case ar_blockwriter_stage_write_new_rally_message:
|
||||||
if (! _dataflash_backend->Log_Write_Message("New rally")) {
|
if (! _dataflash_backend->Write_Message("New rally")) {
|
||||||
return; // call me again
|
return; // call me again
|
||||||
}
|
}
|
||||||
stage = ar_blockwriter_stage_write_all_rally_points;
|
stage = ar_blockwriter_stage_write_all_rally_points;
|
||||||
@ -218,7 +219,7 @@ void LoggerMessageWriter_WriteAllRallyPoints::process() {
|
|||||||
while (_rally_number_to_send < _rally->get_rally_total()) {
|
while (_rally_number_to_send < _rally->get_rally_total()) {
|
||||||
RallyLocation rallypoint;
|
RallyLocation rallypoint;
|
||||||
if (_rally->get_rally_point_with_index(_rally_number_to_send, rallypoint)) {
|
if (_rally->get_rally_point_with_index(_rally_number_to_send, rallypoint)) {
|
||||||
if (!_dataflash_backend->Log_Write_RallyPoint(
|
if (!_dataflash_backend->Write_RallyPoint(
|
||||||
_rally->get_rally_total(),
|
_rally->get_rally_total(),
|
||||||
_rally_number_to_send,
|
_rally_number_to_send,
|
||||||
rallypoint)) {
|
rallypoint)) {
|
||||||
@ -237,9 +238,9 @@ void LoggerMessageWriter_WriteAllRallyPoints::process() {
|
|||||||
_finished = true;
|
_finished = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void DFMessageWriter_WriteAllRallyPoints::reset()
|
void LoggerMessageWriter_WriteAllRallyPoints::reset()
|
||||||
{
|
{
|
||||||
DFMessageWriter::reset();
|
LoggerMessageWriter::reset();
|
||||||
stage = ar_blockwriter_stage_init;
|
stage = ar_blockwriter_stage_init;
|
||||||
_rally_number_to_send = 0;
|
_rally_number_to_send = 0;
|
||||||
}
|
}
|
||||||
|
@ -78,7 +78,8 @@ class LoggerMessageWriter_DFLogStart : public LoggerMessageWriter {
|
|||||||
public:
|
public:
|
||||||
LoggerMessageWriter_DFLogStart() :
|
LoggerMessageWriter_DFLogStart() :
|
||||||
_writesysinfo(),
|
_writesysinfo(),
|
||||||
_writeentiremission()
|
_writeentiremission(),
|
||||||
|
_writeallrallypoints()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user