mirror of https://github.com/ArduPilot/ardupilot
AP_VisualOdom: removed empty constructors
This commit is contained in:
parent
952a827287
commit
2406877a60
|
@ -23,12 +23,6 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// constructor
|
||||
AP_VisualOdom_MAV::AP_VisualOdom_MAV(AP_VisualOdom &frontend) :
|
||||
AP_VisualOdom_Backend(frontend)
|
||||
{
|
||||
}
|
||||
|
||||
// consume vision position estimate data and send to EKF. distances in meters
|
||||
void AP_VisualOdom_MAV::handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter)
|
||||
{
|
||||
|
|
|
@ -9,7 +9,7 @@ class AP_VisualOdom_MAV : public AP_VisualOdom_Backend
|
|||
|
||||
public:
|
||||
// constructor
|
||||
AP_VisualOdom_MAV(AP_VisualOdom &frontend);
|
||||
using AP_VisualOdom_Backend::AP_VisualOdom_Backend;
|
||||
|
||||
// consume vision position estimate data and send to EKF. distances in meters
|
||||
void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) override;
|
||||
|
|
Loading…
Reference in New Issue