mirror of https://github.com/ArduPilot/ardupilot
Tools/Replay: Add handlers for external lat lng position set
This commit is contained in:
parent
3677cb025d
commit
e3d05094a0
|
@ -289,6 +289,12 @@ void LR_MsgHandler_REPH::process_message(uint8_t *msgbytes)
|
|||
AP::dal().handle_message(msg, ekf2, ekf3);
|
||||
}
|
||||
|
||||
void LR_MsgHandler_RSLL::process_message(uint8_t *msgbytes)
|
||||
{
|
||||
MSG_CREATE(RSLL, msgbytes);
|
||||
AP::dal().handle_message(msg, ekf2, ekf3);
|
||||
}
|
||||
|
||||
void LR_MsgHandler_REVH::process_message(uint8_t *msgbytes)
|
||||
{
|
||||
MSG_CREATE(REVH, msgbytes);
|
||||
|
|
|
@ -57,6 +57,12 @@ class LR_MsgHandler_REPH : public LR_MsgHandler_EKF
|
|||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
class LR_MsgHandler_RSLL : public LR_MsgHandler_EKF
|
||||
{
|
||||
using LR_MsgHandler_EKF::LR_MsgHandler_EKF;
|
||||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
class LR_MsgHandler_REVH : public LR_MsgHandler_EKF
|
||||
{
|
||||
using LR_MsgHandler_EKF::LR_MsgHandler_EKF;
|
||||
|
|
|
@ -118,6 +118,8 @@ bool LogReader::handle_log_format_msg(const struct log_Format &f)
|
|||
msgparser[f.type] = new LR_MsgHandler_ROFH(formats[f.type], ekf2, ekf3);
|
||||
} else if (streq(name, "REPH")) {
|
||||
msgparser[f.type] = new LR_MsgHandler_REPH(formats[f.type], ekf2, ekf3);
|
||||
} else if (streq(name, "RSLL")) {
|
||||
msgparser[f.type] = new LR_MsgHandler_RSLL(formats[f.type], ekf2, ekf3);
|
||||
} else if (streq(name, "REVH")) {
|
||||
msgparser[f.type] = new LR_MsgHandler_REVH(formats[f.type], ekf2, ekf3);
|
||||
} else if (streq(name, "RWOH")) {
|
||||
|
|
Loading…
Reference in New Issue