AP_Mission: don't allow waypoint 0 (home) to be changed #29039
+24
−12
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
This highlights what is a tricky problem to fix. The main problem is that this will break most scripts which try and upload missions.
The problem is that mission allows you to set way-point 0, however when you try and read way point 0 you just get home.
ardupilot/libraries/AP_Mission/AP_Mission.cpp
Lines 817 to 822 in 6efe210
This is the key this issue. You can write whatever you like to waypoint 0, but there is no way to read it back or for it to be used in anyway. (The only way I can think is that if you have a eeprom copy you could read it out manualy)
This makes the change that your no longer allowed to write to waypoint 0, this give users a clue that there throwing away there first point, it will never be used.
Maybe the more complete fix is to stop storing home completely, this would require doing param conversion on the total mission item count.
A nice example of something that does not work as expected on master is the copter save way point switch (you have to make sure your mission is fully cleared and MIS_TOTAL is 0). In this case it carefully checks for there being 0 waypoints and tries to add a takeoff.
ardupilot/ArduCopter/RC_Channel_Copter.cpp
Lines 238 to 250 in 6efe210
However, that takeoff is written to index 0 so it is never used. If you read the mission back again you will find only a single mission item and no take off: