mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_OpticalFlow: aligned msp message data struct name to gps,baro and mag
This commit is contained in:
parent
747bf73fec
commit
efca0c04eb
@ -91,7 +91,7 @@ void AP_OpticalFlow_MSP::update(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// handle OPTICAL_FLOW msp messages
|
// handle OPTICAL_FLOW msp messages
|
||||||
void AP_OpticalFlow_MSP::handle_msp(const MSP::msp_opflow_sensor_t &pkt)
|
void AP_OpticalFlow_MSP::handle_msp(const MSP::msp_opflow_data_message_t &pkt)
|
||||||
{
|
{
|
||||||
// record time message was received
|
// record time message was received
|
||||||
// ToDo: add jitter correction
|
// ToDo: add jitter correction
|
||||||
|
@ -18,7 +18,7 @@ public:
|
|||||||
void update(void) override;
|
void update(void) override;
|
||||||
|
|
||||||
// get update from msp
|
// get update from msp
|
||||||
void handle_msp(const MSP::msp_opflow_sensor_t &pkt) override;
|
void handle_msp(const MSP::msp_opflow_data_message_t &pkt) override;
|
||||||
|
|
||||||
// detect if the sensor is available
|
// detect if the sensor is available
|
||||||
static AP_OpticalFlow_MSP *detect(OpticalFlow &_frontend);
|
static AP_OpticalFlow_MSP *detect(OpticalFlow &_frontend);
|
||||||
|
@ -180,7 +180,7 @@ void OpticalFlow::handle_msg(const mavlink_message_t &msg)
|
|||||||
}
|
}
|
||||||
|
|
||||||
#if HAL_MSP_OPTICALFLOW_ENABLED
|
#if HAL_MSP_OPTICALFLOW_ENABLED
|
||||||
void OpticalFlow::handle_msp(const MSP::msp_opflow_sensor_t &pkt)
|
void OpticalFlow::handle_msp(const MSP::msp_opflow_data_message_t &pkt)
|
||||||
{
|
{
|
||||||
// exit immediately if not enabled
|
// exit immediately if not enabled
|
||||||
if (!enabled()) {
|
if (!enabled()) {
|
||||||
|
@ -77,7 +77,7 @@ public:
|
|||||||
|
|
||||||
#if HAL_MSP_OPTICALFLOW_ENABLED
|
#if HAL_MSP_OPTICALFLOW_ENABLED
|
||||||
// handle optical flow msp messages
|
// handle optical flow msp messages
|
||||||
void handle_msp(const MSP::msp_opflow_sensor_t &pkt);
|
void handle_msp(const MSP::msp_opflow_data_message_t &pkt);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// quality - returns the surface quality as a measure from 0 ~ 255
|
// quality - returns the surface quality as a measure from 0 ~ 255
|
||||||
|
@ -40,7 +40,7 @@ public:
|
|||||||
|
|
||||||
#if HAL_MSP_OPTICALFLOW_ENABLED
|
#if HAL_MSP_OPTICALFLOW_ENABLED
|
||||||
// handle optical flow msp messages
|
// handle optical flow msp messages
|
||||||
virtual void handle_msp(const MSP::msp_opflow_sensor_t &pkt) {}
|
virtual void handle_msp(const MSP::msp_opflow_data_message_t &pkt) {}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
Loading…
Reference in New Issue
Block a user