Skip to content

Commit bc4dff5

Browse files
committed
AP_Misison: don't allow home to be changed
1 parent 6efe210 commit bc4dff5

File tree

2 files changed

+24
-12
lines changed

2 files changed

+24
-12
lines changed

libraries/AP_Mission/AP_Mission.cpp

Lines changed: 19 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -498,14 +498,18 @@ bool AP_Mission::start_command(const Mission_Command& cmd)
498498
/// cmd.index is updated with it's new position in the mission
499499
bool AP_Mission::add_cmd(Mission_Command& cmd)
500500
{
501+
// Home is always the index 0.
502+
// Commands should be added after home.
503+
const uint16_t index = MAX(_cmd_total, AP_MISSION_FIRST_REAL_COMMAND);
504+
501505
// attempt to write the command to storage
502-
bool ret = write_cmd_to_storage(_cmd_total, cmd);
506+
bool ret = write_cmd_to_storage(index, cmd);
503507

504508
if (ret) {
505509
// update command's index
506-
cmd.index = _cmd_total;
510+
cmd.index = index;
507511
// increment total number of commands
508-
_cmd_total.set_and_save(_cmd_total + 1);
512+
_cmd_total.set_and_save(index + 1);
509513
}
510514

511515
return ret;
@@ -516,8 +520,8 @@ bool AP_Mission::add_cmd(Mission_Command& cmd)
516520
/// returns true if successfully replaced, false on failure
517521
bool AP_Mission::replace_cmd(uint16_t index, const Mission_Command& cmd)
518522
{
519-
// sanity check index
520-
if (index >= (unsigned)_cmd_total) {
523+
// sanity check index, can't replace home or a waypoint which does not exist
524+
if ((index == 0) || index >= (unsigned)_cmd_total) {
521525
return false;
522526
}
523527

@@ -704,11 +708,19 @@ bool AP_Mission::restart_current_nav_cmd()
704708
// returns false on any issue at all.
705709
bool AP_Mission::set_item(uint16_t index, mavlink_mission_item_int_t& src_packet)
706710
{
711+
// Cannot set home
712+
if (index < AP_MISSION_FIRST_REAL_COMMAND) {
713+
return false;
714+
}
715+
707716
// this is the on-storage format
708717
AP_Mission::Mission_Command cmd {};
709718

719+
// Missions start at 1
720+
const uint16_t mission_index = MAX(num_commands(), AP_MISSION_FIRST_REAL_COMMAND);
721+
710722
// can't handle request for anything bigger than the mission size+1...
711-
if (index > num_commands()) {
723+
if (index > mission_index) {
712724
return false;
713725
}
714726

@@ -719,7 +731,7 @@ bool AP_Mission::set_item(uint16_t index, mavlink_mission_item_int_t& src_packet
719731

720732
// A request to set the 'next' item after the end is how we add an extra
721733
// item to the list, thus allowing us to write entire missions if needed.
722-
if (index == num_commands()) {
734+
if (index == mission_index) {
723735
return add_cmd(cmd);
724736
}
725737

libraries/AP_Mission/AP_Mission.h

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -631,11 +631,6 @@ class AP_Mission
631631
/// true is return if successful
632632
bool read_cmd_from_storage(uint16_t index, Mission_Command& cmd) const;
633633

634-
/// write_cmd_to_storage - write a command to storage
635-
/// cmd.index is used to calculate the storage location
636-
/// true is returned if successful
637-
bool write_cmd_to_storage(uint16_t index, const Mission_Command& cmd);
638-
639634
/// write_home_to_storage - writes the special purpose cmd 0 (home) to storage
640635
/// home is taken directly from ahrs
641636
void write_home_to_storage();
@@ -948,6 +943,11 @@ class AP_Mission
948943
bool start_command_do_gimbal_manager_pitchyaw(const AP_Mission::Mission_Command& cmd);
949944
bool start_command_fence(const AP_Mission::Mission_Command& cmd);
950945

946+
/// write_cmd_to_storage - write a command to storage
947+
/// cmd.index is used to calculate the storage location
948+
/// true is returned if successful
949+
bool write_cmd_to_storage(uint16_t index, const Mission_Command& cmd);
950+
951951
/*
952952
handle format conversion of storage format to allow us to update
953953
format to take advantage of new packing

0 commit comments

Comments
 (0)