From c1433e02205185dba4bd57fda742b2e2d5b8e391 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 12 Jul 2017 11:37:03 +0900 Subject: [PATCH] Copter: minor comment and formatting fixes no functional change --- ArduCopter/control_auto.cpp | 2 +- ArduCopter/control_guided.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/control_auto.cpp b/ArduCopter/control_auto.cpp index 0c2c5a7865..0798efc0d9 100644 --- a/ArduCopter/control_auto.cpp +++ b/ArduCopter/control_auto.cpp @@ -658,7 +658,7 @@ void Copter::set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, // get current yaw target int32_t curr_yaw_target = attitude_control->get_att_target_euler_cd().z; - // get final angle, 1 = Relative, 0 = Absolute + // calculate final angle as relative to vehicle heading or absolute if (!relative_angle) { // absolute angle yaw_look_at_heading = wrap_360_cd(angle_deg * 100); diff --git a/ArduCopter/control_guided.cpp b/ArduCopter/control_guided.cpp index aea8a5ceeb..8eb929f3a1 100644 --- a/ArduCopter/control_guided.cpp +++ b/ArduCopter/control_guided.cpp @@ -485,7 +485,7 @@ void Copter::guided_vel_control_run() uint32_t tnow = millis(); if (tnow - vel_update_time_ms > GUIDED_POSVEL_TIMEOUT_MS) { if (!pos_control->get_desired_velocity().is_zero()) { - guided_set_desired_velocity_with_accel_and_fence_limits(Vector3f(0.0f,0.0f,0.0f)); + guided_set_desired_velocity_with_accel_and_fence_limits(Vector3f(0.0f, 0.0f, 0.0f)); } if (auto_yaw_mode == AUTO_YAW_RATE) { set_auto_yaw_rate(0.0f);