mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 03:49:12 +08:00
Position control needs to be deactivated during the transition otherwise it will fight itself.
This commit is contained in:
@@ -1,4 +1,5 @@
|
|||||||
uint64 timestamp # Microseconds since system boot
|
uint64 timestamp # Microseconds since system boot
|
||||||
bool vtol_in_rw_mode # true: vtol vehicle is in rotating wing mode
|
bool vtol_in_rw_mode # true: vtol vehicle is in rotating wing mode
|
||||||
|
bool vtol_in_trans_mode
|
||||||
bool fw_permanent_stab # In fw mode stabilize attitude even if in manual mode
|
bool fw_permanent_stab # In fw mode stabilize attitude even if in manual mode
|
||||||
float32 airspeed_tot # Estimated airspeed over control surfaces
|
float32 airspeed_tot # Estimated airspeed over control surfaces
|
||||||
|
|||||||
@@ -197,6 +197,8 @@ static struct home_position_s _home;
|
|||||||
|
|
||||||
static unsigned _last_mission_instance = 0;
|
static unsigned _last_mission_instance = 0;
|
||||||
|
|
||||||
|
struct vtol_vehicle_status_s vtol_status;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* The daemon app only briefly exists to start
|
* The daemon app only briefly exists to start
|
||||||
* the background job. The stack size assigned in the
|
* the background job. The stack size assigned in the
|
||||||
@@ -1169,7 +1171,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||||||
|
|
||||||
/* Subscribe to vtol vehicle status topic */
|
/* Subscribe to vtol vehicle status topic */
|
||||||
int vtol_vehicle_status_sub = orb_subscribe(ORB_ID(vtol_vehicle_status));
|
int vtol_vehicle_status_sub = orb_subscribe(ORB_ID(vtol_vehicle_status));
|
||||||
struct vtol_vehicle_status_s vtol_status;
|
//struct vtol_vehicle_status_s vtol_status;
|
||||||
memset(&vtol_status, 0, sizeof(vtol_status));
|
memset(&vtol_status, 0, sizeof(vtol_status));
|
||||||
vtol_status.vtol_in_rw_mode = true; //default for vtol is rotary wing
|
vtol_status.vtol_in_rw_mode = true; //default for vtol is rotary wing
|
||||||
|
|
||||||
@@ -2682,13 +2684,13 @@ set_control_mode()
|
|||||||
!offboard_control_mode.ignore_velocity ||
|
!offboard_control_mode.ignore_velocity ||
|
||||||
!offboard_control_mode.ignore_acceleration_force;
|
!offboard_control_mode.ignore_acceleration_force;
|
||||||
|
|
||||||
control_mode.flag_control_velocity_enabled = !offboard_control_mode.ignore_velocity ||
|
control_mode.flag_control_velocity_enabled = (!offboard_control_mode.ignore_velocity ||
|
||||||
!offboard_control_mode.ignore_position;
|
!offboard_control_mode.ignore_position) && !vtol_status.vtol_in_trans_mode;
|
||||||
|
|
||||||
control_mode.flag_control_climb_rate_enabled = !offboard_control_mode.ignore_velocity ||
|
control_mode.flag_control_climb_rate_enabled = !offboard_control_mode.ignore_velocity ||
|
||||||
!offboard_control_mode.ignore_position;
|
!offboard_control_mode.ignore_position;
|
||||||
|
|
||||||
control_mode.flag_control_position_enabled = !offboard_control_mode.ignore_position;
|
control_mode.flag_control_position_enabled = !offboard_control_mode.ignore_position && !vtol_status.vtol_in_trans_mode;
|
||||||
|
|
||||||
control_mode.flag_control_altitude_enabled = !offboard_control_mode.ignore_velocity ||
|
control_mode.flag_control_altitude_enabled = !offboard_control_mode.ignore_velocity ||
|
||||||
!offboard_control_mode.ignore_position;
|
!offboard_control_mode.ignore_position;
|
||||||
|
|||||||
@@ -491,6 +491,7 @@ void VtolAttitudeControl::task_main()
|
|||||||
if (_vtol_type->get_mode() == ROTARY_WING) {
|
if (_vtol_type->get_mode() == ROTARY_WING) {
|
||||||
// vehicle is in rotary wing mode
|
// vehicle is in rotary wing mode
|
||||||
_vtol_vehicle_status.vtol_in_rw_mode = true;
|
_vtol_vehicle_status.vtol_in_rw_mode = true;
|
||||||
|
_vtol_vehicle_status.vtol_in_trans_mode = false;
|
||||||
|
|
||||||
// got data from mc attitude controller
|
// got data from mc attitude controller
|
||||||
if (fds[0].revents & POLLIN) {
|
if (fds[0].revents & POLLIN) {
|
||||||
@@ -503,6 +504,7 @@ void VtolAttitudeControl::task_main()
|
|||||||
} else if (_vtol_type->get_mode() == FIXED_WING) {
|
} else if (_vtol_type->get_mode() == FIXED_WING) {
|
||||||
// vehicle is in fw mode
|
// vehicle is in fw mode
|
||||||
_vtol_vehicle_status.vtol_in_rw_mode = false;
|
_vtol_vehicle_status.vtol_in_rw_mode = false;
|
||||||
|
_vtol_vehicle_status.vtol_in_trans_mode = false;
|
||||||
|
|
||||||
// got data from fw attitude controller
|
// got data from fw attitude controller
|
||||||
if (fds[1].revents & POLLIN) {
|
if (fds[1].revents & POLLIN) {
|
||||||
@@ -515,6 +517,8 @@ void VtolAttitudeControl::task_main()
|
|||||||
}
|
}
|
||||||
} else if (_vtol_type->get_mode() == TRANSITION) {
|
} else if (_vtol_type->get_mode() == TRANSITION) {
|
||||||
// vehicle is doing a transition
|
// vehicle is doing a transition
|
||||||
|
_vtol_vehicle_status.vtol_in_trans_mode = true;
|
||||||
|
|
||||||
bool got_new_data = false;
|
bool got_new_data = false;
|
||||||
if (fds[0].revents & POLLIN) {
|
if (fds[0].revents & POLLIN) {
|
||||||
orb_copy(ORB_ID(actuator_controls_virtual_mc), _actuator_inputs_mc, &_actuators_mc_in);
|
orb_copy(ORB_ID(actuator_controls_virtual_mc), _actuator_inputs_mc, &_actuators_mc_in);
|
||||||
|
|||||||
Reference in New Issue
Block a user