diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.cpp index c3b3bba1a8..67f85c2a1e 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.cpp @@ -91,7 +91,7 @@ void AP_OpticalFlow_MSP::update(void) } // 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 // ToDo: add jitter correction diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.h index b6ad6bd424..0bf7276179 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.h @@ -18,7 +18,7 @@ public: void update(void) override; // 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 static AP_OpticalFlow_MSP *detect(OpticalFlow &_frontend); diff --git a/libraries/AP_OpticalFlow/OpticalFlow.cpp b/libraries/AP_OpticalFlow/OpticalFlow.cpp index 497c4a9fb5..3a2c5b0167 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/OpticalFlow.cpp @@ -180,7 +180,7 @@ void OpticalFlow::handle_msg(const mavlink_message_t &msg) } #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 if (!enabled()) { diff --git a/libraries/AP_OpticalFlow/OpticalFlow.h b/libraries/AP_OpticalFlow/OpticalFlow.h index 91d3aecd89..d67d0cc475 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.h +++ b/libraries/AP_OpticalFlow/OpticalFlow.h @@ -77,7 +77,7 @@ public: #if HAL_MSP_OPTICALFLOW_ENABLED // 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 // quality - returns the surface quality as a measure from 0 ~ 255 diff --git a/libraries/AP_OpticalFlow/OpticalFlow_backend.h b/libraries/AP_OpticalFlow/OpticalFlow_backend.h index 9c76bd8005..782aa2d470 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow_backend.h +++ b/libraries/AP_OpticalFlow/OpticalFlow_backend.h @@ -40,7 +40,7 @@ public: #if HAL_MSP_OPTICALFLOW_ENABLED // 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 protected: