added which transition the vtol is in to vehicle status

This commit is contained in:
Andreas Antener
2016-05-26 07:06:06 +02:00
parent 46105f735e
commit 8c9f4e8ab8
9 changed files with 34 additions and 25 deletions

View File

@@ -55,6 +55,7 @@ bool is_rotary_wing # True if system is in rotary wing configuration, so for a
bool is_vtol # True if the system is VTOL capable
bool vtol_fw_permanent_stab # True if vtol should stabilize attitude for fw in manual mode
bool in_transition_mode # True if VTOL is doing a transition
bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW
bool rc_signal_lost # true if RC reception lost
uint8 rc_input_mode # set to 1 to disable the RC input, 2 to enable manual control to RC in mapping.

View File

@@ -7,6 +7,7 @@ uint8 VEHICLE_VTOL_STATE_FW = 4
bool vtol_in_rw_mode # true: vtol vehicle is in rotating wing mode
bool vtol_in_trans_mode
bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW
bool vtol_transition_failsafe # vtol in transition failsafe mode
bool fw_permanent_stab # In fw mode stabilize attitude even if in manual mode
float32 airspeed_tot # Estimated airspeed over control surfaces

View File

@@ -1946,6 +1946,7 @@ int commander_thread_main(int argc, char *argv[])
if (is_vtol(&status)) {
status.is_rotary_wing = vtol_status.vtol_in_rw_mode;
status.in_transition_mode = vtol_status.vtol_in_trans_mode;
status.in_transition_to_fw = vtol_status.in_transition_to_fw;
status_flags.vtol_transition_failure = vtol_status.vtol_transition_failsafe;
status_flags.vtol_transition_failure_cmd = vtol_status.vtol_transition_failsafe;
}

View File

@@ -3196,21 +3196,17 @@ protected:
updated = true;
if (status.is_vtol) {
if (status.is_rotary_wing) {
if (status.in_transition_mode) {
if (!status.in_transition_mode && status.is_rotary_wing) {
_msg.vtol_state = MAV_VTOL_STATE_MC;
} else if (!status.in_transition_mode){
_msg.vtol_state = MAV_VTOL_STATE_FW;
} else if (status.in_transition_mode && status.in_transition_to_fw) {
_msg.vtol_state = MAV_VTOL_STATE_TRANSITION_TO_FW;
} else {
_msg.vtol_state = MAV_VTOL_STATE_MC;
}
} else {
if (status.in_transition_mode) {
} else if (status.in_transition_mode) {
_msg.vtol_state = MAV_VTOL_STATE_TRANSITION_TO_MC;
} else {
_msg.vtol_state = MAV_VTOL_STATE_FW;
}
}
}
}

View File

@@ -223,8 +223,11 @@ void Standard::update_vtol_state()
break;
case TRANSITION_TO_FW:
_vtol_mode = mode::TRANSITION_TO_MC;
break;
case TRANSITION_TO_MC:
_vtol_mode = TRANSITION;
_vtol_mode = mode::TRANSITION_TO_FW;
break;
}
}

View File

@@ -215,15 +215,17 @@ void Tailsitter::update_vtol_state()
break;
case TRANSITION_FRONT_P1:
_vtol_mode = TRANSITION;
_vtol_mode = TRANSITION_TO_FW;
_vtol_vehicle_status->vtol_in_trans_mode = true;
break;
case TRANSITION_FRONT_P2:
_vtol_mode = TRANSITION;
_vtol_mode = TRANSITION_TO_FW;
_vtol_vehicle_status->vtol_in_trans_mode = true;
break;
case TRANSITION_BACK:
_vtol_mode = TRANSITION;
_vtol_mode = TRANSITION_TO_MC;
_vtol_vehicle_status->vtol_in_trans_mode = true;
break;
}
@@ -482,7 +484,8 @@ void Tailsitter::fill_actuator_outputs()
_actuators_fw_in->control[actuator_controls_s::INDEX_THROTTLE]; // throttle
break;
case TRANSITION:
case TRANSITION_TO_FW:
case TRANSITION_TO_MC:
// in transition engines are mixed by weight (BACK TRANSITION ONLY)
_actuators_out_0->timestamp = _actuators_mc_in->timestamp;
_actuators_out_1->timestamp = _actuators_mc_in->timestamp;

View File

@@ -244,8 +244,11 @@ void Tiltrotor::update_vtol_state()
case TRANSITION_FRONT_P1:
case TRANSITION_FRONT_P2:
_vtol_mode = TRANSITION_TO_MC;
break;
case TRANSITION_BACK:
_vtol_mode = TRANSITION;
_vtol_mode = TRANSITION_TO_MC;
break;
}
}

View File

@@ -735,13 +735,12 @@ void VtolAttitudeControl::task_main()
} else if (_vtol_type->get_mode() == FIXED_WING) {
_transition_command = vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW;
}
} else if (_vtol_type->get_mode() == TRANSITION_TO_MC) {
/* We want to make sure that a mode change (manual>auto) during the back transition
* doesn't result in an unsafe state. This prevents the instant fall back to
* fixed-wing on the switch from manual to auto */
} else if (_vtol_type->get_mode() == TRANSITION_TO_MC) {
_transition_command = vehicle_status_s::VEHICLE_VTOL_STATE_MC;
_transition_command = vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC;
}
}
@@ -775,10 +774,11 @@ void VtolAttitudeControl::task_main()
fill_fw_att_rates_sp();
}
} else if (_vtol_type->get_mode() == TRANSITION) {
} else if (_vtol_type->get_mode() == TRANSITION_TO_MC || _vtol_type->get_mode() == TRANSITION_TO_FW) {
// vehicle is doing a transition
_vtol_vehicle_status.vtol_in_trans_mode = true;
_vtol_vehicle_status.vtol_in_rw_mode = true; //making mc attitude controller work during transition
_vtol_vehicle_status.in_transition_to_fw = _vtol_type->get_mode() == TRANSITION_TO_FW;
bool got_new_data = false;

View File

@@ -65,7 +65,8 @@ struct Params {
enum mode {
ROTARY_WING = 0,
FIXED_WING,
TRANSITION,
TRANSITION_TO_FW,
TRANSITION_TO_MC,
EXTERNAL
};