mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-07 00:18:29 -04:00
Copter: minor comment and formatting fixes
no functional change
This commit is contained in:
parent
ed65d55f5e
commit
c1433e0220
@ -658,7 +658,7 @@ void Copter::set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps,
|
|||||||
// get current yaw target
|
// get current yaw target
|
||||||
int32_t curr_yaw_target = attitude_control->get_att_target_euler_cd().z;
|
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) {
|
if (!relative_angle) {
|
||||||
// absolute angle
|
// absolute angle
|
||||||
yaw_look_at_heading = wrap_360_cd(angle_deg * 100);
|
yaw_look_at_heading = wrap_360_cd(angle_deg * 100);
|
||||||
|
@ -485,7 +485,7 @@ void Copter::guided_vel_control_run()
|
|||||||
uint32_t tnow = millis();
|
uint32_t tnow = millis();
|
||||||
if (tnow - vel_update_time_ms > GUIDED_POSVEL_TIMEOUT_MS) {
|
if (tnow - vel_update_time_ms > GUIDED_POSVEL_TIMEOUT_MS) {
|
||||||
if (!pos_control->get_desired_velocity().is_zero()) {
|
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) {
|
if (auto_yaw_mode == AUTO_YAW_RATE) {
|
||||||
set_auto_yaw_rate(0.0f);
|
set_auto_yaw_rate(0.0f);
|
||||||
|
Loading…
Reference in New Issue
Block a user