mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 03:49:12 +08:00
commander: remove calibration_enabled
This flag is not used anywhere, it therefore doesn't need to be in vehicle_status.
This commit is contained in:
@@ -65,7 +65,6 @@ uint8 nav_state # set navigation state machine to specified value
|
|||||||
uint8 arming_state # current arming state
|
uint8 arming_state # current arming state
|
||||||
uint8 hil_state # current hil state
|
uint8 hil_state # current hil state
|
||||||
bool failsafe # true if system is in failsafe state
|
bool failsafe # true if system is in failsafe state
|
||||||
bool calibration_enabled # true if current calibrating parts of the system. Also sets the system to ARMING_STATE_INIT.
|
|
||||||
|
|
||||||
uint8 system_type # system type, contains mavlink MAV_TYPE
|
uint8 system_type # system type, contains mavlink MAV_TYPE
|
||||||
uint32 system_id # system id, contains MAVLink's system ID field
|
uint32 system_id # system id, contains MAVLink's system ID field
|
||||||
|
|||||||
@@ -225,6 +225,8 @@ static bool circuit_breaker_engaged_enginefailure_check;
|
|||||||
static bool circuit_breaker_engaged_gpsfailure_check;
|
static bool circuit_breaker_engaged_gpsfailure_check;
|
||||||
static bool cb_usb;
|
static bool cb_usb;
|
||||||
|
|
||||||
|
static bool calibration_enabled = false;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* 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
|
||||||
@@ -2047,7 +2049,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||||||
}
|
}
|
||||||
|
|
||||||
/* If in INIT state, try to proceed to STANDBY state */
|
/* If in INIT state, try to proceed to STANDBY state */
|
||||||
if (!status.calibration_enabled && status.arming_state == vehicle_status_s::ARMING_STATE_INIT) {
|
if (!calibration_enabled && status.arming_state == vehicle_status_s::ARMING_STATE_INIT) {
|
||||||
arming_ret = arming_state_transition(&status,
|
arming_ret = arming_state_transition(&status,
|
||||||
&safety,
|
&safety,
|
||||||
vehicle_status_s::ARMING_STATE_STANDBY,
|
vehicle_status_s::ARMING_STATE_STANDBY,
|
||||||
@@ -3548,7 +3550,7 @@ void *commander_low_prio_loop(void *arg)
|
|||||||
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_DENIED, command_ack_pub, command_ack);
|
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_DENIED, command_ack_pub, command_ack);
|
||||||
break;
|
break;
|
||||||
} else {
|
} else {
|
||||||
status.calibration_enabled = true;
|
calibration_enabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((int)(cmd.param1) == 1) {
|
if ((int)(cmd.param1) == 1) {
|
||||||
@@ -3609,7 +3611,7 @@ void *commander_low_prio_loop(void *arg)
|
|||||||
calib_ret = OK;
|
calib_ret = OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
status.calibration_enabled = false;
|
calibration_enabled = false;
|
||||||
|
|
||||||
if (calib_ret == OK) {
|
if (calib_ret == OK) {
|
||||||
tune_positive(true);
|
tune_positive(true);
|
||||||
|
|||||||
Reference in New Issue
Block a user