From c78b1ab3bfe4503e44d1d61ea3b9c4163a4c9af8 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 31 Mar 2020 14:41:54 +0900 Subject: [PATCH] AP_VisualOdom: rename handle_vision_position_delta_msg --- libraries/AP_VisualOdom/AP_VisualOdom.cpp | 6 +++--- libraries/AP_VisualOdom/AP_VisualOdom.h | 4 ++-- libraries/AP_VisualOdom/AP_VisualOdom_Backend.h | 4 ++-- libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp | 4 ++-- libraries/AP_VisualOdom/AP_VisualOdom_MAV.h | 4 ++-- 5 files changed, 11 insertions(+), 11 deletions(-) diff --git a/libraries/AP_VisualOdom/AP_VisualOdom.cpp b/libraries/AP_VisualOdom/AP_VisualOdom.cpp index 7d41ec330d..7780dc242d 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom.cpp @@ -106,8 +106,8 @@ bool AP_VisualOdom::healthy() const return _driver->healthy(); } -// consume VISION_POSITION_DELTA MAVLink message -void AP_VisualOdom::handle_msg(const mavlink_message_t &msg) +// consume vision_position_delta mavlink messages +void AP_VisualOdom::handle_vision_position_delta_msg(const mavlink_message_t &msg) { // exit immediately if not enabled if (!enabled()) { @@ -116,7 +116,7 @@ void AP_VisualOdom::handle_msg(const mavlink_message_t &msg) // call backend if (_driver != nullptr) { - _driver->handle_msg(msg); + _driver->handle_vision_position_delta_msg(msg); } } diff --git a/libraries/AP_VisualOdom/AP_VisualOdom.h b/libraries/AP_VisualOdom/AP_VisualOdom.h index bad93de03e..83e30c68d4 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom.h +++ b/libraries/AP_VisualOdom/AP_VisualOdom.h @@ -55,8 +55,8 @@ public: // return a 3D vector defining the position offset of the camera in meters relative to the body frame origin const Vector3f &get_pos_offset(void) const { return _pos_offset; } - // consume data from MAVLink messages - void handle_msg(const mavlink_message_t &msg); + // consume vision_position_delta mavlink messages + void handle_vision_position_delta_msg(const mavlink_message_t &msg); // general purpose methods to consume position estimate data and send to EKF // distances in meters, roll, pitch and yaw are in radians diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h index 1e031d46bd..724f43fda5 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h +++ b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h @@ -28,8 +28,8 @@ public: // return true if sensor is basically healthy (we are receiving data) bool healthy() const; - // consume VISION_POSITION_DELTA MAVLink message - virtual void handle_msg(const mavlink_message_t &msg) {}; + // consume vision_position_delta mavlink messages + virtual void handle_vision_position_delta_msg(const mavlink_message_t &msg) {}; // general purpose methods to consume position estimate data and send to EKF // distances in meters, roll, pitch and yaw are in radians diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp b/libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp index 255b478ab3..c752567be9 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp @@ -26,8 +26,8 @@ AP_VisualOdom_MAV::AP_VisualOdom_MAV(AP_VisualOdom &frontend) : { } -// consume VISION_POSITION_DELTA MAVLink message -void AP_VisualOdom_MAV::handle_msg(const mavlink_message_t &msg) +// consume vision_position_delta mavlink messages +void AP_VisualOdom_MAV::handle_vision_position_delta_msg(const mavlink_message_t &msg) { // decode message mavlink_vision_position_delta_t packet; diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_MAV.h b/libraries/AP_VisualOdom/AP_VisualOdom_MAV.h index f1a6fe7474..8aa039cc91 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_MAV.h +++ b/libraries/AP_VisualOdom/AP_VisualOdom_MAV.h @@ -9,6 +9,6 @@ public: // constructor AP_VisualOdom_MAV(AP_VisualOdom &frontend); - // consume VISION_POSITION_DELTA MAVLink message - void handle_msg(const mavlink_message_t &msg) override; + // consume vision_position_delta mavlink messages + void handle_vision_position_delta_msg(const mavlink_message_t &msg) override; };