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

AP_Mission: don't allow waypoint 0 (home) to be changed #29039

Draft
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

IamPete1
Copy link
Member

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.

if (index == 0) {
cmd = {};
cmd.id = MAV_CMD_NAV_WAYPOINT;
cmd.content.location = AP::ahrs().get_home();
return true;
}

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.

// if the mission is empty save a takeoff command
if (copter.mode_auto.mission.num_commands() == 0) {
// set our location ID to 16, MAV_CMD_NAV_WAYPOINT
cmd.id = MAV_CMD_NAV_TAKEOFF;
cmd.content.location.alt = MAX(copter.current_loc.alt,100);
// use the current altitude for the target alt for takeoff.
// only altitude will matter to the AP mission script for takeoff.
if (copter.mode_auto.mission.add_cmd(cmd)) {
// log event
LOGGER_WRITE_EVENT(LogEvent::SAVEWP_ADD_WP);
}
}

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:
image

@IamPete1 IamPete1 added the BUG label Jan 10, 2025
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

1 participant