forked from Archive/PX4-Autopilot
commit
a7e1ba9a00
|
@ -205,10 +205,13 @@ ORB_DECLARE(output_pwm);
|
|||
#define PWM_SERVO_GET_DISABLE_LOCKDOWN _IOC(_PWM_SERVO_BASE, 22)
|
||||
|
||||
/** force safety switch off (to disable use of safety switch) */
|
||||
#define PWM_SERVO_SET_FORCE_SAFETY_OFF _IOC(_PWM_SERVO_BASE, 23)
|
||||
#define PWM_SERVO_SET_FORCE_SAFETY_OFF _IOC(_PWM_SERVO_BASE, 23)
|
||||
|
||||
/** force failsafe mode (failsafe values are set immediately even if failsafe condition not met) */
|
||||
#define PWM_SERVO_SET_FORCE_FAILSAFE _IOC(_PWM_SERVO_BASE, 24)
|
||||
#define PWM_SERVO_SET_FORCE_FAILSAFE _IOC(_PWM_SERVO_BASE, 24)
|
||||
|
||||
/** make failsafe non-recoverable (termination) if it occurs */
|
||||
#define PWM_SERVO_SET_TERMINATION_FAILSAFE _IOC(_PWM_SERVO_BASE, 25)
|
||||
|
||||
/*
|
||||
*
|
||||
|
|
|
@ -1169,12 +1169,21 @@ PX4IO::io_set_arming_state()
|
|||
clear |= PX4IO_P_SETUP_ARMING_LOCKDOWN;
|
||||
}
|
||||
|
||||
if (armed.force_failsafe) {
|
||||
/* Do not set failsafe if circuit breaker is enabled */
|
||||
if (armed.force_failsafe && !circuit_breaker_enabled("CBRK_FLIGHTTERM", CBRK_FLIGHTTERM_KEY)) {
|
||||
set |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
|
||||
} else {
|
||||
clear |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
|
||||
}
|
||||
|
||||
// XXX this is for future support in the commander
|
||||
// but can be removed if unneeded
|
||||
// if (armed.termination_failsafe) {
|
||||
// set |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
|
||||
// } else {
|
||||
// clear |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
|
||||
// }
|
||||
|
||||
if (armed.ready_to_arm) {
|
||||
set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
|
||||
|
||||
|
@ -2038,7 +2047,8 @@ PX4IO::print_status(bool extended_status)
|
|||
((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) ? " INAIR_RESTART_OK" : ""),
|
||||
((arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE) ? " ALWAYS_PWM_ENABLE" : ""),
|
||||
((arming & PX4IO_P_SETUP_ARMING_LOCKDOWN) ? " LOCKDOWN" : ""),
|
||||
((arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE) ? " FORCE_FAILSAFE" : "")
|
||||
((arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE) ? " FORCE_FAILSAFE" : ""),
|
||||
((arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE) ? " TERM_FAILSAFE" : "")
|
||||
);
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||
printf("rates 0x%04x default %u alt %u relays 0x%04x\n",
|
||||
|
@ -2262,6 +2272,17 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
|
|||
}
|
||||
break;
|
||||
|
||||
case PWM_SERVO_SET_TERMINATION_FAILSAFE:
|
||||
/* if failsafe occurs, do not allow the system to recover */
|
||||
if (arg == 0) {
|
||||
/* clear termination failsafe flag */
|
||||
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE, 0);
|
||||
} else {
|
||||
/* set termination failsafe flag */
|
||||
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE);
|
||||
}
|
||||
break;
|
||||
|
||||
case DSM_BIND_START:
|
||||
|
||||
/* only allow DSM2, DSM-X and DSM-X with more than 7 channels */
|
||||
|
|
|
@ -128,8 +128,6 @@ extern struct system_load_s system_load;
|
|||
|
||||
#define POSITION_TIMEOUT (2 * 1000 * 1000) /**< consider the local or global position estimate invalid after 600ms */
|
||||
#define FAILSAFE_DEFAULT_TIMEOUT (3 * 1000 * 1000) /**< hysteresis time - the failsafe will trigger after 3 seconds in this state */
|
||||
#define RC_TIMEOUT 500000
|
||||
#define DL_TIMEOUT (10 * 1000 * 1000)
|
||||
#define OFFBOARD_TIMEOUT 500000
|
||||
#define DIFFPRESS_TIMEOUT 2000000
|
||||
|
||||
|
@ -555,10 +553,35 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
|
|||
if (cmd->param1 > 0.5f) {
|
||||
//XXX update state machine?
|
||||
armed_local->force_failsafe = true;
|
||||
warnx("forcing failsafe");
|
||||
warnx("forcing failsafe (termination)");
|
||||
} else {
|
||||
armed_local->force_failsafe = false;
|
||||
warnx("disabling failsafe");
|
||||
warnx("disabling failsafe (termination)");
|
||||
}
|
||||
/* param2 is currently used for other failsafe modes */
|
||||
status_local->engine_failure_cmd = false;
|
||||
status_local->data_link_lost_cmd = false;
|
||||
status_local->gps_failure_cmd = false;
|
||||
status_local->rc_signal_lost_cmd = false;
|
||||
if ((int)cmd->param2 <= 0) {
|
||||
/* reset all commanded failure modes */
|
||||
warnx("reset all non-flighttermination failsafe commands");
|
||||
} else if ((int)cmd->param2 == 1) {
|
||||
/* trigger engine failure mode */
|
||||
status_local->engine_failure_cmd = true;
|
||||
warnx("engine failure mode commanded");
|
||||
} else if ((int)cmd->param2 == 2) {
|
||||
/* trigger data link loss mode */
|
||||
status_local->data_link_lost_cmd = true;
|
||||
warnx("data link loss mode commanded");
|
||||
} else if ((int)cmd->param2 == 3) {
|
||||
/* trigger gps loss mode */
|
||||
status_local->gps_failure_cmd = true;
|
||||
warnx("gps loss mode commanded");
|
||||
} else if ((int)cmd->param2 == 4) {
|
||||
/* trigger rc loss mode */
|
||||
status_local->rc_signal_lost_cmd = true;
|
||||
warnx("rc loss mode commanded");
|
||||
}
|
||||
cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
|
||||
}
|
||||
|
@ -659,6 +682,12 @@ int commander_thread_main(int argc, char *argv[])
|
|||
param_t _param_takeoff_alt = param_find("NAV_TAKEOFF_ALT");
|
||||
param_t _param_enable_parachute = param_find("NAV_PARACHUTE_EN");
|
||||
param_t _param_enable_datalink_loss = param_find("COM_DL_LOSS_EN");
|
||||
param_t _param_datalink_loss_timeout = param_find("COM_DL_LOSS_T");
|
||||
param_t _param_rc_loss_timeout = param_find("COM_RC_LOSS_T");
|
||||
param_t _param_datalink_regain_timeout = param_find("COM_DL_REG_T");
|
||||
param_t _param_ef_throttle_thres = param_find("COM_EF_THROT");
|
||||
param_t _param_ef_current2throttle_thres = param_find("COM_EF_C2T");
|
||||
param_t _param_ef_time_thres = param_find("COM_EF_TIME");
|
||||
|
||||
/* welcome user */
|
||||
warnx("starting");
|
||||
|
@ -851,11 +880,13 @@ int commander_thread_main(int argc, char *argv[])
|
|||
/* Subscribe to telemetry status topics */
|
||||
int telemetry_subs[TELEMETRY_STATUS_ORB_ID_NUM];
|
||||
uint64_t telemetry_last_heartbeat[TELEMETRY_STATUS_ORB_ID_NUM];
|
||||
uint64_t telemetry_last_dl_loss[TELEMETRY_STATUS_ORB_ID_NUM];
|
||||
bool telemetry_lost[TELEMETRY_STATUS_ORB_ID_NUM];
|
||||
|
||||
for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
|
||||
telemetry_subs[i] = orb_subscribe(telemetry_status_orb_id[i]);
|
||||
telemetry_last_heartbeat[i] = 0;
|
||||
telemetry_last_dl_loss[i] = 0;
|
||||
telemetry_lost[i] = true;
|
||||
}
|
||||
|
||||
|
@ -941,7 +972,16 @@ int commander_thread_main(int argc, char *argv[])
|
|||
transition_result_t arming_ret;
|
||||
|
||||
int32_t datalink_loss_enabled = false;
|
||||
int32_t datalink_loss_timeout = 10;
|
||||
float rc_loss_timeout = 0.5;
|
||||
int32_t datalink_regain_timeout = 0;
|
||||
|
||||
/* Thresholds for engine failure detection */
|
||||
int32_t ef_throttle_thres = 1.0f;
|
||||
int32_t ef_current2throttle_thres = 0.0f;
|
||||
int32_t ef_time_thres = 1000.0f;
|
||||
uint64_t timestamp_engine_healthy = 0; /**< absolute time when engine
|
||||
was healty*/
|
||||
/* check which state machines for changes, clear "changed" flag */
|
||||
bool arming_state_changed = false;
|
||||
bool main_state_changed = false;
|
||||
|
@ -1001,6 +1041,12 @@ int commander_thread_main(int argc, char *argv[])
|
|||
param_get(_param_takeoff_alt, &takeoff_alt);
|
||||
param_get(_param_enable_parachute, ¶chute_enabled);
|
||||
param_get(_param_enable_datalink_loss, &datalink_loss_enabled);
|
||||
param_get(_param_datalink_loss_timeout, &datalink_loss_timeout);
|
||||
param_get(_param_rc_loss_timeout, &rc_loss_timeout);
|
||||
param_get(_param_datalink_regain_timeout, &datalink_regain_timeout);
|
||||
param_get(_param_ef_throttle_thres, &ef_throttle_thres);
|
||||
param_get(_param_ef_current2throttle_thres, &ef_current2throttle_thres);
|
||||
param_get(_param_ef_time_thres, &ef_time_thres);
|
||||
}
|
||||
|
||||
orb_check(sp_man_sub, &updated);
|
||||
|
@ -1041,7 +1087,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
if (mavlink_fd &&
|
||||
telemetry_last_heartbeat[i] == 0 &&
|
||||
telemetry.heartbeat_time > 0 &&
|
||||
hrt_elapsed_time(&telemetry.heartbeat_time) < DL_TIMEOUT) {
|
||||
hrt_elapsed_time(&telemetry.heartbeat_time) < datalink_loss_timeout * 1e6) {
|
||||
|
||||
(void)rc_calibration_check(mavlink_fd);
|
||||
}
|
||||
|
@ -1054,6 +1100,25 @@ int commander_thread_main(int argc, char *argv[])
|
|||
|
||||
if (updated) {
|
||||
orb_copy(ORB_ID(sensor_combined), sensor_sub, &sensors);
|
||||
/* Check if the barometer is healthy and issue a warning in the GCS if not so.
|
||||
* Because the barometer is used for calculating AMSL altitude which is used to ensure
|
||||
* vertical separation from other airtraffic the operator has to know when the
|
||||
* barometer is inoperational.
|
||||
* */
|
||||
if (hrt_elapsed_time(&sensors.baro_timestamp) < FAILSAFE_DEFAULT_TIMEOUT) {
|
||||
/* handle the case where baro was regained */
|
||||
if (status.barometer_failure) {
|
||||
status.barometer_failure = false;
|
||||
status_changed = true;
|
||||
mavlink_log_critical(mavlink_fd, "baro healthy");
|
||||
}
|
||||
} else {
|
||||
if (!status.barometer_failure) {
|
||||
status.barometer_failure = true;
|
||||
status_changed = true;
|
||||
mavlink_log_critical(mavlink_fd, "baro failed");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
orb_check(diff_pres_sub, &updated);
|
||||
|
@ -1141,6 +1206,22 @@ int commander_thread_main(int argc, char *argv[])
|
|||
check_valid(global_position.timestamp, POSITION_TIMEOUT, eph_good, &(status.condition_global_position_valid), &status_changed);
|
||||
|
||||
/* check if GPS fix is ok */
|
||||
if (gps_position.fix_type >= 3 && //XXX check eph and epv ?
|
||||
hrt_elapsed_time(&gps_position.timestamp_position) < FAILSAFE_DEFAULT_TIMEOUT) {
|
||||
/* handle the case where gps was regained */
|
||||
if (status.gps_failure) {
|
||||
status.gps_failure = false;
|
||||
status_changed = true;
|
||||
mavlink_log_critical(mavlink_fd, "gps regained");
|
||||
}
|
||||
} else {
|
||||
if (!status.gps_failure) {
|
||||
status.gps_failure = true;
|
||||
status_changed = true;
|
||||
mavlink_log_critical(mavlink_fd, "gps fix lost");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* update home position */
|
||||
if (!status.condition_home_position_valid && status.condition_global_position_valid && !armed.armed &&
|
||||
|
@ -1358,10 +1439,24 @@ int commander_thread_main(int argc, char *argv[])
|
|||
|
||||
if (updated) {
|
||||
orb_copy(ORB_ID(mission_result), mission_result_sub, &mission_result);
|
||||
|
||||
/* Check for geofence violation */
|
||||
if (armed.armed && (mission_result.geofence_violated || mission_result.flight_termination)) {
|
||||
//XXX: make this configurable to select different actions (e.g. navigation modes)
|
||||
/* this will only trigger if geofence is activated via param and a geofence file is present, also there is a circuit breaker to disable the actual flight termination in the px4io driver */
|
||||
armed.force_failsafe = true;
|
||||
status_changed = true;
|
||||
static bool flight_termination_printed = false;
|
||||
if (!flight_termination_printed) {
|
||||
warnx("Flight termination because of navigator request or geofence");
|
||||
flight_termination_printed = true;
|
||||
}
|
||||
} // no reset is done here on purpose, on geofence violation we want to stay in flighttermination
|
||||
}
|
||||
|
||||
/* RC input check */
|
||||
if (!status.rc_input_blocked && sp_man.timestamp != 0 && hrt_absolute_time() < sp_man.timestamp + RC_TIMEOUT) {
|
||||
if (!status.rc_input_blocked && sp_man.timestamp != 0 &&
|
||||
hrt_absolute_time() < sp_man.timestamp + (uint64_t)(rc_loss_timeout * 1e6f)) {
|
||||
/* handle the case where RC signal was regained */
|
||||
if (!status.rc_signal_found_once) {
|
||||
status.rc_signal_found_once = true;
|
||||
|
@ -1472,15 +1567,25 @@ int commander_thread_main(int argc, char *argv[])
|
|||
/* data links check */
|
||||
bool have_link = false;
|
||||
for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
|
||||
if (telemetry_last_heartbeat[i] != 0 && hrt_elapsed_time(&telemetry_last_heartbeat[i]) < DL_TIMEOUT) {
|
||||
/* handle the case where data link was regained */
|
||||
if (telemetry_lost[i]) {
|
||||
if (telemetry_last_heartbeat[i] != 0 &&
|
||||
hrt_elapsed_time(&telemetry_last_heartbeat[i]) < datalink_loss_timeout * 1e6) {
|
||||
/* handle the case where data link was regained,
|
||||
* accept datalink as healthy only after datalink_regain_timeout seconds
|
||||
* */
|
||||
if (telemetry_lost[i] &&
|
||||
hrt_elapsed_time(&telemetry_last_dl_loss[i]) > datalink_regain_timeout * 1e6) {
|
||||
|
||||
mavlink_log_critical(mavlink_fd, "data link %i regained", i);
|
||||
telemetry_lost[i] = false;
|
||||
have_link = true;
|
||||
} else if (!telemetry_lost[i]) {
|
||||
/* telemetry was healthy also in last iteration
|
||||
* we don't have to check a timeout */
|
||||
have_link = true;
|
||||
}
|
||||
have_link = true;
|
||||
|
||||
} else {
|
||||
telemetry_last_dl_loss[i] = hrt_absolute_time();
|
||||
if (!telemetry_lost[i]) {
|
||||
mavlink_log_critical(mavlink_fd, "data link %i lost", i);
|
||||
telemetry_lost[i] = true;
|
||||
|
@ -1499,10 +1604,40 @@ int commander_thread_main(int argc, char *argv[])
|
|||
if (!status.data_link_lost) {
|
||||
mavlink_log_critical(mavlink_fd, "ALL DATA LINKS LOST");
|
||||
status.data_link_lost = true;
|
||||
status.data_link_lost_counter++;
|
||||
status_changed = true;
|
||||
}
|
||||
}
|
||||
|
||||
/* Check engine failure
|
||||
* only for fixed wing for now
|
||||
*/
|
||||
if (!circuit_breaker_enabled("CBRK_ENGINEFAIL", CBRK_ENGINEFAIL_KEY) &&
|
||||
status.is_rotary_wing == false &&
|
||||
armed.armed &&
|
||||
((actuator_controls.control[3] > ef_throttle_thres &&
|
||||
battery.current_a/actuator_controls.control[3] <
|
||||
ef_current2throttle_thres) ||
|
||||
(status.engine_failure))) {
|
||||
/* potential failure, measure time */
|
||||
if (timestamp_engine_healthy > 0 &&
|
||||
hrt_elapsed_time(×tamp_engine_healthy) >
|
||||
ef_time_thres * 1e6 &&
|
||||
!status.engine_failure) {
|
||||
status.engine_failure = true;
|
||||
status_changed = true;
|
||||
mavlink_log_critical(mavlink_fd, "Engine Failure");
|
||||
}
|
||||
} else {
|
||||
/* no failure reset flag */
|
||||
timestamp_engine_healthy = hrt_absolute_time();
|
||||
if (status.engine_failure) {
|
||||
status.engine_failure = false;
|
||||
status_changed = true;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* handle commands last, as the system needs to be updated to handle them */
|
||||
orb_check(cmd_sub, &updated);
|
||||
|
||||
|
@ -1516,6 +1651,53 @@ int commander_thread_main(int argc, char *argv[])
|
|||
}
|
||||
}
|
||||
|
||||
/* Check for failure combinations which lead to flight termination */
|
||||
if (armed.armed) {
|
||||
/* At this point the data link and the gps system have been checked
|
||||
* If we are not in a manual (RC stick controlled mode)
|
||||
* and both failed we want to terminate the flight */
|
||||
if (status.main_state != MAIN_STATE_MANUAL &&
|
||||
status.main_state != MAIN_STATE_ACRO &&
|
||||
status.main_state != MAIN_STATE_ALTCTL &&
|
||||
status.main_state != MAIN_STATE_POSCTL &&
|
||||
((status.data_link_lost && status.gps_failure) ||
|
||||
(status.data_link_lost_cmd && status.gps_failure_cmd))) {
|
||||
armed.force_failsafe = true;
|
||||
status_changed = true;
|
||||
static bool flight_termination_printed = false;
|
||||
if (!flight_termination_printed) {
|
||||
warnx("Flight termination because of data link loss && gps failure");
|
||||
mavlink_log_critical(mavlink_fd, "DL and GPS lost: flight termination");
|
||||
flight_termination_printed = true;
|
||||
}
|
||||
if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0 ) {
|
||||
mavlink_log_critical(mavlink_fd, "DL and GPS lost: flight termination");
|
||||
}
|
||||
}
|
||||
|
||||
/* At this point the rc signal and the gps system have been checked
|
||||
* If we are in manual (controlled with RC):
|
||||
* if both failed we want to terminate the flight */
|
||||
if ((status.main_state == MAIN_STATE_ACRO ||
|
||||
status.main_state == MAIN_STATE_MANUAL ||
|
||||
status.main_state == MAIN_STATE_ALTCTL ||
|
||||
status.main_state == MAIN_STATE_POSCTL) &&
|
||||
((status.rc_signal_lost && status.gps_failure) ||
|
||||
(status.rc_signal_lost_cmd && status.gps_failure_cmd))) {
|
||||
armed.force_failsafe = true;
|
||||
status_changed = true;
|
||||
static bool flight_termination_printed = false;
|
||||
if (!flight_termination_printed) {
|
||||
warnx("Flight termination because of RC signal loss && gps failure");
|
||||
flight_termination_printed = true;
|
||||
}
|
||||
if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0 ) {
|
||||
mavlink_log_critical(mavlink_fd, "RC and GPS lost: flight termination");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
hrt_abstime t1 = hrt_absolute_time();
|
||||
|
||||
/* print new state */
|
||||
|
@ -1557,7 +1739,8 @@ int commander_thread_main(int argc, char *argv[])
|
|||
|
||||
/* now set navigation state according to failsafe and main state */
|
||||
bool nav_state_changed = set_nav_state(&status, (bool)datalink_loss_enabled,
|
||||
mission_result.finished);
|
||||
mission_result.finished,
|
||||
mission_result.stay_in_failsafe);
|
||||
|
||||
// TODO handle mode changes by commands
|
||||
if (main_state_changed) {
|
||||
|
@ -1997,6 +2180,7 @@ set_control_mode()
|
|||
case NAVIGATION_STATE_AUTO_LOITER:
|
||||
case NAVIGATION_STATE_AUTO_RTL:
|
||||
case NAVIGATION_STATE_AUTO_RTGS:
|
||||
case NAVIGATION_STATE_AUTO_LANDENGFAIL:
|
||||
control_mode.flag_control_manual_enabled = false;
|
||||
control_mode.flag_control_auto_enabled = true;
|
||||
control_mode.flag_control_rates_enabled = true;
|
||||
|
@ -2008,6 +2192,18 @@ set_control_mode()
|
|||
control_mode.flag_control_termination_enabled = false;
|
||||
break;
|
||||
|
||||
case NAVIGATION_STATE_AUTO_LANDGPSFAIL:
|
||||
control_mode.flag_control_manual_enabled = false;
|
||||
control_mode.flag_control_auto_enabled = false;
|
||||
control_mode.flag_control_rates_enabled = true;
|
||||
control_mode.flag_control_attitude_enabled = true;
|
||||
control_mode.flag_control_altitude_enabled = false;
|
||||
control_mode.flag_control_climb_rate_enabled = true;
|
||||
control_mode.flag_control_position_enabled = false;
|
||||
control_mode.flag_control_velocity_enabled = false;
|
||||
control_mode.flag_control_termination_enabled = false;
|
||||
break;
|
||||
|
||||
case NAVIGATION_STATE_LAND:
|
||||
control_mode.flag_control_manual_enabled = false;
|
||||
control_mode.flag_control_auto_enabled = true;
|
||||
|
|
|
@ -105,3 +105,69 @@ PARAM_DEFINE_FLOAT(BAT_CAPACITY, -1.0f);
|
|||
* @max 1
|
||||
*/
|
||||
PARAM_DEFINE_INT32(COM_DL_LOSS_EN, 0);
|
||||
|
||||
/** Datalink loss time threshold
|
||||
*
|
||||
* After this amount of seconds without datalink the data link lost mode triggers
|
||||
*
|
||||
* @group commander
|
||||
* @unit second
|
||||
* @min 0
|
||||
* @max 30
|
||||
*/
|
||||
PARAM_DEFINE_INT32(COM_DL_LOSS_T, 10);
|
||||
|
||||
/** Datalink regain time threshold
|
||||
*
|
||||
* After a data link loss: after this this amount of seconds with a healthy datalink the 'datalink loss'
|
||||
* flag is set back to false
|
||||
*
|
||||
* @group commander
|
||||
* @unit second
|
||||
* @min 0
|
||||
* @max 30
|
||||
*/
|
||||
PARAM_DEFINE_INT32(COM_DL_REG_T, 0);
|
||||
|
||||
/** Engine Failure Throttle Threshold
|
||||
*
|
||||
* Engine failure triggers only above this throttle value
|
||||
*
|
||||
* @group commander
|
||||
* @min 0.0f
|
||||
* @max 1.0f
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(COM_EF_THROT, 0.5f);
|
||||
|
||||
/** Engine Failure Current/Throttle Threshold
|
||||
*
|
||||
* Engine failure triggers only below this current/throttle value
|
||||
*
|
||||
* @group commander
|
||||
* @min 0.0f
|
||||
* @max 7.0f
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(COM_EF_C2T, 5.0f);
|
||||
|
||||
/** Engine Failure Time Threshold
|
||||
*
|
||||
* Engine failure triggers only if the throttle threshold and the
|
||||
* current to throttle threshold are violated for this time
|
||||
*
|
||||
* @group commander
|
||||
* @unit second
|
||||
* @min 0.0f
|
||||
* @max 7.0f
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(COM_EF_TIME, 5.0f);
|
||||
|
||||
/** RC loss time threshold
|
||||
*
|
||||
* After this amount of seconds without RC connection the rc lost flag is set to true
|
||||
*
|
||||
* @group commander
|
||||
* @unit second
|
||||
* @min 0
|
||||
* @max 35
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(COM_RC_LOSS_T, 0.5);
|
||||
|
|
|
@ -443,7 +443,8 @@ transition_result_t hil_state_transition(hil_state_t new_state, int status_pub,
|
|||
/**
|
||||
* Check failsafe and main status and set navigation status for navigator accordingly
|
||||
*/
|
||||
bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished)
|
||||
bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished,
|
||||
const bool stay_in_failsafe)
|
||||
{
|
||||
navigation_state_t nav_state_old = status->nav_state;
|
||||
|
||||
|
@ -457,11 +458,11 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
|
|||
case MAIN_STATE_ALTCTL:
|
||||
case MAIN_STATE_POSCTL:
|
||||
/* require RC for all manual modes */
|
||||
if (status->rc_signal_lost && armed) {
|
||||
if ((status->rc_signal_lost || status->rc_signal_lost_cmd) && armed) {
|
||||
status->failsafe = true;
|
||||
|
||||
if (status->condition_global_position_valid && status->condition_home_position_valid) {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_RTL;
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_RCRECOVER;
|
||||
} else if (status->condition_local_position_valid) {
|
||||
status->nav_state = NAVIGATION_STATE_LAND;
|
||||
} else if (status->condition_local_altitude_valid) {
|
||||
|
@ -497,14 +498,29 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
|
|||
|
||||
case MAIN_STATE_AUTO_MISSION:
|
||||
/* go into failsafe
|
||||
* - if commanded to do so
|
||||
* - if we have an engine failure
|
||||
* - if either the datalink is enabled and lost as well as RC is lost
|
||||
* - if there is no datalink and the mission is finished */
|
||||
if (((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) ||
|
||||
if (status->engine_failure_cmd) {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_LANDENGFAIL;
|
||||
} else if (status->data_link_lost_cmd) {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
|
||||
} else if (status->gps_failure_cmd) {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_LANDGPSFAIL;
|
||||
} else if (status->rc_signal_lost_cmd) {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_RTGS; //XXX
|
||||
/* Finished handling commands which have priority , now handle failures */
|
||||
} else if (status->gps_failure) {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_LANDGPSFAIL;
|
||||
} else if (status->engine_failure) {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_LANDENGFAIL;
|
||||
} else if (((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) ||
|
||||
(!data_link_loss_enabled && status->rc_signal_lost && mission_finished)) {
|
||||
status->failsafe = true;
|
||||
|
||||
if (status->condition_global_position_valid && status->condition_home_position_valid) {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_RTL;
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
|
||||
} else if (status->condition_local_position_valid) {
|
||||
status->nav_state = NAVIGATION_STATE_LAND;
|
||||
} else if (status->condition_local_altitude_valid) {
|
||||
|
@ -528,31 +544,20 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
|
|||
}
|
||||
|
||||
/* don't bother if RC is lost and mission is not yet finished */
|
||||
} else if (status->rc_signal_lost) {
|
||||
} else if (status->rc_signal_lost && !stay_in_failsafe) {
|
||||
|
||||
/* this mode is ok, we don't need RC for missions */
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_MISSION;
|
||||
} else {
|
||||
} else if (!stay_in_failsafe){
|
||||
/* everything is perfect */
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_MISSION;
|
||||
}
|
||||
break;
|
||||
|
||||
case MAIN_STATE_AUTO_LOITER:
|
||||
/* go into failsafe if datalink and RC is lost */
|
||||
if ((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) {
|
||||
status->failsafe = true;
|
||||
|
||||
if (status->condition_global_position_valid && status->condition_home_position_valid) {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_RTL;
|
||||
} else if (status->condition_local_position_valid) {
|
||||
status->nav_state = NAVIGATION_STATE_LAND;
|
||||
} else if (status->condition_local_altitude_valid) {
|
||||
status->nav_state = NAVIGATION_STATE_DESCEND;
|
||||
} else {
|
||||
status->nav_state = NAVIGATION_STATE_TERMINATION;
|
||||
}
|
||||
|
||||
/* go into failsafe on a engine failure */
|
||||
if (status->engine_failure) {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_LANDENGFAIL;
|
||||
/* also go into failsafe if just datalink is lost */
|
||||
} else if (status->data_link_lost && data_link_loss_enabled) {
|
||||
status->failsafe = true;
|
||||
|
@ -593,8 +598,12 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
|
|||
break;
|
||||
|
||||
case MAIN_STATE_AUTO_RTL:
|
||||
/* require global position and home */
|
||||
if ((!status->condition_global_position_valid || !status->condition_home_position_valid)) {
|
||||
/* require global position and home, also go into failsafe on an engine failure */
|
||||
|
||||
if (status->engine_failure) {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_LANDENGFAIL;
|
||||
} else if ((!status->condition_global_position_valid ||
|
||||
!status->condition_home_position_valid)) {
|
||||
status->failsafe = true;
|
||||
|
||||
if (status->condition_local_position_valid) {
|
||||
|
|
|
@ -63,7 +63,7 @@ transition_result_t main_state_transition(struct vehicle_status_s *current_state
|
|||
|
||||
transition_result_t hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_state, const int mavlink_fd);
|
||||
|
||||
bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished);
|
||||
bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished, const bool stay_in_failsafe);
|
||||
|
||||
int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd);
|
||||
|
||||
|
|
|
@ -746,7 +746,14 @@ FixedwingAttitudeControl::task_main()
|
|||
float pitch_sp = _parameters.pitchsp_offset_rad;
|
||||
float throttle_sp = 0.0f;
|
||||
|
||||
if (_vcontrol_mode.flag_control_velocity_enabled || _vcontrol_mode.flag_control_position_enabled) {
|
||||
/* Read attitude setpoint from uorb if
|
||||
* - velocity control or position control is enabled (pos controller is running)
|
||||
* - manual control is disabled (another app may send the setpoint, but it should
|
||||
* for sure not be set from the remote control values)
|
||||
*/
|
||||
if (_vcontrol_mode.flag_control_velocity_enabled ||
|
||||
_vcontrol_mode.flag_control_position_enabled ||
|
||||
!_vcontrol_mode.flag_control_manual_enabled) {
|
||||
/* read in attitude setpoint from attitude setpoint uorb topic */
|
||||
roll_sp = _att_sp.roll_body + _parameters.rollsp_offset_rad;
|
||||
pitch_sp = _att_sp.pitch_body + _parameters.pitchsp_offset_rad;
|
||||
|
@ -886,8 +893,12 @@ FixedwingAttitudeControl::task_main()
|
|||
}
|
||||
}
|
||||
|
||||
/* throttle passed through */
|
||||
_actuators.control[3] = (isfinite(throttle_sp)) ? throttle_sp : 0.0f;
|
||||
/* throttle passed through if it is finite and if no engine failure was
|
||||
* detected */
|
||||
_actuators.control[3] = (isfinite(throttle_sp) &&
|
||||
!(_vehicle_status.engine_failure ||
|
||||
_vehicle_status.engine_failure_cmd)) ?
|
||||
throttle_sp : 0.0f;
|
||||
if (!isfinite(throttle_sp)) {
|
||||
if (_debug && loop_counter % 10 == 0) {
|
||||
warnx("throttle_sp %.4f", (double)throttle_sp);
|
||||
|
|
|
@ -141,7 +141,8 @@ private:
|
|||
int _pos_sp_triplet_sub;
|
||||
int _att_sub; /**< vehicle attitude subscription */
|
||||
int _airspeed_sub; /**< airspeed subscription */
|
||||
int _control_mode_sub; /**< vehicle status subscription */
|
||||
int _control_mode_sub; /**< control mode subscription */
|
||||
int _vehicle_status_sub; /**< vehicle status subscription */
|
||||
int _params_sub; /**< notification of parameter updates */
|
||||
int _manual_control_sub; /**< notification of manual control updates */
|
||||
int _sensor_combined_sub; /**< for body frame accelerations */
|
||||
|
@ -156,7 +157,8 @@ private:
|
|||
struct navigation_capabilities_s _nav_capabilities; /**< navigation capabilities */
|
||||
struct manual_control_setpoint_s _manual; /**< r/c channel data */
|
||||
struct airspeed_s _airspeed; /**< airspeed */
|
||||
struct vehicle_control_mode_s _control_mode; /**< vehicle status */
|
||||
struct vehicle_control_mode_s _control_mode; /**< control mode */
|
||||
struct vehicle_status_s _vehicle_status; /**< vehicle status */
|
||||
struct vehicle_global_position_s _global_pos; /**< global vehicle position */
|
||||
struct position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of mission items */
|
||||
struct sensor_combined_s _sensor_combined; /**< for body frame accelerations */
|
||||
|
@ -304,10 +306,15 @@ private:
|
|||
void control_update();
|
||||
|
||||
/**
|
||||
* Check for changes in vehicle status.
|
||||
* Check for changes in control mode
|
||||
*/
|
||||
void vehicle_control_mode_poll();
|
||||
|
||||
/**
|
||||
* Check for changes in vehicle status.
|
||||
*/
|
||||
void vehicle_status_poll();
|
||||
|
||||
/**
|
||||
* Check for airspeed updates.
|
||||
*/
|
||||
|
@ -412,6 +419,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
|
|||
_att_sub(-1),
|
||||
_airspeed_sub(-1),
|
||||
_control_mode_sub(-1),
|
||||
_vehicle_status_sub(-1),
|
||||
_params_sub(-1),
|
||||
_manual_control_sub(-1),
|
||||
_sensor_combined_sub(-1),
|
||||
|
@ -429,6 +437,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
|
|||
_manual(),
|
||||
_airspeed(),
|
||||
_control_mode(),
|
||||
_vehicle_status(),
|
||||
_global_pos(),
|
||||
_pos_sp_triplet(),
|
||||
_sensor_combined(),
|
||||
|
@ -639,16 +648,27 @@ FixedwingPositionControl::parameters_update()
|
|||
void
|
||||
FixedwingPositionControl::vehicle_control_mode_poll()
|
||||
{
|
||||
bool vstatus_updated;
|
||||
bool updated;
|
||||
|
||||
/* Check HIL state if vehicle status has changed */
|
||||
orb_check(_control_mode_sub, &vstatus_updated);
|
||||
orb_check(_control_mode_sub, &updated);
|
||||
|
||||
if (vstatus_updated) {
|
||||
if (updated) {
|
||||
orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
FixedwingPositionControl::vehicle_status_poll()
|
||||
{
|
||||
bool updated;
|
||||
|
||||
orb_check(_vehicle_status_sub, &updated);
|
||||
|
||||
if (updated) {
|
||||
orb_copy(ORB_ID(vehicle_status), _vehicle_status_sub, &_vehicle_status);
|
||||
}
|
||||
}
|
||||
|
||||
bool
|
||||
FixedwingPositionControl::vehicle_airspeed_poll()
|
||||
{
|
||||
|
@ -1210,16 +1230,20 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
|||
}
|
||||
}
|
||||
|
||||
/* Copy thrust and pitch values from tecs
|
||||
* making sure again that the correct thrust is used,
|
||||
* without depending on library calls for safety reasons */
|
||||
if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
|
||||
if (_vehicle_status.engine_failure || _vehicle_status.engine_failure_cmd) {
|
||||
/* Set thrust to 0 to minimize damage */
|
||||
_att_sp.thrust = 0.0f;
|
||||
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
|
||||
launch_detection_state != LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS) {
|
||||
/* making sure again that the correct thrust is used,
|
||||
* without depending on library calls for safety reasons */
|
||||
_att_sp.thrust = launchDetector.getThrottlePreTakeoff();
|
||||
} else {
|
||||
/* Copy thrust and pitch values from tecs */
|
||||
_att_sp.thrust = math::min(_mTecs.getEnabled() ? _mTecs.getThrottleSetpoint() :
|
||||
_tecs.get_throttle_demand(), throttle_max);
|
||||
}
|
||||
else {
|
||||
_att_sp.thrust = math::min(_mTecs.getEnabled() ? _mTecs.getThrottleSetpoint() : _tecs.get_throttle_demand(), throttle_max);
|
||||
}
|
||||
|
||||
/* During a takeoff waypoint while waiting for launch the pitch sp is set
|
||||
* already (not by tecs) */
|
||||
if (!(pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
|
||||
|
@ -1249,13 +1273,16 @@ FixedwingPositionControl::task_main()
|
|||
_att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
||||
_sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
|
||||
_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
|
||||
_vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
|
||||
_airspeed_sub = orb_subscribe(ORB_ID(airspeed));
|
||||
_params_sub = orb_subscribe(ORB_ID(parameter_update));
|
||||
_manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
|
||||
_range_finder_sub = orb_subscribe(ORB_ID(sensor_range_finder));
|
||||
|
||||
/* rate limit vehicle status updates to 5Hz */
|
||||
/* rate limit control mode updates to 5Hz */
|
||||
orb_set_interval(_control_mode_sub, 200);
|
||||
/* rate limit vehicle status updates to 5Hz */
|
||||
orb_set_interval(_vehicle_status_sub, 200);
|
||||
/* rate limit position updates to 50 Hz */
|
||||
orb_set_interval(_global_pos_sub, 20);
|
||||
|
||||
|
@ -1294,9 +1321,12 @@ FixedwingPositionControl::task_main()
|
|||
|
||||
perf_begin(_loop_perf);
|
||||
|
||||
/* check vehicle status for changes to publication state */
|
||||
/* check vehicle control mode for changes to publication state */
|
||||
vehicle_control_mode_poll();
|
||||
|
||||
/* check vehicle status for changes to publication state */
|
||||
vehicle_status_poll();
|
||||
|
||||
/* only update parameters if they changed */
|
||||
if (fds[0].revents & POLLIN) {
|
||||
/* read from param to clear updated flag */
|
||||
|
@ -1408,7 +1438,12 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_
|
|||
flightPathAngle = -asinf(ground_speed(2)/ground_speed_length);
|
||||
}
|
||||
fwPosctrl::LimitOverride limitOverride;
|
||||
if (climbout_mode) {
|
||||
if (_vehicle_status.engine_failure || _vehicle_status.engine_failure_cmd) {
|
||||
/* Force the slow downwards spiral */
|
||||
limitOverride.enablePitchMinOverride(-1.0f);
|
||||
limitOverride.enablePitchMaxOverride(5.0f);
|
||||
|
||||
} else if (climbout_mode) {
|
||||
limitOverride.enablePitchMinOverride(M_RAD_TO_DEG_F * climbout_pitch_min_rad);
|
||||
} else {
|
||||
limitOverride.disablePitchMinOverride();
|
||||
|
@ -1424,7 +1459,13 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_
|
|||
_mTecs.updateAltitudeSpeed(flightPathAngle, altitude, alt_sp, _airspeed.true_airspeed_m_s, v_sp, mode,
|
||||
limitOverride);
|
||||
} else {
|
||||
/* No underspeed protection in landing mode */
|
||||
if (_vehicle_status.engine_failure || _vehicle_status.engine_failure_cmd) {
|
||||
/* Force the slow downwards spiral */
|
||||
pitch_min_rad = M_DEG_TO_RAD_F * -1.0f;
|
||||
pitch_max_rad = M_DEG_TO_RAD_F * 5.0f;
|
||||
}
|
||||
|
||||
/* No underspeed protection in landing mode */
|
||||
_tecs.set_detect_underspeed_enabled(!(mode == TECS_MODE_LAND || mode == TECS_MODE_LAND_THROTTLELIM));
|
||||
|
||||
/* Using tecs library */
|
||||
|
|
|
@ -534,6 +534,8 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg)
|
|||
tstatus.remote_noise = rstatus.remnoise;
|
||||
tstatus.rxerrors = rstatus.rxerrors;
|
||||
tstatus.fixed = rstatus.fixed;
|
||||
tstatus.system_id = msg->sysid;
|
||||
tstatus.component_id = msg->compid;
|
||||
|
||||
if (_telemetry_status_pub < 0) {
|
||||
_telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus);
|
||||
|
|
|
@ -0,0 +1,227 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
/**
|
||||
* @file datalinkloss.cpp
|
||||
* Helper class for Data Link Loss Mode according to the OBC rules
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <math.h>
|
||||
#include <fcntl.h>
|
||||
|
||||
#include <mavlink/mavlink_log.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <geo/geo.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
#include <uORB/topics/home_position.h>
|
||||
|
||||
#include "navigator.h"
|
||||
#include "datalinkloss.h"
|
||||
|
||||
#define DELAY_SIGMA 0.01f
|
||||
|
||||
DataLinkLoss::DataLinkLoss(Navigator *navigator, const char *name) :
|
||||
MissionBlock(navigator, name),
|
||||
_param_commsholdwaittime(this, "CH_T"),
|
||||
_param_commsholdlat(this, "CH_LAT"),
|
||||
_param_commsholdlon(this, "CH_LON"),
|
||||
_param_commsholdalt(this, "CH_ALT"),
|
||||
_param_airfieldhomelat(this, "NAV_AH_LAT", false),
|
||||
_param_airfieldhomelon(this, "NAV_AH_LON", false),
|
||||
_param_airfieldhomealt(this, "NAV_AH_ALT", false),
|
||||
_param_airfieldhomewaittime(this, "AH_T"),
|
||||
_param_numberdatalinklosses(this, "N"),
|
||||
_param_skipcommshold(this, "CHSK"),
|
||||
_dll_state(DLL_STATE_NONE)
|
||||
{
|
||||
/* load initial params */
|
||||
updateParams();
|
||||
/* initial reset */
|
||||
on_inactive();
|
||||
}
|
||||
|
||||
DataLinkLoss::~DataLinkLoss()
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
DataLinkLoss::on_inactive()
|
||||
{
|
||||
/* reset DLL state only if setpoint moved */
|
||||
if (!_navigator->get_can_loiter_at_sp()) {
|
||||
_dll_state = DLL_STATE_NONE;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
DataLinkLoss::on_activation()
|
||||
{
|
||||
_dll_state = DLL_STATE_NONE;
|
||||
updateParams();
|
||||
advance_dll();
|
||||
set_dll_item();
|
||||
}
|
||||
|
||||
void
|
||||
DataLinkLoss::on_active()
|
||||
{
|
||||
if (is_mission_item_reached()) {
|
||||
updateParams();
|
||||
advance_dll();
|
||||
set_dll_item();
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
DataLinkLoss::set_dll_item()
|
||||
{
|
||||
struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
|
||||
|
||||
set_previous_pos_setpoint();
|
||||
_navigator->set_can_loiter_at_sp(false);
|
||||
|
||||
switch (_dll_state) {
|
||||
case DLL_STATE_FLYTOCOMMSHOLDWP: {
|
||||
_mission_item.lat = (double)(_param_commsholdlat.get()) * 1.0e-7;
|
||||
_mission_item.lon = (double)(_param_commsholdlon.get()) * 1.0e-7;
|
||||
_mission_item.altitude_is_relative = false;
|
||||
_mission_item.altitude = _param_commsholdalt.get();
|
||||
_mission_item.yaw = NAN;
|
||||
_mission_item.loiter_radius = _navigator->get_loiter_radius();
|
||||
_mission_item.loiter_direction = 1;
|
||||
_mission_item.nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
|
||||
_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
|
||||
_mission_item.time_inside = _param_commsholdwaittime.get() < 0.0f ? 0.0f : _param_commsholdwaittime.get();
|
||||
_mission_item.pitch_min = 0.0f;
|
||||
_mission_item.autocontinue = true;
|
||||
_mission_item.origin = ORIGIN_ONBOARD;
|
||||
|
||||
_navigator->set_can_loiter_at_sp(true);
|
||||
break;
|
||||
}
|
||||
case DLL_STATE_FLYTOAIRFIELDHOMEWP: {
|
||||
_mission_item.lat = (double)(_param_airfieldhomelat.get()) * 1.0e-7;
|
||||
_mission_item.lon = (double)(_param_airfieldhomelon.get()) * 1.0e-7;
|
||||
_mission_item.altitude_is_relative = false;
|
||||
_mission_item.altitude = _param_airfieldhomealt.get();
|
||||
_mission_item.yaw = NAN;
|
||||
_mission_item.loiter_radius = _navigator->get_loiter_radius();
|
||||
_mission_item.loiter_direction = 1;
|
||||
_mission_item.nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
|
||||
_mission_item.time_inside = _param_airfieldhomewaittime.get() < 0.0f ? 0.0f : _param_airfieldhomewaittime.get();
|
||||
_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
|
||||
_mission_item.pitch_min = 0.0f;
|
||||
_mission_item.autocontinue = true;
|
||||
_mission_item.origin = ORIGIN_ONBOARD;
|
||||
|
||||
_navigator->set_can_loiter_at_sp(true);
|
||||
break;
|
||||
}
|
||||
case DLL_STATE_TERMINATE: {
|
||||
/* Request flight termination from the commander */
|
||||
_navigator->get_mission_result()->flight_termination = true;
|
||||
_navigator->publish_mission_result();
|
||||
warnx("not switched to manual: request flight termination");
|
||||
pos_sp_triplet->previous.valid = false;
|
||||
pos_sp_triplet->current.valid = false;
|
||||
pos_sp_triplet->next.valid = false;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
reset_mission_item_reached();
|
||||
|
||||
/* convert mission item to current position setpoint and make it valid */
|
||||
mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
|
||||
pos_sp_triplet->next.valid = false;
|
||||
|
||||
_navigator->set_position_setpoint_triplet_updated();
|
||||
}
|
||||
|
||||
void
|
||||
DataLinkLoss::advance_dll()
|
||||
{
|
||||
switch (_dll_state) {
|
||||
case DLL_STATE_NONE:
|
||||
/* Check the number of data link losses. If above home fly home directly */
|
||||
/* if number of data link losses limit is not reached fly to comms hold wp */
|
||||
if (_navigator->get_vstatus()->data_link_lost_counter > _param_numberdatalinklosses.get()) {
|
||||
warnx("%d data link losses, limit is %d, fly to airfield home",
|
||||
_navigator->get_vstatus()->data_link_lost_counter, _param_numberdatalinklosses.get());
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: too many DL losses, fly to airfield home");
|
||||
_navigator->get_mission_result()->stay_in_failsafe = true;
|
||||
_navigator->publish_mission_result();
|
||||
_dll_state = DLL_STATE_FLYTOAIRFIELDHOMEWP;
|
||||
} else {
|
||||
if (!_param_skipcommshold.get()) {
|
||||
warnx("fly to comms hold, datalink loss counter: %d", _navigator->get_vstatus()->data_link_lost_counter);
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: fly to comms hold");
|
||||
_dll_state = DLL_STATE_FLYTOCOMMSHOLDWP;
|
||||
} else {
|
||||
/* comms hold wp not active, fly to airfield home directly */
|
||||
warnx("Skipping comms hold wp. Flying directly to airfield home");
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: fly to airfield home, comms hold skipped");
|
||||
_dll_state = DLL_STATE_FLYTOAIRFIELDHOMEWP;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case DLL_STATE_FLYTOCOMMSHOLDWP:
|
||||
warnx("fly to airfield home");
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: fly to airfield home");
|
||||
_dll_state = DLL_STATE_FLYTOAIRFIELDHOMEWP;
|
||||
_navigator->get_mission_result()->stay_in_failsafe = true;
|
||||
_navigator->publish_mission_result();
|
||||
break;
|
||||
case DLL_STATE_FLYTOAIRFIELDHOMEWP:
|
||||
_dll_state = DLL_STATE_TERMINATE;
|
||||
warnx("time is up, state should have been changed manually by now");
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: no manual control, terminating");
|
||||
_navigator->get_mission_result()->stay_in_failsafe = true;
|
||||
_navigator->publish_mission_result();
|
||||
break;
|
||||
case DLL_STATE_TERMINATE:
|
||||
warnx("dll end");
|
||||
_dll_state = DLL_STATE_END;
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
|
@ -0,0 +1,98 @@
|
|||
/***************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
/**
|
||||
* @file datalinkloss.h
|
||||
* Helper class for Data Link Loss Mode acording to the OBC rules
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#ifndef NAVIGATOR_DATALINKLOSS_H
|
||||
#define NAVIGATOR_DATALINKLOSS_H
|
||||
|
||||
#include <controllib/blocks.hpp>
|
||||
#include <controllib/block/BlockParam.hpp>
|
||||
|
||||
#include <uORB/Subscription.hpp>
|
||||
|
||||
#include "navigator_mode.h"
|
||||
#include "mission_block.h"
|
||||
|
||||
class Navigator;
|
||||
|
||||
class DataLinkLoss : public MissionBlock
|
||||
{
|
||||
public:
|
||||
DataLinkLoss(Navigator *navigator, const char *name);
|
||||
|
||||
~DataLinkLoss();
|
||||
|
||||
virtual void on_inactive();
|
||||
|
||||
virtual void on_activation();
|
||||
|
||||
virtual void on_active();
|
||||
|
||||
private:
|
||||
/* Params */
|
||||
control::BlockParamFloat _param_commsholdwaittime;
|
||||
control::BlockParamInt _param_commsholdlat; // * 1e7
|
||||
control::BlockParamInt _param_commsholdlon; // * 1e7
|
||||
control::BlockParamFloat _param_commsholdalt;
|
||||
control::BlockParamInt _param_airfieldhomelat; // * 1e7
|
||||
control::BlockParamInt _param_airfieldhomelon; // * 1e7
|
||||
control::BlockParamFloat _param_airfieldhomealt;
|
||||
control::BlockParamFloat _param_airfieldhomewaittime;
|
||||
control::BlockParamInt _param_numberdatalinklosses;
|
||||
control::BlockParamInt _param_skipcommshold;
|
||||
|
||||
enum DLLState {
|
||||
DLL_STATE_NONE = 0,
|
||||
DLL_STATE_FLYTOCOMMSHOLDWP = 1,
|
||||
DLL_STATE_FLYTOAIRFIELDHOMEWP = 2,
|
||||
DLL_STATE_TERMINATE = 3,
|
||||
DLL_STATE_END = 4
|
||||
} _dll_state;
|
||||
|
||||
/**
|
||||
* Set the DLL item
|
||||
*/
|
||||
void set_dll_item();
|
||||
|
||||
/**
|
||||
* Move to next DLL item
|
||||
*/
|
||||
void advance_dll();
|
||||
|
||||
};
|
||||
#endif
|
|
@ -0,0 +1,126 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file datalinkloss_params.c
|
||||
*
|
||||
* Parameters for DLL
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/*
|
||||
* Data Link Loss parameters, accessible via MAVLink
|
||||
*/
|
||||
|
||||
/**
|
||||
* Comms hold wait time
|
||||
*
|
||||
* The amount of time in seconds the system should wait at the comms hold waypoint
|
||||
*
|
||||
* @unit seconds
|
||||
* @min 0.0
|
||||
* @group DLL
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_DLL_CH_T, 120.0f);
|
||||
|
||||
/**
|
||||
* Comms hold Lat
|
||||
*
|
||||
* Latitude of comms hold waypoint
|
||||
*
|
||||
* @unit degrees * 1e7
|
||||
* @min 0.0
|
||||
* @group DLL
|
||||
*/
|
||||
PARAM_DEFINE_INT32(NAV_DLL_CH_LAT, -266072120);
|
||||
|
||||
/**
|
||||
* Comms hold Lon
|
||||
*
|
||||
* Longitude of comms hold waypoint
|
||||
*
|
||||
* @unit degrees * 1e7
|
||||
* @min 0.0
|
||||
* @group DLL
|
||||
*/
|
||||
PARAM_DEFINE_INT32(NAV_DLL_CH_LON, 1518453890);
|
||||
|
||||
/**
|
||||
* Comms hold alt
|
||||
*
|
||||
* Altitude of comms hold waypoint
|
||||
*
|
||||
* @unit m
|
||||
* @min 0.0
|
||||
* @group DLL
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_DLL_CH_ALT, 600.0f);
|
||||
|
||||
/**
|
||||
* Aifield hole wait time
|
||||
*
|
||||
* The amount of time in seconds the system should wait at the airfield home waypoint
|
||||
*
|
||||
* @unit seconds
|
||||
* @min 0.0
|
||||
* @group DLL
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_DLL_AH_T, 120.0f);
|
||||
|
||||
/**
|
||||
* Number of allowed Datalink timeouts
|
||||
*
|
||||
* After more than this number of data link timeouts the aircraft returns home directly
|
||||
*
|
||||
* @group DLL
|
||||
* @min 0
|
||||
* @max 1000
|
||||
*/
|
||||
PARAM_DEFINE_INT32(NAV_DLL_N, 2);
|
||||
|
||||
/**
|
||||
* Skip comms hold wp
|
||||
*
|
||||
* If set to 1 the system will skip the comms hold wp on data link loss and will directly fly to
|
||||
* airfield home
|
||||
*
|
||||
* @group DLL
|
||||
* @min 0
|
||||
* @max 1
|
||||
*/
|
||||
PARAM_DEFINE_INT32(NAV_DLL_CHSK, 0);
|
|
@ -0,0 +1,149 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* @file enginefailure.cpp
|
||||
* Helper class for a fixedwing engine failure mode
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <math.h>
|
||||
#include <fcntl.h>
|
||||
|
||||
#include <mavlink/mavlink_log.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <geo/geo.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
|
||||
#include "navigator.h"
|
||||
#include "enginefailure.h"
|
||||
|
||||
#define DELAY_SIGMA 0.01f
|
||||
|
||||
EngineFailure::EngineFailure(Navigator *navigator, const char *name) :
|
||||
MissionBlock(navigator, name),
|
||||
_ef_state(EF_STATE_NONE)
|
||||
{
|
||||
/* load initial params */
|
||||
updateParams();
|
||||
/* initial reset */
|
||||
on_inactive();
|
||||
}
|
||||
|
||||
EngineFailure::~EngineFailure()
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
EngineFailure::on_inactive()
|
||||
{
|
||||
_ef_state = EF_STATE_NONE;
|
||||
}
|
||||
|
||||
void
|
||||
EngineFailure::on_activation()
|
||||
{
|
||||
_ef_state = EF_STATE_NONE;
|
||||
advance_ef();
|
||||
set_ef_item();
|
||||
}
|
||||
|
||||
void
|
||||
EngineFailure::on_active()
|
||||
{
|
||||
if (is_mission_item_reached()) {
|
||||
advance_ef();
|
||||
set_ef_item();
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
EngineFailure::set_ef_item()
|
||||
{
|
||||
struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
|
||||
|
||||
/* make sure we have the latest params */
|
||||
updateParams();
|
||||
|
||||
set_previous_pos_setpoint();
|
||||
_navigator->set_can_loiter_at_sp(false);
|
||||
|
||||
switch (_ef_state) {
|
||||
case EF_STATE_LOITERDOWN: {
|
||||
//XXX create mission item at ground (below?) here
|
||||
|
||||
_mission_item.lat = _navigator->get_global_position()->lat;
|
||||
_mission_item.lon = _navigator->get_global_position()->lon;
|
||||
_mission_item.altitude_is_relative = false;
|
||||
//XXX setting altitude to a very low value, evaluate other options
|
||||
_mission_item.altitude = _navigator->get_home_position()->alt - 1000.0f;
|
||||
_mission_item.yaw = NAN;
|
||||
_mission_item.loiter_radius = _navigator->get_loiter_radius();
|
||||
_mission_item.loiter_direction = 1;
|
||||
_mission_item.nav_cmd = NAV_CMD_LOITER_UNLIMITED;
|
||||
_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
|
||||
_mission_item.pitch_min = 0.0f;
|
||||
_mission_item.autocontinue = true;
|
||||
_mission_item.origin = ORIGIN_ONBOARD;
|
||||
|
||||
_navigator->set_can_loiter_at_sp(true);
|
||||
break;
|
||||
}
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
reset_mission_item_reached();
|
||||
|
||||
/* convert mission item to current position setpoint and make it valid */
|
||||
mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
|
||||
pos_sp_triplet->next.valid = false;
|
||||
|
||||
_navigator->set_position_setpoint_triplet_updated();
|
||||
}
|
||||
|
||||
void
|
||||
EngineFailure::advance_ef()
|
||||
{
|
||||
switch (_ef_state) {
|
||||
case EF_STATE_NONE:
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: Engine failure. Loitering down");
|
||||
_ef_state = EF_STATE_LOITERDOWN;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
|
@ -0,0 +1,83 @@
|
|||
/***************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
/**
|
||||
* @file enginefailure.h
|
||||
* Helper class for a fixedwing engine failure mode
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#ifndef NAVIGATOR_ENGINEFAILURE_H
|
||||
#define NAVIGATOR_ENGINEFAILURE_H
|
||||
|
||||
#include <controllib/blocks.hpp>
|
||||
#include <controllib/block/BlockParam.hpp>
|
||||
|
||||
#include <uORB/Subscription.hpp>
|
||||
|
||||
#include "navigator_mode.h"
|
||||
#include "mission_block.h"
|
||||
|
||||
class Navigator;
|
||||
|
||||
class EngineFailure : public MissionBlock
|
||||
{
|
||||
public:
|
||||
EngineFailure(Navigator *navigator, const char *name);
|
||||
|
||||
~EngineFailure();
|
||||
|
||||
virtual void on_inactive();
|
||||
|
||||
virtual void on_activation();
|
||||
|
||||
virtual void on_active();
|
||||
|
||||
private:
|
||||
enum EFState {
|
||||
EF_STATE_NONE = 0,
|
||||
EF_STATE_LOITERDOWN = 1,
|
||||
} _ef_state;
|
||||
|
||||
/**
|
||||
* Set the DLL item
|
||||
*/
|
||||
void set_ef_item();
|
||||
|
||||
/**
|
||||
* Move to next EF item
|
||||
*/
|
||||
void advance_ef();
|
||||
|
||||
};
|
||||
#endif
|
|
@ -48,6 +48,7 @@
|
|||
#include <ctype.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <mavlink/mavlink_log.h>
|
||||
|
||||
|
||||
/* Oddly, ERROR is not defined for C++ */
|
||||
|
@ -62,7 +63,12 @@ Geofence::Geofence() :
|
|||
_altitude_min(0),
|
||||
_altitude_max(0),
|
||||
_verticesCount(0),
|
||||
param_geofence_on(this, "ON")
|
||||
_param_geofence_on(this, "ON"),
|
||||
_param_altitude_mode(this, "ALTMODE"),
|
||||
_param_source(this, "SOURCE"),
|
||||
_param_counter_threshold(this, "COUNT"),
|
||||
_outside_counter(0),
|
||||
_mavlinkFd(-1)
|
||||
{
|
||||
/* Load initial params */
|
||||
updateParams();
|
||||
|
@ -74,27 +80,69 @@ Geofence::~Geofence()
|
|||
}
|
||||
|
||||
|
||||
bool Geofence::inside(const struct vehicle_global_position_s *vehicle)
|
||||
bool Geofence::inside(const struct vehicle_global_position_s &global_position)
|
||||
{
|
||||
double lat = vehicle->lat / 1e7d;
|
||||
double lon = vehicle->lon / 1e7d;
|
||||
//float alt = vehicle->alt;
|
||||
return inside(global_position.lat, global_position.lon, global_position.alt);
|
||||
}
|
||||
|
||||
return inside(lat, lon, vehicle->alt);
|
||||
bool Geofence::inside(const struct vehicle_global_position_s &global_position, float baro_altitude_amsl)
|
||||
{
|
||||
return inside(global_position.lat, global_position.lon, baro_altitude_amsl);
|
||||
}
|
||||
|
||||
|
||||
bool Geofence::inside(const struct vehicle_global_position_s &global_position,
|
||||
const struct vehicle_gps_position_s &gps_position,float baro_altitude_amsl) {
|
||||
updateParams();
|
||||
|
||||
if (getAltitudeMode() == Geofence::GF_ALT_MODE_WGS84) {
|
||||
if (getSource() == Geofence::GF_SOURCE_GLOBALPOS) {
|
||||
return inside(global_position);
|
||||
} else {
|
||||
return inside((double)gps_position.lat * 1.0e-7, (double)gps_position.lon * 1.0e-7,
|
||||
(double)gps_position.alt * 1.0e-3);
|
||||
}
|
||||
} else {
|
||||
if (getSource() == Geofence::GF_SOURCE_GLOBALPOS) {
|
||||
return inside(global_position, baro_altitude_amsl);
|
||||
} else {
|
||||
return inside((double)gps_position.lat * 1.0e-7, (double)gps_position.lon * 1.0e-7,
|
||||
baro_altitude_amsl);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool Geofence::inside(double lat, double lon, float altitude)
|
||||
{
|
||||
bool inside_fence = inside_polygon(lat, lon, altitude);
|
||||
|
||||
if (inside_fence) {
|
||||
_outside_counter = 0;
|
||||
return inside_fence;
|
||||
} {
|
||||
_outside_counter++;
|
||||
if(_outside_counter > _param_counter_threshold.get()) {
|
||||
return inside_fence;
|
||||
} else {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
bool Geofence::inside_polygon(double lat, double lon, float altitude)
|
||||
{
|
||||
/* Return true if geofence is disabled */
|
||||
if (param_geofence_on.get() != 1)
|
||||
if (_param_geofence_on.get() != 1)
|
||||
return true;
|
||||
|
||||
if (valid()) {
|
||||
|
||||
if (!isEmpty()) {
|
||||
/* Vertical check */
|
||||
if (altitude > _altitude_max || altitude < _altitude_min)
|
||||
if (altitude > _altitude_max || altitude < _altitude_min) {
|
||||
return false;
|
||||
}
|
||||
|
||||
/*Horizontal check */
|
||||
/* Adaptation of algorithm originally presented as
|
||||
|
@ -284,8 +332,10 @@ Geofence::loadFromFile(const char *filename)
|
|||
{
|
||||
_verticesCount = pointCounter;
|
||||
warnx("Geofence: imported successfully");
|
||||
mavlink_log_info(_mavlinkFd, "Geofence imported");
|
||||
} else {
|
||||
warnx("Geofence: import error");
|
||||
mavlink_log_critical(_mavlinkFd, "#audio: Geofence import error");
|
||||
}
|
||||
|
||||
return ERROR;
|
||||
|
|
|
@ -42,6 +42,9 @@
|
|||
#define GEOFENCE_H_
|
||||
|
||||
#include <uORB/topics/fence.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
#include <controllib/blocks.hpp>
|
||||
#include <controllib/block/BlockParam.hpp>
|
||||
|
||||
|
@ -49,30 +52,32 @@
|
|||
|
||||
class Geofence : public control::SuperBlock
|
||||
{
|
||||
private:
|
||||
orb_advert_t _fence_pub; /**< publish fence topic */
|
||||
|
||||
float _altitude_min;
|
||||
float _altitude_max;
|
||||
|
||||
unsigned _verticesCount;
|
||||
|
||||
/* Params */
|
||||
control::BlockParamInt param_geofence_on;
|
||||
public:
|
||||
Geofence();
|
||||
~Geofence();
|
||||
|
||||
/* Altitude mode, corresponding to the param GF_ALTMODE */
|
||||
enum {
|
||||
GF_ALT_MODE_WGS84 = 0,
|
||||
GF_ALT_MODE_AMSL = 1
|
||||
};
|
||||
|
||||
/* Source, corresponding to the param GF_SOURCE */
|
||||
enum {
|
||||
GF_SOURCE_GLOBALPOS = 0,
|
||||
GF_SOURCE_GPS = 1
|
||||
};
|
||||
|
||||
/**
|
||||
* Return whether craft is inside geofence.
|
||||
* Return whether system is inside geofence.
|
||||
*
|
||||
* Calculate whether point is inside arbitrary polygon
|
||||
* @param craft pointer craft coordinates
|
||||
* @param fence pointer to array of coordinates, one per vertex. First and last vertex are assumed connected
|
||||
* @return true: craft is inside fence, false:craft is outside fence
|
||||
* @return true: system is inside fence, false: system is outside fence
|
||||
*/
|
||||
bool inside(const struct vehicle_global_position_s *craft);
|
||||
bool inside(double lat, double lon, float altitude);
|
||||
bool inside(const struct vehicle_global_position_s &global_position,
|
||||
const struct vehicle_gps_position_s &gps_position,float baro_altitude_amsl);
|
||||
bool inside_polygon(double lat, double lon, float altitude);
|
||||
|
||||
int clearDm();
|
||||
|
||||
|
@ -88,6 +93,34 @@ public:
|
|||
int loadFromFile(const char *filename);
|
||||
|
||||
bool isEmpty() {return _verticesCount == 0;}
|
||||
|
||||
int getAltitudeMode() { return _param_altitude_mode.get(); }
|
||||
|
||||
int getSource() { return _param_source.get(); }
|
||||
|
||||
void setMavlinkFd(int value) { _mavlinkFd = value; }
|
||||
|
||||
private:
|
||||
orb_advert_t _fence_pub; /**< publish fence topic */
|
||||
|
||||
float _altitude_min;
|
||||
float _altitude_max;
|
||||
|
||||
unsigned _verticesCount;
|
||||
|
||||
/* Params */
|
||||
control::BlockParamInt _param_geofence_on;
|
||||
control::BlockParamInt _param_altitude_mode;
|
||||
control::BlockParamInt _param_source;
|
||||
control::BlockParamInt _param_counter_threshold;
|
||||
|
||||
uint8_t _outside_counter;
|
||||
|
||||
int _mavlinkFd;
|
||||
|
||||
bool inside(double lat, double lon, float altitude);
|
||||
bool inside(const struct vehicle_global_position_s &global_position);
|
||||
bool inside(const struct vehicle_global_position_s &global_position, float baro_altitude_amsl);
|
||||
};
|
||||
|
||||
|
||||
|
|
|
@ -58,3 +58,39 @@
|
|||
* @group Geofence
|
||||
*/
|
||||
PARAM_DEFINE_INT32(GF_ON, 1);
|
||||
|
||||
/**
|
||||
* Geofence altitude mode
|
||||
*
|
||||
* Select which altitude reference should be used
|
||||
* 0 = WGS84, 1 = AMSL
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @group Geofence
|
||||
*/
|
||||
PARAM_DEFINE_INT32(GF_ALTMODE, 0);
|
||||
|
||||
/**
|
||||
* Geofence source
|
||||
*
|
||||
* Select which position source should be used. Selecting GPS instead of global position makes sure that there is
|
||||
* no dependence on the position estimator
|
||||
* 0 = global position, 1 = GPS
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @group Geofence
|
||||
*/
|
||||
PARAM_DEFINE_INT32(GF_SOURCE, 0);
|
||||
|
||||
/**
|
||||
* Geofence counter limit
|
||||
*
|
||||
* Set how many subsequent position measurements outside of the fence are needed before geofence violation is triggered
|
||||
*
|
||||
* @min -1
|
||||
* @max 10
|
||||
* @group Geofence
|
||||
*/
|
||||
PARAM_DEFINE_INT32(GF_COUNT, -1);
|
||||
|
|
|
@ -0,0 +1,178 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
/**
|
||||
* @file gpsfailure.cpp
|
||||
* Helper class for gpsfailure mode according to the OBC rules
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <math.h>
|
||||
#include <fcntl.h>
|
||||
|
||||
#include <mavlink/mavlink_log.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <geo/geo.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
#include <uORB/topics/home_position.h>
|
||||
|
||||
#include "navigator.h"
|
||||
#include "gpsfailure.h"
|
||||
|
||||
#define DELAY_SIGMA 0.01f
|
||||
|
||||
GpsFailure::GpsFailure(Navigator *navigator, const char *name) :
|
||||
MissionBlock(navigator, name),
|
||||
_param_loitertime(this, "LT"),
|
||||
_param_openlooploiter_roll(this, "R"),
|
||||
_param_openlooploiter_pitch(this, "P"),
|
||||
_param_openlooploiter_thrust(this, "TR"),
|
||||
_gpsf_state(GPSF_STATE_NONE),
|
||||
_timestamp_activation(0)
|
||||
{
|
||||
/* load initial params */
|
||||
updateParams();
|
||||
/* initial reset */
|
||||
on_inactive();
|
||||
}
|
||||
|
||||
GpsFailure::~GpsFailure()
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
GpsFailure::on_inactive()
|
||||
{
|
||||
/* reset GPSF state only if setpoint moved */
|
||||
if (!_navigator->get_can_loiter_at_sp()) {
|
||||
_gpsf_state = GPSF_STATE_NONE;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
GpsFailure::on_activation()
|
||||
{
|
||||
_gpsf_state = GPSF_STATE_NONE;
|
||||
_timestamp_activation = hrt_absolute_time();
|
||||
updateParams();
|
||||
advance_gpsf();
|
||||
set_gpsf_item();
|
||||
}
|
||||
|
||||
void
|
||||
GpsFailure::on_active()
|
||||
{
|
||||
|
||||
switch (_gpsf_state) {
|
||||
case GPSF_STATE_LOITER: {
|
||||
/* Position controller does not run in this mode:
|
||||
* navigator has to publish an attitude setpoint */
|
||||
_navigator->get_att_sp()->roll_body = M_DEG_TO_RAD_F * _param_openlooploiter_roll.get();
|
||||
_navigator->get_att_sp()->pitch_body = M_DEG_TO_RAD_F * _param_openlooploiter_pitch.get();
|
||||
_navigator->get_att_sp()->thrust = _param_openlooploiter_thrust.get();
|
||||
_navigator->publish_att_sp();
|
||||
|
||||
/* Measure time */
|
||||
hrt_abstime elapsed = hrt_elapsed_time(&_timestamp_activation);
|
||||
|
||||
//warnx("open loop loiter, posctl enabled %u, elapsed %.1fs, thrust %.2f",
|
||||
//_navigator->get_control_mode()->flag_control_position_enabled, elapsed * 1e-6, (double)_param_openlooploiter_thrust.get());
|
||||
if (elapsed > _param_loitertime.get() * 1e6f) {
|
||||
/* no recovery, adavance the state machine */
|
||||
warnx("gps not recovered, switch to next state");
|
||||
advance_gpsf();
|
||||
}
|
||||
break;
|
||||
}
|
||||
case GPSF_STATE_TERMINATE:
|
||||
set_gpsf_item();
|
||||
advance_gpsf();
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
GpsFailure::set_gpsf_item()
|
||||
{
|
||||
struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
|
||||
|
||||
/* Set pos sp triplet to invalid to stop pos controller */
|
||||
pos_sp_triplet->previous.valid = false;
|
||||
pos_sp_triplet->current.valid = false;
|
||||
pos_sp_triplet->next.valid = false;
|
||||
|
||||
switch (_gpsf_state) {
|
||||
case GPSF_STATE_TERMINATE: {
|
||||
/* Request flight termination from the commander */
|
||||
_navigator->get_mission_result()->flight_termination = true;
|
||||
_navigator->publish_mission_result();
|
||||
warnx("gps fail: request flight termination");
|
||||
}
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
reset_mission_item_reached();
|
||||
_navigator->set_position_setpoint_triplet_updated();
|
||||
}
|
||||
|
||||
void
|
||||
GpsFailure::advance_gpsf()
|
||||
{
|
||||
updateParams();
|
||||
|
||||
switch (_gpsf_state) {
|
||||
case GPSF_STATE_NONE:
|
||||
_gpsf_state = GPSF_STATE_LOITER;
|
||||
warnx("gpsf loiter");
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: open loop loiter");
|
||||
break;
|
||||
case GPSF_STATE_LOITER:
|
||||
_gpsf_state = GPSF_STATE_TERMINATE;
|
||||
warnx("gpsf terminate");
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: no gps recovery, termination");
|
||||
warnx("mavlink sent");
|
||||
break;
|
||||
case GPSF_STATE_TERMINATE:
|
||||
warnx("gpsf end");
|
||||
_gpsf_state = GPSF_STATE_END;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
|
@ -0,0 +1,97 @@
|
|||
/***************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
/**
|
||||
* @file gpsfailure.h
|
||||
* Helper class for Data Link Loss Mode according to the OBC rules
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#ifndef NAVIGATOR_GPSFAILURE_H
|
||||
#define NAVIGATOR_GPSFAILURE_H
|
||||
|
||||
#include <controllib/blocks.hpp>
|
||||
#include <controllib/block/BlockParam.hpp>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/Publication.hpp>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include "navigator_mode.h"
|
||||
#include "mission_block.h"
|
||||
|
||||
class Navigator;
|
||||
|
||||
class GpsFailure : public MissionBlock
|
||||
{
|
||||
public:
|
||||
GpsFailure(Navigator *navigator, const char *name);
|
||||
|
||||
~GpsFailure();
|
||||
|
||||
virtual void on_inactive();
|
||||
|
||||
virtual void on_activation();
|
||||
|
||||
virtual void on_active();
|
||||
|
||||
private:
|
||||
/* Params */
|
||||
control::BlockParamFloat _param_loitertime;
|
||||
control::BlockParamFloat _param_openlooploiter_roll;
|
||||
control::BlockParamFloat _param_openlooploiter_pitch;
|
||||
control::BlockParamFloat _param_openlooploiter_thrust;
|
||||
|
||||
enum GPSFState {
|
||||
GPSF_STATE_NONE = 0,
|
||||
GPSF_STATE_LOITER = 1,
|
||||
GPSF_STATE_TERMINATE = 2,
|
||||
GPSF_STATE_END = 3,
|
||||
} _gpsf_state;
|
||||
|
||||
hrt_abstime _timestamp_activation; //*< timestamp when this mode was activated */
|
||||
|
||||
/**
|
||||
* Set the GPSF item
|
||||
*/
|
||||
void set_gpsf_item();
|
||||
|
||||
/**
|
||||
* Move to next GPSF item
|
||||
*/
|
||||
void advance_gpsf();
|
||||
|
||||
};
|
||||
#endif
|
|
@ -0,0 +1,97 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file gpsfailure_params.c
|
||||
*
|
||||
* Parameters for GPSF navigation mode
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/*
|
||||
* GPS Failure Navigation Mode parameters, accessible via MAVLink
|
||||
*/
|
||||
|
||||
/**
|
||||
* Loiter time
|
||||
*
|
||||
* The amount of time in seconds the system should do open loop loiter and wait for gps recovery
|
||||
* before it goes into flight termination.
|
||||
*
|
||||
* @unit seconds
|
||||
* @min 0.0
|
||||
* @group GPSF
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_GPSF_LT, 30.0f);
|
||||
|
||||
/**
|
||||
* Open loop loiter roll
|
||||
*
|
||||
* Roll in degrees during the open loop loiter
|
||||
*
|
||||
* @unit deg
|
||||
* @min 0.0
|
||||
* @max 30.0
|
||||
* @group GPSF
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_GPSF_R, 15.0f);
|
||||
|
||||
/**
|
||||
* Open loop loiter pitch
|
||||
*
|
||||
* Pitch in degrees during the open loop loiter
|
||||
*
|
||||
* @unit deg
|
||||
* @min -30.0
|
||||
* @max 30.0
|
||||
* @group GPSF
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_GPSF_P, 0.0f);
|
||||
|
||||
/**
|
||||
* Open loop loiter thrust
|
||||
*
|
||||
* Thrust value which is set during the open loop loiter
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @group GPSF
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_GPSF_TR, 0.7f);
|
||||
|
||||
|
|
@ -62,18 +62,16 @@
|
|||
|
||||
Mission::Mission(Navigator *navigator, const char *name) :
|
||||
MissionBlock(navigator, name),
|
||||
_param_onboard_enabled(this, "ONBOARD_EN"),
|
||||
_param_takeoff_alt(this, "TAKEOFF_ALT"),
|
||||
_param_dist_1wp(this, "DIST_1WP"),
|
||||
_param_altmode(this, "ALTMODE"),
|
||||
_param_onboard_enabled(this, "MIS_ONBOARD_EN", false),
|
||||
_param_takeoff_alt(this, "MIS_TAKEOFF_ALT", false),
|
||||
_param_dist_1wp(this, "MIS_DIST_1WP", false),
|
||||
_param_altmode(this, "MIS_ALTMODE", false),
|
||||
_onboard_mission({0}),
|
||||
_offboard_mission({0}),
|
||||
_current_onboard_mission_index(-1),
|
||||
_current_offboard_mission_index(-1),
|
||||
_need_takeoff(true),
|
||||
_takeoff(false),
|
||||
_mission_result_pub(-1),
|
||||
_mission_result({0}),
|
||||
_mission_type(MISSION_TYPE_NONE),
|
||||
_inited(false),
|
||||
_dist_1wp_ok(false),
|
||||
|
@ -671,18 +669,18 @@ void
|
|||
Mission::report_mission_item_reached()
|
||||
{
|
||||
if (_mission_type == MISSION_TYPE_OFFBOARD) {
|
||||
_mission_result.reached = true;
|
||||
_mission_result.seq_reached = _current_offboard_mission_index;
|
||||
_navigator->get_mission_result()->reached = true;
|
||||
_navigator->get_mission_result()->seq_reached = _current_offboard_mission_index;
|
||||
}
|
||||
publish_mission_result();
|
||||
_navigator->publish_mission_result();
|
||||
}
|
||||
|
||||
void
|
||||
Mission::report_current_offboard_mission_item()
|
||||
{
|
||||
warnx("current offboard mission index: %d", _current_offboard_mission_index);
|
||||
_mission_result.seq_current = _current_offboard_mission_index;
|
||||
publish_mission_result();
|
||||
_navigator->get_mission_result()->seq_current = _current_offboard_mission_index;
|
||||
_navigator->publish_mission_result();
|
||||
|
||||
save_offboard_mission_state();
|
||||
}
|
||||
|
@ -690,23 +688,7 @@ Mission::report_current_offboard_mission_item()
|
|||
void
|
||||
Mission::report_mission_finished()
|
||||
{
|
||||
_mission_result.finished = true;
|
||||
publish_mission_result();
|
||||
_navigator->get_mission_result()->finished = true;
|
||||
_navigator->publish_mission_result();
|
||||
}
|
||||
|
||||
void
|
||||
Mission::publish_mission_result()
|
||||
{
|
||||
/* lazily publish the mission result only once available */
|
||||
if (_mission_result_pub > 0) {
|
||||
/* publish mission result */
|
||||
orb_publish(ORB_ID(mission_result), _mission_result_pub, &_mission_result);
|
||||
|
||||
} else {
|
||||
/* advertise and publish */
|
||||
_mission_result_pub = orb_advertise(ORB_ID(mission_result), &_mission_result);
|
||||
}
|
||||
/* reset reached bool */
|
||||
_mission_result.reached = false;
|
||||
_mission_result.finished = false;
|
||||
}
|
||||
|
|
|
@ -144,11 +144,6 @@ private:
|
|||
*/
|
||||
void report_mission_finished();
|
||||
|
||||
/**
|
||||
* Publish the mission result so commander and mavlink know what is going on
|
||||
*/
|
||||
void publish_mission_result();
|
||||
|
||||
control::BlockParamInt _param_onboard_enabled;
|
||||
control::BlockParamFloat _param_takeoff_alt;
|
||||
control::BlockParamFloat _param_dist_1wp;
|
||||
|
@ -162,9 +157,6 @@ private:
|
|||
bool _need_takeoff;
|
||||
bool _takeoff;
|
||||
|
||||
orb_advert_t _mission_result_pub;
|
||||
struct mission_result_s _mission_result;
|
||||
|
||||
enum {
|
||||
MISSION_TYPE_NONE,
|
||||
MISSION_TYPE_ONBOARD,
|
||||
|
|
|
@ -109,7 +109,7 @@ bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMiss
|
|||
return false;
|
||||
}
|
||||
|
||||
if (!geofence.inside(missionitem.lat, missionitem.lon, missionitem.altitude)) {
|
||||
if (!geofence.inside_polygon(missionitem.lat, missionitem.lon, missionitem.altitude)) {
|
||||
mavlink_log_info(_mavlink_fd, "#audio: Geofence violation waypoint %d", i);
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -49,7 +49,14 @@ SRCS = navigator_main.cpp \
|
|||
offboard.cpp \
|
||||
mission_feasibility_checker.cpp \
|
||||
geofence.cpp \
|
||||
geofence_params.c
|
||||
geofence_params.c \
|
||||
datalinkloss.cpp \
|
||||
datalinkloss_params.c \
|
||||
rcloss.cpp \
|
||||
rcloss_params.c \
|
||||
enginefailure.cpp \
|
||||
gpsfailure.cpp \
|
||||
gpsfailure_params.c
|
||||
|
||||
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
|
||||
|
||||
|
|
|
@ -35,6 +35,7 @@
|
|||
* Helper class to access missions
|
||||
* @author Julian Oes <julian@oes.ch>
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#ifndef NAVIGATOR_H
|
||||
|
@ -50,20 +51,26 @@
|
|||
#include <uORB/topics/vehicle_control_mode.h>
|
||||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/mission_result.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
|
||||
#include "navigator_mode.h"
|
||||
#include "mission.h"
|
||||
#include "loiter.h"
|
||||
#include "rtl.h"
|
||||
#include "offboard.h"
|
||||
#include "datalinkloss.h"
|
||||
#include "enginefailure.h"
|
||||
#include "gpsfailure.h"
|
||||
#include "rcloss.h"
|
||||
#include "geofence.h"
|
||||
|
||||
/**
|
||||
* Number of navigation modes that need on_active/on_inactive calls
|
||||
* Currently: mission, loiter, and rtl
|
||||
*/
|
||||
#define NAVIGATOR_MODE_ARRAY_SIZE 4
|
||||
#define NAVIGATOR_MODE_ARRAY_SIZE 8
|
||||
|
||||
class Navigator : public control::SuperBlock
|
||||
{
|
||||
|
@ -100,6 +107,17 @@ public:
|
|||
*/
|
||||
void load_fence_from_file(const char *filename);
|
||||
|
||||
/**
|
||||
* Publish the mission result so commander and mavlink know what is going on
|
||||
*/
|
||||
void publish_mission_result();
|
||||
|
||||
/**
|
||||
* Publish the attitude sp, only to be used in very special modes when position control is deactivated
|
||||
* Example: mode that is triggered on gps failure
|
||||
*/
|
||||
void publish_att_sp();
|
||||
|
||||
/**
|
||||
* Setters
|
||||
*/
|
||||
|
@ -112,8 +130,13 @@ public:
|
|||
struct vehicle_status_s* get_vstatus() { return &_vstatus; }
|
||||
struct vehicle_control_mode_s* get_control_mode() { return &_control_mode; }
|
||||
struct vehicle_global_position_s* get_global_position() { return &_global_pos; }
|
||||
struct vehicle_gps_position_s* get_gps_position() { return &_gps_pos; }
|
||||
struct sensor_combined_s* get_sensor_combined() { return &_sensor_combined; }
|
||||
struct home_position_s* get_home_position() { return &_home_pos; }
|
||||
struct position_setpoint_triplet_s* get_position_setpoint_triplet() { return &_pos_sp_triplet; }
|
||||
struct position_setpoint_triplet_s* get_position_setpoint_triplet() { return &_pos_sp_triplet; }
|
||||
struct mission_result_s* get_mission_result() { return &_mission_result; }
|
||||
struct vehicle_attitude_setpoint_s* get_att_sp() { return &_att_sp; }
|
||||
|
||||
int get_onboard_mission_sub() { return _onboard_mission_sub; }
|
||||
int get_offboard_mission_sub() { return _offboard_mission_sub; }
|
||||
int get_offboard_control_sp_sub() { return _offboard_control_sp_sub; }
|
||||
|
@ -131,6 +154,8 @@ private:
|
|||
int _mavlink_fd; /**< the file descriptor to send messages over mavlink */
|
||||
|
||||
int _global_pos_sub; /**< global position subscription */
|
||||
int _gps_pos_sub; /**< gps position subscription */
|
||||
int _sensor_combined_sub; /**< sensor combined subscription */
|
||||
int _home_pos_sub; /**< home position subscription */
|
||||
int _vstatus_sub; /**< vehicle status subscription */
|
||||
int _capabilities_sub; /**< notification of vehicle capabilities updates */
|
||||
|
@ -141,15 +166,24 @@ private:
|
|||
int _param_update_sub; /**< param update subscription */
|
||||
|
||||
orb_advert_t _pos_sp_triplet_pub; /**< publish position setpoint triplet */
|
||||
orb_advert_t _mission_result_pub;
|
||||
orb_advert_t _att_sp_pub; /**< publish att sp
|
||||
used only in very special failsafe modes
|
||||
when pos control is deactivated */
|
||||
|
||||
vehicle_status_s _vstatus; /**< vehicle status */
|
||||
vehicle_control_mode_s _control_mode; /**< vehicle control mode */
|
||||
vehicle_global_position_s _global_pos; /**< global vehicle position */
|
||||
vehicle_gps_position_s _gps_pos; /**< gps position */
|
||||
sensor_combined_s _sensor_combined; /**< sensor values */
|
||||
home_position_s _home_pos; /**< home position for RTL */
|
||||
mission_item_s _mission_item; /**< current mission item */
|
||||
navigation_capabilities_s _nav_caps; /**< navigation capabilities */
|
||||
position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of position setpoints */
|
||||
|
||||
mission_result_s _mission_result;
|
||||
vehicle_attitude_setpoint_s _att_sp;
|
||||
|
||||
bool _mission_item_valid; /**< flags if the current mission item is valid */
|
||||
|
||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||
|
@ -157,14 +191,19 @@ private:
|
|||
Geofence _geofence; /**< class that handles the geofence */
|
||||
bool _geofence_violation_warning_sent; /**< prevents spaming to mavlink */
|
||||
|
||||
bool _fence_valid; /**< flag if fence is valid */
|
||||
bool _inside_fence; /**< vehicle is inside fence */
|
||||
|
||||
NavigatorMode *_navigation_mode; /**< abstract pointer to current navigation mode class */
|
||||
Mission _mission; /**< class that handles the missions */
|
||||
Loiter _loiter; /**< class that handles loiter */
|
||||
RTL _rtl; /**< class that handles RTL */
|
||||
RCLoss _rcLoss; /**< class that handles RTL according to
|
||||
OBC rules (rc loss mode) */
|
||||
Offboard _offboard; /**< class that handles offboard */
|
||||
DataLinkLoss _dataLinkLoss; /**< class that handles the OBC datalink loss mode */
|
||||
EngineFailure _engineFailure; /**< class that handles the engine failure mode
|
||||
(FW only!) */
|
||||
GpsFailure _gpsFailure; /**< class that handles the OBC gpsfailure loss mode */
|
||||
|
||||
NavigatorMode *_navigation_mode_array[NAVIGATOR_MODE_ARRAY_SIZE]; /**< array of navigation modes */
|
||||
|
||||
|
@ -173,11 +212,23 @@ private:
|
|||
|
||||
control::BlockParamFloat _param_loiter_radius; /**< loiter radius for fixedwing */
|
||||
control::BlockParamFloat _param_acceptance_radius; /**< acceptance for takeoff */
|
||||
control::BlockParamInt _param_datalinkloss_obc; /**< if true: obc mode on data link loss enabled */
|
||||
control::BlockParamInt _param_rcloss_obc; /**< if true: obc mode on rc loss enabled */
|
||||
/**
|
||||
* Retrieve global position
|
||||
*/
|
||||
void global_position_update();
|
||||
|
||||
/**
|
||||
* Retrieve gps position
|
||||
*/
|
||||
void gps_position_update();
|
||||
|
||||
/**
|
||||
* Retrieve sensor values
|
||||
*/
|
||||
void sensor_combined_update();
|
||||
|
||||
/**
|
||||
* Retrieve home position
|
||||
*/
|
||||
|
|
|
@ -40,6 +40,7 @@
|
|||
* @author Jean Cyr <jean.m.cyr@gmail.com>
|
||||
* @author Julian Oes <julian@oes.ch>
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
@ -68,6 +69,7 @@
|
|||
#include <uORB/topics/fence.h>
|
||||
#include <uORB/topics/navigation_capabilities.h>
|
||||
#include <uORB/topics/offboard_control_setpoint.h>
|
||||
#include <drivers/drv_baro.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
@ -98,6 +100,7 @@ Navigator::Navigator() :
|
|||
_navigator_task(-1),
|
||||
_mavlink_fd(-1),
|
||||
_global_pos_sub(-1),
|
||||
_gps_pos_sub(-1),
|
||||
_home_pos_sub(-1),
|
||||
_vstatus_sub(-1),
|
||||
_capabilities_sub(-1),
|
||||
|
@ -107,34 +110,49 @@ Navigator::Navigator() :
|
|||
_offboard_mission_sub(-1),
|
||||
_param_update_sub(-1),
|
||||
_pos_sp_triplet_pub(-1),
|
||||
_mission_result_pub(-1),
|
||||
_att_sp_pub(-1),
|
||||
_vstatus{},
|
||||
_control_mode{},
|
||||
_global_pos{},
|
||||
_gps_pos{},
|
||||
_sensor_combined{},
|
||||
_home_pos{},
|
||||
_mission_item{},
|
||||
_nav_caps{},
|
||||
_pos_sp_triplet{},
|
||||
_mission_result{},
|
||||
_att_sp{},
|
||||
_mission_item_valid(false),
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, "navigator")),
|
||||
_geofence{},
|
||||
_geofence_violation_warning_sent(false),
|
||||
_fence_valid(false),
|
||||
_inside_fence(true),
|
||||
_navigation_mode(nullptr),
|
||||
_mission(this, "MIS"),
|
||||
_loiter(this, "LOI"),
|
||||
_rtl(this, "RTL"),
|
||||
_rcLoss(this, "RCL"),
|
||||
_offboard(this, "OFF"),
|
||||
_dataLinkLoss(this, "DLL"),
|
||||
_engineFailure(this, "EF"),
|
||||
_gpsFailure(this, "GPSF"),
|
||||
_can_loiter_at_sp(false),
|
||||
_pos_sp_triplet_updated(false),
|
||||
_param_loiter_radius(this, "LOITER_RAD"),
|
||||
_param_acceptance_radius(this, "ACC_RAD")
|
||||
_param_acceptance_radius(this, "ACC_RAD"),
|
||||
_param_datalinkloss_obc(this, "DLL_OBC"),
|
||||
_param_rcloss_obc(this, "RCL_OBC")
|
||||
{
|
||||
/* Create a list of our possible navigation types */
|
||||
_navigation_mode_array[0] = &_mission;
|
||||
_navigation_mode_array[1] = &_loiter;
|
||||
_navigation_mode_array[2] = &_rtl;
|
||||
_navigation_mode_array[3] = &_offboard;
|
||||
_navigation_mode_array[4] = &_dataLinkLoss;
|
||||
_navigation_mode_array[5] = &_engineFailure;
|
||||
_navigation_mode_array[6] = &_gpsFailure;
|
||||
_navigation_mode_array[7] = &_rcLoss;
|
||||
|
||||
updateParams();
|
||||
}
|
||||
|
@ -170,6 +188,18 @@ Navigator::global_position_update()
|
|||
orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
|
||||
}
|
||||
|
||||
void
|
||||
Navigator::gps_position_update()
|
||||
{
|
||||
orb_copy(ORB_ID(vehicle_gps_position), _gps_pos_sub, &_gps_pos);
|
||||
}
|
||||
|
||||
void
|
||||
Navigator::sensor_combined_update()
|
||||
{
|
||||
orb_copy(ORB_ID(sensor_combined), _sensor_combined_sub, &_sensor_combined);
|
||||
}
|
||||
|
||||
void
|
||||
Navigator::home_position_update()
|
||||
{
|
||||
|
@ -221,6 +251,7 @@ Navigator::task_main()
|
|||
warnx("Initializing..");
|
||||
|
||||
_mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
|
||||
_geofence.setMavlinkFd(_mavlink_fd);
|
||||
|
||||
/* Try to load the geofence:
|
||||
* if /fs/microsd/etc/geofence.txt load from this file
|
||||
|
@ -232,6 +263,7 @@ Navigator::task_main()
|
|||
_geofence.loadFromFile(GEOFENCE_FILENAME);
|
||||
|
||||
} else {
|
||||
mavlink_log_critical(_mavlink_fd, "#audio: No geofence file");
|
||||
if (_geofence.clearDm() > 0)
|
||||
warnx("Geofence cleared");
|
||||
else
|
||||
|
@ -240,6 +272,8 @@ Navigator::task_main()
|
|||
|
||||
/* do subscriptions */
|
||||
_global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
|
||||
_gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
|
||||
_sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
|
||||
_capabilities_sub = orb_subscribe(ORB_ID(navigation_capabilities));
|
||||
_vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
|
||||
_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
|
||||
|
@ -253,6 +287,8 @@ Navigator::task_main()
|
|||
vehicle_status_update();
|
||||
vehicle_control_mode_update();
|
||||
global_position_update();
|
||||
gps_position_update();
|
||||
sensor_combined_update();
|
||||
home_position_update();
|
||||
navigation_capabilities_update();
|
||||
params_update();
|
||||
|
@ -264,7 +300,7 @@ Navigator::task_main()
|
|||
const hrt_abstime mavlink_open_interval = 500000;
|
||||
|
||||
/* wakeup source(s) */
|
||||
struct pollfd fds[6];
|
||||
struct pollfd fds[8];
|
||||
|
||||
/* Setup of loop */
|
||||
fds[0].fd = _global_pos_sub;
|
||||
|
@ -279,6 +315,10 @@ Navigator::task_main()
|
|||
fds[4].events = POLLIN;
|
||||
fds[5].fd = _param_update_sub;
|
||||
fds[5].events = POLLIN;
|
||||
fds[6].fd = _sensor_combined_sub;
|
||||
fds[6].events = POLLIN;
|
||||
fds[7].fd = _gps_pos_sub;
|
||||
fds[7].events = POLLIN;
|
||||
|
||||
while (!_task_should_exit) {
|
||||
|
||||
|
@ -303,6 +343,21 @@ Navigator::task_main()
|
|||
_mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
|
||||
}
|
||||
|
||||
bool have_geofence_position_data = false;
|
||||
|
||||
/* gps updated */
|
||||
if (fds[7].revents & POLLIN) {
|
||||
gps_position_update();
|
||||
if (_geofence.getSource() == Geofence::GF_SOURCE_GPS) {
|
||||
have_geofence_position_data = true;
|
||||
}
|
||||
}
|
||||
|
||||
/* sensors combined updated */
|
||||
if (fds[6].revents & POLLIN) {
|
||||
sensor_combined_update();
|
||||
}
|
||||
|
||||
/* parameters updated */
|
||||
if (fds[5].revents & POLLIN) {
|
||||
params_update();
|
||||
|
@ -332,9 +387,18 @@ Navigator::task_main()
|
|||
/* global position updated */
|
||||
if (fds[0].revents & POLLIN) {
|
||||
global_position_update();
|
||||
if (_geofence.getSource() == Geofence::GF_SOURCE_GLOBALPOS) {
|
||||
have_geofence_position_data = true;
|
||||
}
|
||||
}
|
||||
|
||||
/* Check geofence violation */
|
||||
if (!_geofence.inside(&_global_pos)) {
|
||||
/* Check geofence violation */
|
||||
if (have_geofence_position_data) {
|
||||
bool inside = _geofence.inside(_global_pos, _gps_pos, _sensor_combined.baro_alt_meter);
|
||||
if (!inside) {
|
||||
/* inform other apps via the mission result */
|
||||
_mission_result.geofence_violated = true;
|
||||
publish_mission_result();
|
||||
|
||||
/* Issue a warning about the geofence violation once */
|
||||
if (!_geofence_violation_warning_sent) {
|
||||
|
@ -342,6 +406,9 @@ Navigator::task_main()
|
|||
_geofence_violation_warning_sent = true;
|
||||
}
|
||||
} else {
|
||||
/* inform other apps via the mission result */
|
||||
_mission_result.geofence_violated = false;
|
||||
publish_mission_result();
|
||||
/* Reset the _geofence_violation_warning_sent field */
|
||||
_geofence_violation_warning_sent = false;
|
||||
}
|
||||
|
@ -359,16 +426,38 @@ Navigator::task_main()
|
|||
_can_loiter_at_sp = false;
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_MISSION:
|
||||
/* Some failsafe modes prohibit the fallback to mission
|
||||
* usually this is done after some time to make sure
|
||||
* that the full failsafe operation is performed */
|
||||
_navigation_mode = &_mission;
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_LOITER:
|
||||
_navigation_mode = &_loiter;
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_RTL:
|
||||
_navigation_mode = &_rtl;
|
||||
case NAVIGATION_STATE_AUTO_RCRECOVER:
|
||||
if (_param_rcloss_obc.get() != 0) {
|
||||
_navigation_mode = &_rcLoss;
|
||||
} else {
|
||||
_navigation_mode = &_rtl;
|
||||
}
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_RTGS:
|
||||
_navigation_mode = &_rtl; /* TODO: change this to something else */
|
||||
case NAVIGATION_STATE_AUTO_RTL:
|
||||
_navigation_mode = &_rtl;
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_RTGS: //XXX OBC: differentiate between rc loss and dl loss here
|
||||
/* Use complex data link loss mode only when enabled via param
|
||||
* otherwise use rtl */
|
||||
if (_param_datalinkloss_obc.get() != 0) {
|
||||
_navigation_mode = &_dataLinkLoss;
|
||||
} else {
|
||||
_navigation_mode = &_rtl;
|
||||
}
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_LANDENGFAIL:
|
||||
_navigation_mode = &_engineFailure;
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_LANDGPSFAIL:
|
||||
_navigation_mode = &_gpsFailure;
|
||||
break;
|
||||
case NAVIGATION_STATE_OFFBOARD:
|
||||
_navigation_mode = &_offboard;
|
||||
|
@ -442,7 +531,7 @@ Navigator::status()
|
|||
// warnx("Compass heading in degrees %5.5f", (double)(_global_pos.yaw * M_RAD_TO_DEG_F));
|
||||
// }
|
||||
|
||||
if (_fence_valid) {
|
||||
if (_geofence.valid()) {
|
||||
warnx("Geofence is valid");
|
||||
/* TODO: needed? */
|
||||
// warnx("Vertex longitude latitude");
|
||||
|
@ -450,7 +539,7 @@ Navigator::status()
|
|||
// warnx("%6u %9.5f %8.5f", i, (double)_fence.vertices[i].lon, (double)_fence.vertices[i].lat);
|
||||
|
||||
} else {
|
||||
warnx("Geofence not set");
|
||||
warnx("Geofence not set (no /etc/geofence.txt on microsd) or not valid");
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -534,3 +623,34 @@ int navigator_main(int argc, char *argv[])
|
|||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void
|
||||
Navigator::publish_mission_result()
|
||||
{
|
||||
/* lazily publish the mission result only once available */
|
||||
if (_mission_result_pub > 0) {
|
||||
/* publish mission result */
|
||||
orb_publish(ORB_ID(mission_result), _mission_result_pub, &_mission_result);
|
||||
|
||||
} else {
|
||||
/* advertise and publish */
|
||||
_mission_result_pub = orb_advertise(ORB_ID(mission_result), &_mission_result);
|
||||
}
|
||||
/* reset reached bool */
|
||||
_mission_result.reached = false;
|
||||
_mission_result.finished = false;
|
||||
}
|
||||
|
||||
void
|
||||
Navigator::publish_att_sp()
|
||||
{
|
||||
/* lazily publish the attitude sp only once available */
|
||||
if (_att_sp_pub > 0) {
|
||||
/* publish att sp*/
|
||||
orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &_att_sp);
|
||||
|
||||
} else {
|
||||
/* advertise and publish */
|
||||
_att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &_att_sp);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
#include "navigator.h"
|
||||
|
||||
NavigatorMode::NavigatorMode(Navigator *navigator, const char *name) :
|
||||
SuperBlock(NULL, name),
|
||||
SuperBlock(navigator, name),
|
||||
_navigator(navigator),
|
||||
_first_run(true)
|
||||
{
|
||||
|
@ -63,6 +63,9 @@ NavigatorMode::run(bool active) {
|
|||
if (_first_run) {
|
||||
/* first run */
|
||||
_first_run = false;
|
||||
/* Reset stay in failsafe flag */
|
||||
_navigator->get_mission_result()->stay_in_failsafe = false;
|
||||
_navigator->publish_mission_result();
|
||||
on_activation();
|
||||
|
||||
} else {
|
||||
|
|
|
@ -37,6 +37,7 @@
|
|||
* Parameters for navigator in general
|
||||
*
|
||||
* @author Julian Oes <julian@oes.ch>
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
@ -64,3 +65,56 @@ PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f);
|
|||
* @group Mission
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_ACC_RAD, 25.0f);
|
||||
|
||||
/**
|
||||
* Set OBC mode for data link loss
|
||||
*
|
||||
* If set to 1 the behaviour on data link loss is set to a mode according to the OBC rules
|
||||
*
|
||||
* @min 0
|
||||
* @group Mission
|
||||
*/
|
||||
PARAM_DEFINE_INT32(NAV_DLL_OBC, 0);
|
||||
|
||||
/**
|
||||
* Set OBC mode for rc loss
|
||||
*
|
||||
* If set to 1 the behaviour on data link loss is set to a mode according to the OBC rules
|
||||
*
|
||||
* @min 0
|
||||
* @group Mission
|
||||
*/
|
||||
PARAM_DEFINE_INT32(NAV_RCL_OBC, 0);
|
||||
|
||||
/**
|
||||
* Airfield home Lat
|
||||
*
|
||||
* Latitude of airfield home waypoint
|
||||
*
|
||||
* @unit degrees * 1e7
|
||||
* @min 0.0
|
||||
* @group DLL
|
||||
*/
|
||||
PARAM_DEFINE_INT32(NAV_AH_LAT, -265847810);
|
||||
|
||||
/**
|
||||
* Airfield home Lon
|
||||
*
|
||||
* Longitude of airfield home waypoint
|
||||
*
|
||||
* @unit degrees * 1e7
|
||||
* @min 0.0
|
||||
* @group DLL
|
||||
*/
|
||||
PARAM_DEFINE_INT32(NAV_AH_LON, 1518423250);
|
||||
|
||||
/**
|
||||
* Airfield home alt
|
||||
*
|
||||
* Altitude of airfield home waypoint
|
||||
*
|
||||
* @unit m
|
||||
* @min 0.0
|
||||
* @group DLL
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_AH_ALT, 600.0f);
|
||||
|
|
|
@ -0,0 +1,182 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
/**
|
||||
* @file rcloss.cpp
|
||||
* Helper class for RC Loss Mode according to the OBC rules
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <math.h>
|
||||
#include <fcntl.h>
|
||||
|
||||
#include <mavlink/mavlink_log.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <geo/geo.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
#include <uORB/topics/home_position.h>
|
||||
|
||||
#include "navigator.h"
|
||||
#include "datalinkloss.h"
|
||||
|
||||
#define DELAY_SIGMA 0.01f
|
||||
|
||||
RCLoss::RCLoss(Navigator *navigator, const char *name) :
|
||||
MissionBlock(navigator, name),
|
||||
_param_loitertime(this, "LT"),
|
||||
_rcl_state(RCL_STATE_NONE)
|
||||
{
|
||||
/* load initial params */
|
||||
updateParams();
|
||||
/* initial reset */
|
||||
on_inactive();
|
||||
}
|
||||
|
||||
RCLoss::~RCLoss()
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
RCLoss::on_inactive()
|
||||
{
|
||||
/* reset RCL state only if setpoint moved */
|
||||
if (!_navigator->get_can_loiter_at_sp()) {
|
||||
_rcl_state = RCL_STATE_NONE;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
RCLoss::on_activation()
|
||||
{
|
||||
_rcl_state = RCL_STATE_NONE;
|
||||
updateParams();
|
||||
advance_rcl();
|
||||
set_rcl_item();
|
||||
}
|
||||
|
||||
void
|
||||
RCLoss::on_active()
|
||||
{
|
||||
if (is_mission_item_reached()) {
|
||||
updateParams();
|
||||
advance_rcl();
|
||||
set_rcl_item();
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
RCLoss::set_rcl_item()
|
||||
{
|
||||
struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
|
||||
|
||||
set_previous_pos_setpoint();
|
||||
_navigator->set_can_loiter_at_sp(false);
|
||||
|
||||
switch (_rcl_state) {
|
||||
case RCL_STATE_LOITER: {
|
||||
_mission_item.lat = _navigator->get_global_position()->lat;
|
||||
_mission_item.lon = _navigator->get_global_position()->lon;
|
||||
_mission_item.altitude = _navigator->get_global_position()->alt;
|
||||
_mission_item.altitude_is_relative = false;
|
||||
_mission_item.yaw = NAN;
|
||||
_mission_item.loiter_radius = _navigator->get_loiter_radius();
|
||||
_mission_item.loiter_direction = 1;
|
||||
_mission_item.nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
|
||||
_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
|
||||
_mission_item.time_inside = _param_loitertime.get() < 0.0f ? 0.0f : _param_loitertime.get();
|
||||
_mission_item.pitch_min = 0.0f;
|
||||
_mission_item.autocontinue = true;
|
||||
_mission_item.origin = ORIGIN_ONBOARD;
|
||||
|
||||
_navigator->set_can_loiter_at_sp(true);
|
||||
break;
|
||||
}
|
||||
case RCL_STATE_TERMINATE: {
|
||||
/* Request flight termination from the commander */
|
||||
_navigator->get_mission_result()->flight_termination = true;
|
||||
_navigator->publish_mission_result();
|
||||
warnx("rc not recovered: request flight termination");
|
||||
pos_sp_triplet->previous.valid = false;
|
||||
pos_sp_triplet->current.valid = false;
|
||||
pos_sp_triplet->next.valid = false;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
reset_mission_item_reached();
|
||||
|
||||
/* convert mission item to current position setpoint and make it valid */
|
||||
mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
|
||||
pos_sp_triplet->next.valid = false;
|
||||
|
||||
_navigator->set_position_setpoint_triplet_updated();
|
||||
}
|
||||
|
||||
void
|
||||
RCLoss::advance_rcl()
|
||||
{
|
||||
switch (_rcl_state) {
|
||||
case RCL_STATE_NONE:
|
||||
if (_param_loitertime.get() > 0.0f) {
|
||||
warnx("RC loss, OBC mode, loiter");
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: rc loss, loitering");
|
||||
_rcl_state = RCL_STATE_LOITER;
|
||||
} else {
|
||||
warnx("RC loss, OBC mode, slip loiter, terminate");
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: rc loss, terminating");
|
||||
_rcl_state = RCL_STATE_TERMINATE;
|
||||
_navigator->get_mission_result()->stay_in_failsafe = true;
|
||||
_navigator->publish_mission_result();
|
||||
}
|
||||
break;
|
||||
case RCL_STATE_LOITER:
|
||||
_rcl_state = RCL_STATE_TERMINATE;
|
||||
warnx("time is up, no RC regain, terminating");
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RC not regained, terminating");
|
||||
_navigator->get_mission_result()->stay_in_failsafe = true;
|
||||
_navigator->publish_mission_result();
|
||||
break;
|
||||
case RCL_STATE_TERMINATE:
|
||||
warnx("rcl end");
|
||||
_rcl_state = RCL_STATE_END;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
|
@ -0,0 +1,88 @@
|
|||
/***************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
/**
|
||||
* @file rcloss.h
|
||||
* Helper class for RC Loss Mode acording to the OBC rules
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#ifndef NAVIGATOR_RCLOSS_H
|
||||
#define NAVIGATOR_RCLOSS_H
|
||||
|
||||
#include <controllib/blocks.hpp>
|
||||
#include <controllib/block/BlockParam.hpp>
|
||||
|
||||
#include <uORB/Subscription.hpp>
|
||||
|
||||
#include "navigator_mode.h"
|
||||
#include "mission_block.h"
|
||||
|
||||
class Navigator;
|
||||
|
||||
class RCLoss : public MissionBlock
|
||||
{
|
||||
public:
|
||||
RCLoss(Navigator *navigator, const char *name);
|
||||
|
||||
~RCLoss();
|
||||
|
||||
virtual void on_inactive();
|
||||
|
||||
virtual void on_activation();
|
||||
|
||||
virtual void on_active();
|
||||
|
||||
private:
|
||||
/* Params */
|
||||
control::BlockParamFloat _param_loitertime;
|
||||
|
||||
enum RCLState {
|
||||
RCL_STATE_NONE = 0,
|
||||
RCL_STATE_LOITER = 1,
|
||||
RCL_STATE_TERMINATE = 2,
|
||||
RCL_STATE_END = 3
|
||||
} _rcl_state;
|
||||
|
||||
/**
|
||||
* Set the RCL item
|
||||
*/
|
||||
void set_rcl_item();
|
||||
|
||||
/**
|
||||
* Move to next RCL item
|
||||
*/
|
||||
void advance_rcl();
|
||||
|
||||
};
|
||||
#endif
|
|
@ -0,0 +1,60 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file rcloss_params.c
|
||||
*
|
||||
* Parameters for RC Loss (OBC)
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/*
|
||||
* OBC RC Loss mode parameters, accessible via MAVLink
|
||||
*/
|
||||
|
||||
/**
|
||||
* Loiter Time
|
||||
*
|
||||
* The amount of time in seconds the system should loiter at current position before termination
|
||||
* Set to -1 to make the system skip loitering
|
||||
*
|
||||
* @unit seconds
|
||||
* @min -1.0
|
||||
* @group RCL
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_RCL_LT, 120.0f);
|
|
@ -58,9 +58,9 @@
|
|||
RTL::RTL(Navigator *navigator, const char *name) :
|
||||
MissionBlock(navigator, name),
|
||||
_rtl_state(RTL_STATE_NONE),
|
||||
_param_return_alt(this, "RETURN_ALT"),
|
||||
_param_descend_alt(this, "DESCEND_ALT"),
|
||||
_param_land_delay(this, "LAND_DELAY")
|
||||
_param_return_alt(this, "RTL_RETURN_ALT", false),
|
||||
_param_descend_alt(this, "RTL_DESCEND_ALT", false),
|
||||
_param_land_delay(this, "RTL_LAND_DELAY", false)
|
||||
{
|
||||
/* load initial params */
|
||||
updateParams();
|
||||
|
|
|
@ -58,7 +58,7 @@ extern "C" {
|
|||
/*
|
||||
* Maximum interval in us before FMU signal is considered lost
|
||||
*/
|
||||
#define FMU_INPUT_DROP_LIMIT_US 200000
|
||||
#define FMU_INPUT_DROP_LIMIT_US 500000
|
||||
|
||||
/* XXX need to move the RC_CHANNEL_FUNCTION out of rc_channels.h and into systemlib */
|
||||
#define ROLL 0
|
||||
|
@ -98,7 +98,8 @@ mixer_tick(void)
|
|||
{
|
||||
|
||||
/* check that we are receiving fresh data from the FMU */
|
||||
if (hrt_elapsed_time(&system_state.fmu_data_received_time) > FMU_INPUT_DROP_LIMIT_US) {
|
||||
if ((system_state.fmu_data_received_time == 0) ||
|
||||
hrt_elapsed_time(&system_state.fmu_data_received_time) > FMU_INPUT_DROP_LIMIT_US) {
|
||||
|
||||
/* too long without FMU input, time to go to failsafe */
|
||||
if (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) {
|
||||
|
@ -109,6 +110,9 @@ mixer_tick(void)
|
|||
|
||||
} else {
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK;
|
||||
|
||||
/* this flag is never cleared once OK */
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED;
|
||||
}
|
||||
|
||||
/* default to failsafe mixing - it will be forced below if flag is set */
|
||||
|
@ -139,7 +143,9 @@ mixer_tick(void)
|
|||
(r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) &&
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) &&
|
||||
!(r_setup_arming & PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED) &&
|
||||
!(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) {
|
||||
!(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) &&
|
||||
/* do not enter manual override if we asked for termination failsafe and FMU is lost */
|
||||
!(r_setup_arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE)) {
|
||||
|
||||
/* if allowed, mix from RC inputs directly */
|
||||
source = MIX_OVERRIDE;
|
||||
|
@ -154,6 +160,44 @@ mixer_tick(void)
|
|||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Decide whether the servos should be armed right now.
|
||||
*
|
||||
* We must be armed, and we must have a PWM source; either raw from
|
||||
* FMU or from the mixer.
|
||||
*
|
||||
*/
|
||||
should_arm = (
|
||||
/* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
|
||||
/* and IO is armed */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
|
||||
/* and FMU is armed */ && (
|
||||
((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)
|
||||
/* and there is valid input via or mixer */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) )
|
||||
/* or direct PWM is set */ || (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM)
|
||||
/* or failsafe was set manually */ || ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) && !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK))
|
||||
)
|
||||
);
|
||||
|
||||
should_always_enable_pwm = (r_setup_arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE)
|
||||
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
|
||||
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK);
|
||||
|
||||
/*
|
||||
* Check if failsafe termination is set - if yes,
|
||||
* set the force failsafe flag once entering the first
|
||||
* failsafe condition.
|
||||
*/
|
||||
if ( /* if we have requested flight termination style failsafe (noreturn) */
|
||||
(r_setup_arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE) &&
|
||||
/* and we ended up in a failsafe condition */
|
||||
(source == MIX_FAILSAFE) &&
|
||||
/* and we should be armed, so we intended to provide outputs */
|
||||
should_arm &&
|
||||
/* and FMU is initialized */
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED)) {
|
||||
r_setup_arming |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
|
||||
}
|
||||
|
||||
/*
|
||||
* Check if we should force failsafe - and do it if we have to
|
||||
*/
|
||||
|
@ -170,30 +214,6 @@ mixer_tick(void)
|
|||
r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FAILSAFE);
|
||||
}
|
||||
|
||||
/*
|
||||
* Decide whether the servos should be armed right now.
|
||||
*
|
||||
* We must be armed, and we must have a PWM source; either raw from
|
||||
* FMU or from the mixer.
|
||||
*
|
||||
* XXX correct behaviour for failsafe may require an additional case
|
||||
* here.
|
||||
*/
|
||||
should_arm = (
|
||||
/* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
|
||||
/* and IO is armed */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
|
||||
/* and FMU is armed */ && (
|
||||
((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)
|
||||
/* and there is valid input via or mixer */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) )
|
||||
/* or direct PWM is set */ || (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM)
|
||||
/* or failsafe was set manually */ || ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) && !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK))
|
||||
)
|
||||
);
|
||||
|
||||
should_always_enable_pwm = (r_setup_arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE)
|
||||
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
|
||||
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK);
|
||||
|
||||
/*
|
||||
* Run the mixers.
|
||||
*/
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -111,6 +111,7 @@
|
|||
#define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 10) /* initialisation of the IO completed without error */
|
||||
#define PX4IO_P_STATUS_FLAGS_FAILSAFE (1 << 11) /* failsafe is active */
|
||||
#define PX4IO_P_STATUS_FLAGS_SAFETY_OFF (1 << 12) /* safety is off */
|
||||
#define PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED (1 << 13) /* FMU was initialized and OK once */
|
||||
|
||||
#define PX4IO_P_STATUS_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */
|
||||
#define PX4IO_P_STATUS_ALARMS_VBATT_LOW (1 << 0) /* [1] VBatt is very close to regulator dropout */
|
||||
|
@ -180,6 +181,7 @@
|
|||
#define PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED (1 << 6) /* Disable the IO-internal evaluation of the RC */
|
||||
#define PX4IO_P_SETUP_ARMING_LOCKDOWN (1 << 7) /* If set, the system operates normally, but won't actuate any servos */
|
||||
#define PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE (1 << 8) /* If set, the system will always output the failsafe values */
|
||||
#define PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE (1 << 9) /* If set, the system will never return from a failsafe, but remain in failsafe once triggered. */
|
||||
|
||||
#define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */
|
||||
#define PX4IO_P_SETUP_PWM_DEFAULTRATE 3 /* 'low' PWM frame output rate in Hz */
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -190,7 +190,8 @@ volatile uint16_t r_page_setup[] =
|
|||
PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE | \
|
||||
PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED | \
|
||||
PX4IO_P_SETUP_ARMING_LOCKDOWN | \
|
||||
PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE)
|
||||
PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE | \
|
||||
PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE)
|
||||
#define PX4IO_P_SETUP_RATES_VALID ((1 << PX4IO_SERVO_COUNT) - 1)
|
||||
#define PX4IO_P_SETUP_RELAYS_VALID ((1 << PX4IO_RELAY_CHANNELS) - 1)
|
||||
|
||||
|
@ -518,6 +519,19 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
|
|||
r_status_flags |= PX4IO_P_STATUS_FLAGS_INIT_OK;
|
||||
}
|
||||
|
||||
/*
|
||||
* If the failsafe termination flag is set, do not allow the autopilot to unset it
|
||||
*/
|
||||
value |= (r_setup_arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE);
|
||||
|
||||
/*
|
||||
* If failsafe termination is enabled and force failsafe bit is set, do not allow
|
||||
* the autopilot to clear it.
|
||||
*/
|
||||
if (r_setup_arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE) {
|
||||
value |= (r_setup_arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE);
|
||||
}
|
||||
|
||||
r_setup_arming = value;
|
||||
|
||||
break;
|
||||
|
|
|
@ -95,6 +95,33 @@ PARAM_DEFINE_INT32(CBRK_IO_SAFETY, 0);
|
|||
*/
|
||||
PARAM_DEFINE_INT32(CBRK_AIRSPD_CHK, 0);
|
||||
|
||||
/**
|
||||
* Circuit breaker for flight termination
|
||||
*
|
||||
* Setting this parameter to 121212 will disable the flight termination action.
|
||||
* --> The IO driver will not do flight termination if requested by the FMU
|
||||
* WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
|
||||
*
|
||||
* @min 0
|
||||
* @max 121212
|
||||
* @group Circuit Breaker
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CBRK_FLIGHTTERM, 0);
|
||||
|
||||
/**
|
||||
* Circuit breaker for engine failure detection
|
||||
*
|
||||
* Setting this parameter to 284953 will disable the engine failure detection.
|
||||
* If the aircraft is in engine failure mode the enine failure flag will be
|
||||
* set to healthy
|
||||
* WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
|
||||
*
|
||||
* @min 0
|
||||
* @max 284953
|
||||
* @group Circuit Breaker
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CBRK_ENGINEFAIL, 0);
|
||||
|
||||
bool circuit_breaker_enabled(const char* breaker, int32_t magic)
|
||||
{
|
||||
int32_t val;
|
||||
|
|
|
@ -53,6 +53,8 @@
|
|||
#define CBRK_RATE_CTRL_KEY 140253
|
||||
#define CBRK_IO_SAFETY_KEY 22027
|
||||
#define CBRK_AIRSPD_CHK_KEY 162128
|
||||
#define CBRK_FLIGHTTERM_KEY 121212
|
||||
#define CBRK_ENGINEFAIL_KEY 284953
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
|
|
|
@ -55,8 +55,11 @@ struct mission_result_s
|
|||
{
|
||||
unsigned seq_reached; /**< Sequence of the mission item which has been reached */
|
||||
unsigned seq_current; /**< Sequence of the current mission item */
|
||||
bool reached; /**< true if mission has been reached */
|
||||
bool finished; /**< true if mission has been completed */
|
||||
bool reached; /**< true if mission has been reached */
|
||||
bool finished; /**< true if mission has been completed */
|
||||
bool stay_in_failsafe; /**< true if the commander should not switch out of the failsafe mode*/
|
||||
bool geofence_violated; /**< true if the geofence is violated */
|
||||
bool flight_termination; /**< true if the navigator demands a flight termination from the commander app */
|
||||
};
|
||||
|
||||
/**
|
||||
|
|
|
@ -67,6 +67,8 @@ struct telemetry_status_s {
|
|||
uint8_t noise; /**< background noise level */
|
||||
uint8_t remote_noise; /**< remote background noise level */
|
||||
uint8_t txbuf; /**< how full the tx buffer is as a percentage */
|
||||
uint8_t system_id; /**< system id of the remote system */
|
||||
uint8_t component_id; /**< component id of the remote system */
|
||||
};
|
||||
|
||||
/**
|
||||
|
|
|
@ -102,7 +102,10 @@ typedef enum {
|
|||
NAVIGATION_STATE_AUTO_MISSION, /**< Auto mission mode */
|
||||
NAVIGATION_STATE_AUTO_LOITER, /**< Auto loiter mode */
|
||||
NAVIGATION_STATE_AUTO_RTL, /**< Auto return to launch mode */
|
||||
NAVIGATION_STATE_AUTO_RCRECOVER, /**< RC recover mode */
|
||||
NAVIGATION_STATE_AUTO_RTGS, /**< Auto return to groundstation on data link loss */
|
||||
NAVIGATION_STATE_AUTO_LANDENGFAIL, /**< Auto land on engine failure */
|
||||
NAVIGATION_STATE_AUTO_LANDGPSFAIL, /**< Auto land on gps failure (e.g. open loop loiter down) */
|
||||
NAVIGATION_STATE_ACRO, /**< Acro mode */
|
||||
NAVIGATION_STATE_LAND, /**< Land mode */
|
||||
NAVIGATION_STATE_DESCEND, /**< Descend mode (no position control) */
|
||||
|
@ -198,9 +201,18 @@ struct vehicle_status_s {
|
|||
|
||||
bool rc_signal_found_once;
|
||||
bool rc_signal_lost; /**< true if RC reception lost */
|
||||
bool rc_signal_lost_cmd; /**< true if RC lost mode is commanded */
|
||||
bool rc_input_blocked; /**< set if RC input should be ignored */
|
||||
|
||||
bool data_link_lost; /**< datalink to GCS lost */
|
||||
bool data_link_lost; /**< datalink to GCS lost */
|
||||
bool data_link_lost_cmd; /**< datalink to GCS lost mode commanded */
|
||||
uint8_t data_link_lost_counter; /**< counts unique data link lost events */
|
||||
bool engine_failure; /** Set to true if an engine failure is detected */
|
||||
bool engine_failure_cmd; /** Set to true if an engine failure mode is commanded */
|
||||
bool gps_failure; /** Set to true if a gps failure is detected */
|
||||
bool gps_failure_cmd; /** Set to true if a gps failure mode is commanded */
|
||||
|
||||
bool barometer_failure; /** Set to true if a barometer failure is detected */
|
||||
|
||||
bool offboard_control_signal_found_once;
|
||||
bool offboard_control_signal_lost;
|
||||
|
|
|
@ -654,9 +654,28 @@ pwm_main(int argc, char *argv[])
|
|||
}
|
||||
}
|
||||
exit(0);
|
||||
} else if (!strcmp(argv[1], "terminatefail")) {
|
||||
|
||||
if (argc < 3) {
|
||||
errx(1, "arg missing [on|off]");
|
||||
} else {
|
||||
|
||||
if (!strcmp(argv[2], "on")) {
|
||||
/* force failsafe */
|
||||
ret = ioctl(fd, PWM_SERVO_SET_TERMINATION_FAILSAFE, 1);
|
||||
} else {
|
||||
/* force failsafe */
|
||||
ret = ioctl(fd, PWM_SERVO_SET_TERMINATION_FAILSAFE, 0);
|
||||
}
|
||||
|
||||
if (ret != OK) {
|
||||
warnx("FAILED setting termination failsafe %s", argv[2]);
|
||||
}
|
||||
}
|
||||
exit(0);
|
||||
}
|
||||
|
||||
usage("specify arm|disarm|rate|failsafe|disarmed|min|max|test|info|forcefail");
|
||||
usage("specify arm|disarm|rate|failsafe\n\t\tdisarmed|min|max|test|info|forcefail|terminatefail");
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue