Skip to content

Commit

Permalink
AP_Mission: update NAV_DELAY comment that said wrong ID number
Browse files Browse the repository at this point in the history
  • Loading branch information
magicrub committed Aug 14, 2019
1 parent 6c3ce52 commit e70ff1b
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_Mission/AP_Mission.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -790,7 +790,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
cmd.p1 = packet.param1; // on/off. >0.5 means "on", hand-over control to external controller
break;

case MAV_CMD_NAV_DELAY: // MAV ID: 94
case MAV_CMD_NAV_DELAY: // MAV ID: 93
cmd.content.nav_delay.seconds = packet.param1; // delay in seconds
cmd.content.nav_delay.hour_utc = packet.param2;// absolute time's hour (utc)
cmd.content.nav_delay.min_utc = packet.param3;// absolute time's min (utc)
Expand Down Expand Up @@ -1222,7 +1222,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
packet.param1 = cmd.p1; // on/off. >0.5 means "on", hand-over control to external controller
break;

case MAV_CMD_NAV_DELAY: // MAV ID: 94
case MAV_CMD_NAV_DELAY: // MAV ID: 93
packet.param1 = cmd.content.nav_delay.seconds; // delay in seconds
packet.param2 = cmd.content.nav_delay.hour_utc; // absolute time's day of week (utc)
packet.param3 = cmd.content.nav_delay.min_utc; // absolute time's hour (utc)
Expand Down

0 comments on commit e70ff1b

Please sign in to comment.