mirror of https://github.com/ArduPilot/ardupilot
Blimp: move handling of DO_SET_HOME up to GCS_MAVLink base class
This commit is contained in:
parent
89a9a0e6d1
commit
6477effa3f
|
@ -310,8 +310,8 @@ private:
|
||||||
// commands.cpp
|
// commands.cpp
|
||||||
void update_home_from_EKF();
|
void update_home_from_EKF();
|
||||||
void set_home_to_current_location_inflight();
|
void set_home_to_current_location_inflight();
|
||||||
bool set_home_to_current_location(bool lock) WARN_IF_UNUSED;
|
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
|
||||||
bool set_home(const Location& loc, bool lock) WARN_IF_UNUSED;
|
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
||||||
bool far_from_EKF_origin(const Location& loc);
|
bool far_from_EKF_origin(const Location& loc);
|
||||||
|
|
||||||
// ekf_check.cpp
|
// ekf_check.cpp
|
||||||
|
|
|
@ -448,15 +448,6 @@ MAV_RESULT GCS_MAVLINK_Blimp::handle_command_do_set_roi(const Location &roi_loc)
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool GCS_MAVLINK_Blimp::set_home_to_current_location(bool _lock)
|
|
||||||
{
|
|
||||||
return blimp.set_home_to_current_location(_lock);
|
|
||||||
}
|
|
||||||
bool GCS_MAVLINK_Blimp::set_home(const Location& loc, bool _lock)
|
|
||||||
{
|
|
||||||
return blimp.set_home(loc, _lock);
|
|
||||||
}
|
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
|
MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
|
||||||
{
|
{
|
||||||
const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
|
const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
|
||||||
|
|
|
@ -35,8 +35,6 @@ protected:
|
||||||
bool mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const override;
|
bool mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const override;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
|
|
||||||
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
|
||||||
void send_nav_controller_output() const override; //TODO Apparently can't remove this or the build fails.
|
void send_nav_controller_output() const override; //TODO Apparently can't remove this or the build fails.
|
||||||
uint64_t capabilities() const override;
|
uint64_t capabilities() const override;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue