Sub: roll pitch comments

In ArduSub modes Auto & Guided, direct (not translated to forward/lateral) Roll and Pitch values come from the RC channels, not from wp controller. The existing comments are leftovers from ArduCopter
This commit is contained in:
GH6947 2022-05-24 16:24:05 +03:00 committed by Randy Mackay
parent f6544ca25a
commit 9304fa0f52
2 changed files with 9 additions and 9 deletions

View File

@ -162,10 +162,10 @@ void Sub::auto_wp_run()
// call attitude controller
if (auto_yaw_mode == AUTO_YAW_HOLD) {
// roll & pitch from waypoint controller, yaw rate from pilot
// roll & pitch & yaw rate from pilot
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
} else {
// roll, pitch from waypoint controller, yaw heading from auto_heading()
// roll, pitch from pilot, yaw heading from auto_heading()
attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, get_auto_heading(), true);
}
}
@ -339,7 +339,7 @@ void Sub::auto_loiter_run()
float target_roll, target_pitch;
get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
// roll & pitch from waypoint controller, yaw rate from pilot
// roll & pitch & yaw rate from pilot
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
}

View File

@ -315,10 +315,10 @@ void Sub::guided_pos_control_run()
// call attitude controller
if (auto_yaw_mode == AUTO_YAW_HOLD) {
// roll & pitch from waypoint controller, yaw rate from pilot
// roll & pitch & yaw rate from pilot
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
} else {
// roll, pitch from waypoint controller, yaw heading from auto_heading()
// roll, pitch from pilot, yaw heading from auto_heading()
attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);
}
}
@ -371,10 +371,10 @@ void Sub::guided_vel_control_run()
// call attitude controller
if (auto_yaw_mode == AUTO_YAW_HOLD) {
// roll & pitch from waypoint controller, yaw rate from pilot
// roll & pitch & yaw rate from pilot
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
} else {
// roll, pitch from waypoint controller, yaw heading from auto_heading()
// roll, pitch from pilot, yaw heading from auto_heading()
attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);
}
}
@ -437,10 +437,10 @@ void Sub::guided_posvel_control_run()
// call attitude controller
if (auto_yaw_mode == AUTO_YAW_HOLD) {
// roll & pitch from waypoint controller, yaw rate from pilot
// roll & pitch & yaw rate from pilot
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
} else {
// roll, pitch from waypoint controller, yaw heading from auto_heading()
// roll, pitch from pilot, yaw heading from auto_heading()
attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);
}
}