mirror of https://github.com/ArduPilot/ardupilot
AP_VisualOdom: rename handle_vision_position_delta_msg
This commit is contained in:
parent
b519d285a6
commit
c78b1ab3bf
|
@ -106,8 +106,8 @@ bool AP_VisualOdom::healthy() const
|
||||||
return _driver->healthy();
|
return _driver->healthy();
|
||||||
}
|
}
|
||||||
|
|
||||||
// consume VISION_POSITION_DELTA MAVLink message
|
// consume vision_position_delta mavlink messages
|
||||||
void AP_VisualOdom::handle_msg(const mavlink_message_t &msg)
|
void AP_VisualOdom::handle_vision_position_delta_msg(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
// exit immediately if not enabled
|
// exit immediately if not enabled
|
||||||
if (!enabled()) {
|
if (!enabled()) {
|
||||||
|
@ -116,7 +116,7 @@ void AP_VisualOdom::handle_msg(const mavlink_message_t &msg)
|
||||||
|
|
||||||
// call backend
|
// call backend
|
||||||
if (_driver != nullptr) {
|
if (_driver != nullptr) {
|
||||||
_driver->handle_msg(msg);
|
_driver->handle_vision_position_delta_msg(msg);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -55,8 +55,8 @@ public:
|
||||||
// return a 3D vector defining the position offset of the camera in meters relative to the body frame origin
|
// 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; }
|
const Vector3f &get_pos_offset(void) const { return _pos_offset; }
|
||||||
|
|
||||||
// consume data from MAVLink messages
|
// consume vision_position_delta mavlink messages
|
||||||
void handle_msg(const mavlink_message_t &msg);
|
void handle_vision_position_delta_msg(const mavlink_message_t &msg);
|
||||||
|
|
||||||
// general purpose methods to consume position estimate data and send to EKF
|
// general purpose methods to consume position estimate data and send to EKF
|
||||||
// distances in meters, roll, pitch and yaw are in radians
|
// distances in meters, roll, pitch and yaw are in radians
|
||||||
|
|
|
@ -28,8 +28,8 @@ public:
|
||||||
// return true if sensor is basically healthy (we are receiving data)
|
// return true if sensor is basically healthy (we are receiving data)
|
||||||
bool healthy() const;
|
bool healthy() const;
|
||||||
|
|
||||||
// consume VISION_POSITION_DELTA MAVLink message
|
// consume vision_position_delta mavlink messages
|
||||||
virtual void handle_msg(const mavlink_message_t &msg) {};
|
virtual void handle_vision_position_delta_msg(const mavlink_message_t &msg) {};
|
||||||
|
|
||||||
// general purpose methods to consume position estimate data and send to EKF
|
// general purpose methods to consume position estimate data and send to EKF
|
||||||
// distances in meters, roll, pitch and yaw are in radians
|
// distances in meters, roll, pitch and yaw are in radians
|
||||||
|
|
|
@ -26,8 +26,8 @@ AP_VisualOdom_MAV::AP_VisualOdom_MAV(AP_VisualOdom &frontend) :
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
// consume VISION_POSITION_DELTA MAVLink message
|
// consume vision_position_delta mavlink messages
|
||||||
void AP_VisualOdom_MAV::handle_msg(const mavlink_message_t &msg)
|
void AP_VisualOdom_MAV::handle_vision_position_delta_msg(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
// decode message
|
// decode message
|
||||||
mavlink_vision_position_delta_t packet;
|
mavlink_vision_position_delta_t packet;
|
||||||
|
|
|
@ -9,6 +9,6 @@ public:
|
||||||
// constructor
|
// constructor
|
||||||
AP_VisualOdom_MAV(AP_VisualOdom &frontend);
|
AP_VisualOdom_MAV(AP_VisualOdom &frontend);
|
||||||
|
|
||||||
// consume VISION_POSITION_DELTA MAVLink message
|
// consume vision_position_delta mavlink messages
|
||||||
void handle_msg(const mavlink_message_t &msg) override;
|
void handle_vision_position_delta_msg(const mavlink_message_t &msg) override;
|
||||||
};
|
};
|
||||||
|
|
Loading…
Reference in New Issue