mirror of https://github.com/ArduPilot/ardupilot
Rover: minor format fix
This commit is contained in:
parent
58b643c458
commit
a035950a22
|
@ -145,7 +145,7 @@ void AP_MotorsUGV::set_throttle(float throttle)
|
|||
{
|
||||
// sanity check throttle min and max
|
||||
_throttle_min = constrain_int16(_throttle_min, 0, 20);
|
||||
_throttle_max = constrain_int16(_throttle_max,30,100);
|
||||
_throttle_max = constrain_int16(_throttle_max, 30, 100);
|
||||
|
||||
// check throttle is between -_throttle_max ~ +_throttle_max but outside -throttle_min ~ +throttle_min
|
||||
_throttle = constrain_float(throttle, -_throttle_max, _throttle_max);
|
||||
|
|
|
@ -229,7 +229,7 @@ void Rover::do_nav_wp(const AP_Mission::Mission_Command& cmd, bool stay_active_a
|
|||
// in case of non-zero loiter duration, we provide heading-unknown to signal we should stop at the point
|
||||
float next_leg_bearing_cd = MODE_NEXT_HEADING_UNKNOWN;
|
||||
if (loiter_duration == 0) {
|
||||
next_leg_bearing_cd = mission.get_next_ground_course_cd(MODE_NEXT_HEADING_UNKNOWN);
|
||||
next_leg_bearing_cd = mission.get_next_ground_course_cd(MODE_NEXT_HEADING_UNKNOWN);
|
||||
}
|
||||
|
||||
// retrieve and sanitize target location
|
||||
|
|
Loading…
Reference in New Issue