mirror of https://github.com/ArduPilot/ardupilot
Rover: adjust for AP_Mission logging mission-item-starts
This commit is contained in:
parent
48c9cd6eae
commit
981c500845
|
@ -512,13 +512,6 @@ void ModeAuto::send_guided_position_target()
|
|||
/********************************************************************************/
|
||||
bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// log when new commands start
|
||||
if (rover.should_log(MASK_LOG_CMD)) {
|
||||
rover.logger.Write_Mission_Cmd(mission, cmd);
|
||||
}
|
||||
#endif
|
||||
|
||||
switch (cmd.id) {
|
||||
case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint
|
||||
return do_nav_wp(cmd, false);
|
||||
|
|
|
@ -125,6 +125,9 @@ void Rover::init_ardupilot()
|
|||
#if AP_MISSION_ENABLED
|
||||
// initialise mission library
|
||||
mode_auto.mission.init();
|
||||
#if HAL_LOGGING_ENABLED
|
||||
mode_auto.mission.set_log_start_mission_item_bit(MASK_LOG_CMD);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// initialise AP_Logger library
|
||||
|
|
Loading…
Reference in New Issue