Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Make GCS_MAVLink base class handle DO_SET_HOME #26683

Merged
merged 9 commits into from
Apr 8, 2024
9 changes: 1 addition & 8 deletions AntennaTracker/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -451,13 +451,6 @@ MAV_RESULT GCS_MAVLINK_Tracker::handle_command_int_packet(const mavlink_command_
}
}

bool GCS_MAVLINK_Tracker::set_home_to_current_location(bool _lock) {
return tracker.set_home(AP::gps().location());
}
bool GCS_MAVLINK_Tracker::set_home(const Location& loc, bool _lock) {
return tracker.set_home(loc);
}

void GCS_MAVLINK_Tracker::handle_message(const mavlink_message_t &msg)
{
switch (msg.msgid) {
Expand Down Expand Up @@ -584,7 +577,7 @@ void GCS_MAVLINK_Tracker::handle_message_mission_item(const mavlink_message_t &m

// check if this is the HOME wp
if (packet.seq == 0) {
if (!tracker.set_home(tell_command)) {
if (!tracker.set_home(tell_command, false)) {
result = MAV_MISSION_ERROR;
goto mission_failed;
}
Expand Down
3 changes: 0 additions & 3 deletions AntennaTracker/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,6 @@ class GCS_MAVLINK_Tracker : public GCS_MAVLINK
return 0; // what if we have been picked up and carried somewhere?
}

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;
void send_pid_tuning() override;

Expand Down
2 changes: 1 addition & 1 deletion AntennaTracker/Tracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ void Tracker::one_second_loop()
// set home to current location
Location temp_loc;
if (ahrs.get_location(temp_loc)) {
if (!set_home(temp_loc)){
if (!set_home(temp_loc, false)) {
// fail silently
}
}
Expand Down
3 changes: 2 additions & 1 deletion AntennaTracker/Tracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,8 @@ class Tracker : public AP_Vehicle {
void init_ardupilot() override;
bool get_home_eeprom(Location &loc) const;
bool set_home_eeprom(const Location &temp) WARN_IF_UNUSED;
bool set_home(const Location &temp) WARN_IF_UNUSED;
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location &temp, bool lock) override WARN_IF_UNUSED;
void prepare_servos();
void set_mode(Mode &newmode, ModeReason reason);
bool set_mode(uint8_t new_mode, ModeReason reason) override;
Expand Down
2 changes: 1 addition & 1 deletion AntennaTracker/sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ void Tracker::update_GPS(void)
// Now have an initial GPS position
// use it as the HOME position in future startups
current_loc = gps.location();
IGNORE_RETURN(set_home(current_loc));
IGNORE_RETURN(set_home(current_loc, false));
ground_start_count = 0;
}
}
Expand Down
7 changes: 6 additions & 1 deletion AntennaTracker/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,12 @@ bool Tracker::set_home_eeprom(const Location &temp)
return true;
}

bool Tracker::set_home(const Location &temp)
bool Tracker::set_home_to_current_location(bool lock)
{
return set_home(AP::gps().location(), lock);
}

bool Tracker::set_home(const Location &temp, bool lock)
{
// check EKF origin has been set
Location ekf_origin;
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -739,8 +739,8 @@ class Copter : public AP_Vehicle {
// commands.cpp
void update_home_from_EKF();
void set_home_to_current_location_inflight();
bool set_home_to_current_location(bool lock) WARN_IF_UNUSED;
bool set_home(const Location& loc, 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) override WARN_IF_UNUSED;
bool far_from_EKF_origin(const Location& loc);

// compassmot.cpp
Expand Down
7 changes: 0 additions & 7 deletions ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -711,13 +711,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_int
return GCS_MAVLINK::handle_preflight_reboot(packet, msg);
}

bool GCS_MAVLINK_Copter::set_home_to_current_location(bool _lock) {
return copter.set_home_to_current_location(_lock);
}
bool GCS_MAVLINK_Copter::set_home(const Location& loc, bool _lock) {
return copter.set_home(loc, _lock);
}

MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
{
#if MODE_GUIDED_ENABLED == ENABLED
Expand Down
2 changes: 0 additions & 2 deletions ArduCopter/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,6 @@ class GCS_MAVLINK_Copter : public GCS_MAVLINK

void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;

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;
uint64_t capabilities() const override;

Expand Down
18 changes: 9 additions & 9 deletions ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -781,39 +781,39 @@ void GCS_MAVLINK_Plane::packetReceived(const mavlink_status_t &status,
}


bool GCS_MAVLINK_Plane::set_home_to_current_location(bool _lock)
bool Plane::set_home_to_current_location(bool _lock)
{
if (!plane.set_home_persistently(AP::gps().location())) {
if (!set_home_persistently(AP::gps().location())) {
return false;
}
if (_lock) {
AP::ahrs().lock_home();
}
if ((plane.control_mode == &plane.mode_rtl)
if ((control_mode == &mode_rtl)
#if HAL_QUADPLANE_ENABLED
|| (plane.control_mode == &plane.mode_qrtl)
|| (control_mode == &mode_qrtl)
#endif
) {
// if in RTL head to the updated home location
plane.control_mode->enter();
control_mode->enter();
}
return true;
}
bool GCS_MAVLINK_Plane::set_home(const Location& loc, bool _lock)
bool Plane::set_home(const Location& loc, bool _lock)
{
if (!AP::ahrs().set_home(loc)) {
return false;
}
if (_lock) {
AP::ahrs().lock_home();
}
if ((plane.control_mode == &plane.mode_rtl)
if ((control_mode == &mode_rtl)
#if HAL_QUADPLANE_ENABLED
|| (plane.control_mode == &plane.mode_qrtl)
|| (control_mode == &mode_qrtl)
#endif
) {
// if in RTL head to the updated home location
plane.control_mode->enter();
control_mode->enter();
}
return true;
}
Expand Down
2 changes: 0 additions & 2 deletions ArduPlane/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,6 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK

bool persist_streamrates() const override { return true; }

bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
uint64_t capabilities() const override;

void send_nav_controller_output() const override;
Expand Down
2 changes: 2 additions & 0 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -986,6 +986,8 @@ class Plane : public AP_Vehicle {

// set home location and store it persistently:
bool set_home_persistently(const Location &loc) WARN_IF_UNUSED;
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;

// control_modes.cpp
void read_control_switch();
Expand Down
7 changes: 0 additions & 7 deletions ArduSub/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -475,13 +475,6 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_do_set_roi(const Location &roi_loc)
return MAV_RESULT_ACCEPTED;
}

bool GCS_MAVLINK_Sub::set_home_to_current_location(bool _lock) {
return sub.set_home_to_current_location(_lock);
}
bool GCS_MAVLINK_Sub::set_home(const Location& loc, bool _lock) {
return sub.set_home(loc, _lock);
}

MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{
switch(packet.command) {
Expand Down
3 changes: 0 additions & 3 deletions ArduSub/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,6 @@ class GCS_MAVLINK_Sub : public GCS_MAVLINK {
int32_t global_position_int_alt() const override;
int32_t global_position_int_relative_alt() const override;

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_banner() override;

void send_nav_controller_output() const override;
Expand Down
4 changes: 2 additions & 2 deletions ArduSub/Sub.h
Original file line number Diff line number Diff line change
Expand Up @@ -423,8 +423,8 @@ class Sub : public AP_Vehicle {
void userhook_SuperSlowLoop();
void update_home_from_EKF();
void set_home_to_current_location_inflight();
bool set_home_to_current_location(bool lock) WARN_IF_UNUSED;
bool set_home(const Location& loc, 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) override WARN_IF_UNUSED;
bool far_from_EKF_origin(const Location& loc);
void exit_mission();
bool verify_loiter_unlimited();
Expand Down
4 changes: 2 additions & 2 deletions Blimp/Blimp.h
Original file line number Diff line number Diff line change
Expand Up @@ -310,8 +310,8 @@ class Blimp : public AP_Vehicle
// commands.cpp
void update_home_from_EKF();
void set_home_to_current_location_inflight();
bool set_home_to_current_location(bool lock) WARN_IF_UNUSED;
bool set_home(const Location& loc, 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) override WARN_IF_UNUSED;
bool far_from_EKF_origin(const Location& loc);

// ekf_check.cpp
Expand Down
9 changes: 0 additions & 9 deletions Blimp/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -448,15 +448,6 @@ MAV_RESULT GCS_MAVLINK_Blimp::handle_command_do_set_roi(const Location &roi_loc)
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)
{
const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
Expand Down
2 changes: 0 additions & 2 deletions Blimp/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,6 @@ class GCS_MAVLINK_Blimp : public GCS_MAVLINK
bool mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const override;
#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.
uint64_t capabilities() const override;

Expand Down
8 changes: 0 additions & 8 deletions Rover/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -656,14 +656,6 @@ MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlin
return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg);
}

bool GCS_MAVLINK_Rover::set_home_to_current_location(bool _lock) {
return rover.set_home_to_current_location(_lock);
}

bool GCS_MAVLINK_Rover::set_home(const Location& loc, bool _lock) {
return rover.set_home(loc, _lock);
}

MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{
switch (packet.command) {
Expand Down
2 changes: 0 additions & 2 deletions Rover/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,6 @@ class GCS_MAVLINK_Rover : public GCS_MAVLINK

bool persist_streamrates() const override { return true; }

bool set_home_to_current_location(bool lock) override;
bool set_home(const Location& loc, bool lock) override;
uint64_t capabilities() const override;

void send_nav_controller_output() const override;
Expand Down
4 changes: 2 additions & 2 deletions Rover/Rover.h
Original file line number Diff line number Diff line change
Expand Up @@ -295,8 +295,8 @@ class Rover : public AP_Vehicle {
bool is_balancebot() const;

// commands.cpp
bool set_home_to_current_location(bool lock) WARN_IF_UNUSED;
bool set_home(const Location& loc, 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) override WARN_IF_UNUSED;
void update_home();

// crash_check.cpp
Expand Down
5 changes: 5 additions & 0 deletions libraries/AP_Vehicle/AP_Vehicle.h
Original file line number Diff line number Diff line change
Expand Up @@ -289,6 +289,11 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks {
*/
virtual bool get_rate_ef_targets(Vector3f& rate_ef_targets) const { return false; }

#if AP_AHRS_ENABLED
virtual bool set_home_to_current_location(bool lock) WARN_IF_UNUSED { return false; }
virtual bool set_home(const Location& loc, bool lock) WARN_IF_UNUSED { return false; }
#endif

protected:

virtual void init_ardupilot() = 0;
Expand Down
4 changes: 2 additions & 2 deletions libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -526,8 +526,8 @@ class GCS_MAVLINK
virtual MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
MAV_RESULT handle_command_int_external_position_estimate(const mavlink_command_int_t &packet);

virtual bool set_home_to_current_location(bool lock) = 0;
virtual bool set_home(const Location& loc, bool lock) = 0;
bool set_home_to_current_location(bool lock);
bool set_home(const Location& loc, bool lock);

#if AP_ARMING_ENABLED
virtual MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_int_t &packet);
Expand Down
17 changes: 17 additions & 0 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5057,6 +5057,23 @@ void GCS_MAVLINK::handle_landing_target(const mavlink_message_t &msg)
}


bool GCS_MAVLINK::set_home_to_current_location(bool _lock)
{
#if AP_VEHICLE_ENABLED
return AP::vehicle()->set_home_to_current_location(_lock);
#else
return false;
#endif
}

bool GCS_MAVLINK::set_home(const Location& loc, bool _lock) {
#if AP_VEHICLE_ENABLED
return AP::vehicle()->set_home(loc, _lock);
#else
return false;
#endif
}

MAV_RESULT GCS_MAVLINK::handle_command_do_set_home(const mavlink_command_int_t &packet)
{
if (is_equal(packet.param1, 1.0f) || (packet.x == 0 && packet.y == 0)) {
Expand Down
3 changes: 0 additions & 3 deletions libraries/GCS_MAVLink/GCS_Dummy.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,6 @@ class GCS_MAVLINK_Dummy : public GCS_MAVLINK
MAV_MODE base_mode() const override { return (MAV_MODE)MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; }
MAV_STATE vehicle_system_status() const override { return MAV_STATE_CALIBRATING; }

bool set_home_to_current_location(bool _lock) override { return false; }
bool set_home(const Location& loc, bool _lock) override { return false; }

void send_nav_controller_output() const override {};
void send_pid_tuning() override {};
};
Expand Down
Loading