mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 09:28:58 +00:00
commander add parameter COM_ARM_MIS_REQ
- arm without mission on by default
This commit is contained in:
@@ -41,12 +41,6 @@
|
||||
*/
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
#include <stdint.h>
|
||||
#include <dirent.h>
|
||||
#include <fcntl.h>
|
||||
#include <string.h>
|
||||
#include <math.h>
|
||||
|
||||
#include <px4_posix.h>
|
||||
@@ -54,18 +48,17 @@
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/differential_pressure.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_accel.h>
|
||||
#include <drivers/drv_device.h>
|
||||
|
||||
#include "state_machine_helper.h"
|
||||
#include "commander_helper.h"
|
||||
#include "PreflightCheck.h"
|
||||
|
||||
#ifndef __PX4_NUTTX
|
||||
#include "DevMgr.hpp"
|
||||
using namespace DriverFramework;
|
||||
@@ -129,7 +122,8 @@ transition_result_t arming_state_transition(struct vehicle_status_s *status,
|
||||
orb_advert_t *mavlink_log_pub, ///< uORB handle for mavlink log
|
||||
status_flags_s *status_flags,
|
||||
float avionics_power_rail_voltage,
|
||||
bool can_arm_without_gps,
|
||||
bool arm_without_gps,
|
||||
bool arm_mission_required,
|
||||
hrt_abstime time_since_boot)
|
||||
{
|
||||
// Double check that our static arrays are still valid
|
||||
@@ -157,7 +151,7 @@ transition_result_t arming_state_transition(struct vehicle_status_s *status,
|
||||
&& status->hil_state == vehicle_status_s::HIL_STATE_OFF) {
|
||||
|
||||
prearm_ret = preflight_check(status, mavlink_log_pub, true /* pre-arm */, false /* force_report */,
|
||||
status_flags, battery, can_arm_without_gps, time_since_boot);
|
||||
status_flags, battery, arm_without_gps, arm_mission_required, time_since_boot);
|
||||
}
|
||||
|
||||
/* re-run the pre-flight check as long as sensors are failing */
|
||||
@@ -168,7 +162,7 @@ transition_result_t arming_state_transition(struct vehicle_status_s *status,
|
||||
|
||||
if (last_preflight_check == 0 || hrt_absolute_time() - last_preflight_check > 1000 * 1000) {
|
||||
prearm_ret = preflight_check(status, mavlink_log_pub, false /* pre-flight */, false /* force_report */,
|
||||
status_flags, battery, can_arm_without_gps, time_since_boot);
|
||||
status_flags, battery, arm_without_gps, arm_mission_required, time_since_boot);
|
||||
status_flags->condition_system_sensors_initialized = (prearm_ret == OK);
|
||||
last_preflight_check = hrt_absolute_time();
|
||||
last_prearm_ret = prearm_ret;
|
||||
@@ -258,7 +252,6 @@ transition_result_t arming_state_transition(struct vehicle_status_s *status,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
} else if (new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY
|
||||
@@ -420,6 +413,17 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
|
||||
break;
|
||||
|
||||
case commander_state_s::MAIN_STATE_AUTO_MISSION:
|
||||
|
||||
/* need global position, home position, and a valid mission */
|
||||
if (status_flags->condition_global_position_valid &&
|
||||
status_flags->condition_home_position_valid &&
|
||||
status_flags->condition_auto_mission_available) {
|
||||
|
||||
ret = TRANSITION_CHANGED;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case commander_state_s::MAIN_STATE_AUTO_RTL:
|
||||
|
||||
/* need global position and home position */
|
||||
@@ -441,8 +445,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
|
||||
|
||||
case commander_state_s::MAIN_STATE_OFFBOARD:
|
||||
|
||||
/* need offboard signal
|
||||
*/
|
||||
/* need offboard signal */
|
||||
if (!status_flags->offboard_control_signal_lost) {
|
||||
|
||||
ret = TRANSITION_CHANGED;
|
||||
@@ -1008,7 +1011,8 @@ void reset_link_loss_globals(struct actuator_armed_s *armed, const bool old_fail
|
||||
}
|
||||
|
||||
int preflight_check(struct vehicle_status_s *status, orb_advert_t *mavlink_log_pub, bool prearm, bool force_report,
|
||||
status_flags_s *status_flags, battery_status_s *battery, bool can_arm_without_gps, hrt_abstime time_since_boot)
|
||||
status_flags_s *status_flags, battery_status_s *battery, bool arm_without_gps, bool arm_mission_required,
|
||||
hrt_abstime time_since_boot)
|
||||
{
|
||||
bool reportFailures = force_report || (!status_flags->condition_system_prearm_error_reported &&
|
||||
status_flags->condition_system_hotplug_timeout);
|
||||
@@ -1023,7 +1027,7 @@ int preflight_check(struct vehicle_status_s *status, orb_advert_t *mavlink_log_p
|
||||
|
||||
bool preflight_ok = Commander::preflightCheck(mavlink_log_pub, true, true, true, true,
|
||||
checkAirspeed, (status->rc_input_mode == vehicle_status_s::RC_IN_MODE_DEFAULT),
|
||||
!can_arm_without_gps, true, status->is_vtol, reportFailures, prearm, time_since_boot);
|
||||
!arm_without_gps, true, status->is_vtol, reportFailures, prearm, time_since_boot);
|
||||
|
||||
if (!status_flags->circuit_breaker_engaged_usb_check && status_flags->usb_connected && prearm) {
|
||||
preflight_ok = false;
|
||||
@@ -1041,6 +1045,19 @@ int preflight_check(struct vehicle_status_s *status, orb_advert_t *mavlink_log_p
|
||||
}
|
||||
}
|
||||
|
||||
// mission required
|
||||
if (arm_mission_required &&
|
||||
(!status_flags->condition_auto_mission_available ||
|
||||
!status_flags->condition_home_position_valid ||
|
||||
!status_flags->condition_global_position_valid)) {
|
||||
|
||||
preflight_ok = false;
|
||||
|
||||
if (reportFailures) {
|
||||
mavlink_log_critical(mavlink_log_pub, "ARMING DENIED: valid mission required");
|
||||
}
|
||||
}
|
||||
|
||||
/* report once, then set the flag */
|
||||
if (reportFailures && !preflight_ok) {
|
||||
status_flags->condition_system_prearm_error_reported = true;
|
||||
|
||||
Reference in New Issue
Block a user