From 9b6de75203b7641d38a548eedd9deb387bb7316a Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sat, 23 Apr 2016 23:35:00 -0700 Subject: [PATCH] Copter: clipped param cmd float to zero --- ArduCopter/commands_logic.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/commands_logic.cpp b/ArduCopter/commands_logic.cpp index 47bde85be6..e326145604 100644 --- a/ArduCopter/commands_logic.cpp +++ b/ArduCopter/commands_logic.cpp @@ -299,7 +299,7 @@ void Copter::do_nav_wp(const AP_Mission::Mission_Command& cmd) // this will be used to remember the time in millis after we reach or pass the WP. loiter_time = 0; // this is the delay, stored in seconds - loiter_time_max = cmd.p1; + loiter_time_max = (cmd.p1 >= 1) ? cmd.p1 : 0; // Set wp navigation target auto_wp_start(local_pos); @@ -428,7 +428,7 @@ void Copter::do_loiter_time(const AP_Mission::Mission_Command& cmd) // setup loiter timer loiter_time = 0; - loiter_time_max = cmd.p1; // units are (seconds) + loiter_time_max = (cmd.p1 >= 1) ? cmd.p1 : 0; // units are (seconds) } // do_spline_wp - initiate move to next waypoint @@ -440,7 +440,7 @@ void Copter::do_spline_wp(const AP_Mission::Mission_Command& cmd) // this will be used to remember the time in millis after we reach or pass the WP. loiter_time = 0; // this is the delay, stored in seconds - loiter_time_max = cmd.p1; + loiter_time_max = (cmd.p1 >= 1) ? cmd.p1 : 0; // determine segment start and end type bool stopped_at_start = true;