mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-10 01:44:00 -04:00
AP_RangeFinder: aligned msp message data struct name to gps,baro and mag
This commit is contained in:
parent
efca0c04eb
commit
bc21e505e3
@ -597,7 +597,7 @@ void RangeFinder::handle_msg(const mavlink_message_t &msg)
|
||||
}
|
||||
|
||||
#if HAL_MSP_RANGEFINDER_ENABLED
|
||||
void RangeFinder::handle_msp(const MSP::msp_rangefinder_sensor_t &pkt)
|
||||
void RangeFinder::handle_msp(const MSP::msp_rangefinder_data_message_t &pkt)
|
||||
{
|
||||
uint8_t i;
|
||||
for (i=0; i<num_instances; i++) {
|
||||
|
@ -142,7 +142,7 @@ public:
|
||||
|
||||
#if HAL_MSP_RANGEFINDER_ENABLED
|
||||
// Handle an incoming DISTANCE_SENSOR message (from a MSP enabled range finder)
|
||||
void handle_msp(const MSP::msp_rangefinder_sensor_t &pkt);
|
||||
void handle_msp(const MSP::msp_rangefinder_data_message_t &pkt);
|
||||
#endif
|
||||
// return true if we have a range finder with the specified orientation
|
||||
bool has_orientation(enum Rotation orientation) const;
|
||||
|
@ -33,7 +33,7 @@ public:
|
||||
|
||||
virtual void handle_msg(const mavlink_message_t &msg) { return; }
|
||||
#if HAL_MSP_RANGEFINDER_ENABLED
|
||||
virtual void handle_msp(const MSP::msp_rangefinder_sensor_t &pkt) { return; }
|
||||
virtual void handle_msp(const MSP::msp_rangefinder_data_message_t &pkt) { return; }
|
||||
#endif
|
||||
|
||||
enum Rotation orientation() const { return (Rotation)params.orientation.get(); }
|
||||
|
@ -46,7 +46,7 @@ bool AP_RangeFinder_MSP::detect()
|
||||
/*
|
||||
Set the distance based on a MSP message
|
||||
*/
|
||||
void AP_RangeFinder_MSP::handle_msp(const MSP::msp_rangefinder_sensor_t &pkt)
|
||||
void AP_RangeFinder_MSP::handle_msp(const MSP::msp_rangefinder_data_message_t &pkt)
|
||||
{
|
||||
state.last_reading_ms = AP_HAL::millis();
|
||||
distance_cm = pkt.distance_mm / 10;
|
||||
|
@ -22,7 +22,7 @@ public:
|
||||
void update(void) override;
|
||||
|
||||
// Get update from msp
|
||||
void handle_msp(const MSP::msp_rangefinder_sensor_t &pkt) override;
|
||||
void handle_msp(const MSP::msp_rangefinder_data_message_t &pkt) override;
|
||||
|
||||
protected:
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user