mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Replay: support body frame odometry
This commit is contained in:
parent
851cb30e0d
commit
3d2f07e757
@ -247,6 +247,11 @@ void LR_MsgHandler_RWOH::process_message(uint8_t *msg)
|
||||
AP::dal().handle_message(MSG_CAST(RWOH,msg), ekf2, ekf3);
|
||||
}
|
||||
|
||||
void LR_MsgHandler_RBOH::process_message(uint8_t *msg)
|
||||
{
|
||||
AP::dal().handle_message(MSG_CAST(RBOH,msg), ekf2, ekf3);
|
||||
}
|
||||
|
||||
void LR_MsgHandler_REPH::process_message(uint8_t *msg)
|
||||
{
|
||||
AP::dal().handle_message(MSG_CAST(REPH,msg), ekf2, ekf3);
|
||||
|
@ -106,6 +106,12 @@ class LR_MsgHandler_RWOH : public LR_MsgHandler_EKF
|
||||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
class LR_MsgHandler_RBOH : public LR_MsgHandler_EKF
|
||||
{
|
||||
using LR_MsgHandler_EKF::LR_MsgHandler_EKF;
|
||||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
class LR_MsgHandler_RFRN : public LR_MsgHandler
|
||||
{
|
||||
public:
|
||||
|
@ -228,6 +228,8 @@ bool LogReader::handle_log_format_msg(const struct log_Format &f)
|
||||
msgparser[f.type] = new LR_MsgHandler_REVH(formats[f.type], ekf2, ekf3);
|
||||
} else if (streq(name, "RWOH")) {
|
||||
msgparser[f.type] = new LR_MsgHandler_RWOH(formats[f.type], ekf2, ekf3);
|
||||
} else if (streq(name, "RBOH")) {
|
||||
msgparser[f.type] = new LR_MsgHandler_RBOH(formats[f.type], ekf2, ekf3);
|
||||
} else {
|
||||
// debug(" No parser for (%s)\n", name);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user