Browse Source

AP_OpticalFlow: aligned msp message data struct name to gps,baro and mag

zr-v5.1
yaapu 4 years ago committed by Andrew Tridgell
parent
commit
efca0c04eb
  1. 2
      libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.cpp
  2. 2
      libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.h
  3. 2
      libraries/AP_OpticalFlow/OpticalFlow.cpp
  4. 2
      libraries/AP_OpticalFlow/OpticalFlow.h
  5. 2
      libraries/AP_OpticalFlow/OpticalFlow_backend.h

2
libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.cpp

@ -91,7 +91,7 @@ void AP_OpticalFlow_MSP::update(void) @@ -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

2
libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.h

@ -18,7 +18,7 @@ public: @@ -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);

2
libraries/AP_OpticalFlow/OpticalFlow.cpp

@ -180,7 +180,7 @@ void OpticalFlow::handle_msg(const mavlink_message_t &msg) @@ -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()) {

2
libraries/AP_OpticalFlow/OpticalFlow.h

@ -77,7 +77,7 @@ public: @@ -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

2
libraries/AP_OpticalFlow/OpticalFlow_backend.h

@ -40,7 +40,7 @@ public: @@ -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:

Loading…
Cancel
Save