mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: Tri: dont check yaw servo on plane
This commit is contained in:
parent
7726848a50
commit
152e2366f0
|
@ -35,13 +35,14 @@ void AP_MotorsTri::init(motor_frame_class frame_class, motor_frame_type frame_ty
|
|||
motor_enabled[AP_MOTORS_MOT_2] = true;
|
||||
motor_enabled[AP_MOTORS_MOT_4] = true;
|
||||
|
||||
#if !APM_BUILD_TYPE(APM_BUILD_ArduPlane) // Tilt Rotors do not need a yaw servo
|
||||
// find the yaw servo
|
||||
_yaw_servo = SRV_Channels::get_channel_for(SRV_Channel::k_motor7, AP_MOTORS_CH_TRI_YAW);
|
||||
if (!_yaw_servo) {
|
||||
if (!SRV_Channels::get_channel_for(SRV_Channel::k_motor7, AP_MOTORS_CH_TRI_YAW)) {
|
||||
gcs().send_text(MAV_SEVERITY_ERROR, "MotorsTri: unable to setup yaw channel");
|
||||
// don't set initialised_ok
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
// allow mapping of motor7
|
||||
add_motor_num(AP_MOTORS_CH_TRI_YAW);
|
||||
|
@ -67,7 +68,7 @@ void AP_MotorsTri::set_frame_class_and_type(motor_frame_class frame_class, motor
|
|||
_pitch_reversed = false;
|
||||
}
|
||||
|
||||
_flags.initialised_ok = (frame_class == MOTOR_FRAME_TRI);
|
||||
_flags.initialised_ok = (frame_class == MOTOR_FRAME_TRI) && SRV_Channels::function_assigned(SRV_Channel::k_motor7);
|
||||
}
|
||||
|
||||
// set update rate to motors - a value in hertz
|
||||
|
|
|
@ -63,7 +63,6 @@ protected:
|
|||
|
||||
// parameters
|
||||
|
||||
SRV_Channel *_yaw_servo; // yaw output channel
|
||||
float _pivot_angle; // Angle of yaw pivot
|
||||
float _thrust_right;
|
||||
float _thrust_rear;
|
||||
|
|
Loading…
Reference in New Issue