forked from Archive/PX4-Autopilot
Merge branch 'master' of github.com:PX4/Firmware into asfilter
This commit is contained in:
commit
628b735bc1
|
@ -736,6 +736,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||||
|
|
||||||
// CIRCUIT BREAKERS
|
// CIRCUIT BREAKERS
|
||||||
status.circuit_breaker_engaged_power_check = false;
|
status.circuit_breaker_engaged_power_check = false;
|
||||||
|
status.circuit_breaker_engaged_airspd_check = false;
|
||||||
|
|
||||||
/* publish initial state */
|
/* publish initial state */
|
||||||
status_pub = orb_advertise(ORB_ID(vehicle_status), &status);
|
status_pub = orb_advertise(ORB_ID(vehicle_status), &status);
|
||||||
|
@ -977,6 +978,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||||
param_get(_param_component_id, &(status.component_id));
|
param_get(_param_component_id, &(status.component_id));
|
||||||
|
|
||||||
status.circuit_breaker_engaged_power_check = circuit_breaker_enabled("CBRK_SUPPLY_CHK", CBRK_SUPPLY_CHK_KEY);
|
status.circuit_breaker_engaged_power_check = circuit_breaker_enabled("CBRK_SUPPLY_CHK", CBRK_SUPPLY_CHK_KEY);
|
||||||
|
status.circuit_breaker_engaged_airspd_check = circuit_breaker_enabled("CBRK_AIRSPD_CHK", CBRK_AIRSPD_CHK_KEY);
|
||||||
|
|
||||||
status_changed = true;
|
status_changed = true;
|
||||||
|
|
||||||
|
|
|
@ -669,7 +669,9 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd)
|
||||||
goto system_eval;
|
goto system_eval;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!status->is_rotary_wing) {
|
/* Perform airspeed check only if circuit breaker is not
|
||||||
|
* engaged and it's not a rotary wing */
|
||||||
|
if (!status->circuit_breaker_engaged_airspd_check && !status->is_rotary_wing) {
|
||||||
/* accel done, close it */
|
/* accel done, close it */
|
||||||
close(fd);
|
close(fd);
|
||||||
fd = orb_subscribe(ORB_ID(airspeed));
|
fd = orb_subscribe(ORB_ID(airspeed));
|
||||||
|
|
|
@ -630,10 +630,10 @@ FixedwingEstimator::check_filter_state()
|
||||||
rep.health_flags |= (((uint8_t)ekf_report.posHealth) << 1);
|
rep.health_flags |= (((uint8_t)ekf_report.posHealth) << 1);
|
||||||
rep.health_flags |= (((uint8_t)ekf_report.hgtHealth) << 2);
|
rep.health_flags |= (((uint8_t)ekf_report.hgtHealth) << 2);
|
||||||
rep.health_flags |= (((uint8_t)!ekf_report.gyroOffsetsExcessive) << 3);
|
rep.health_flags |= (((uint8_t)!ekf_report.gyroOffsetsExcessive) << 3);
|
||||||
// rep.health_flags |= (((uint8_t)ekf_report.onGround) << 4);
|
rep.health_flags |= (((uint8_t)ekf_report.onGround) << 4);
|
||||||
// rep.health_flags |= (((uint8_t)ekf_report.staticMode) << 5);
|
rep.health_flags |= (((uint8_t)ekf_report.staticMode) << 5);
|
||||||
// rep.health_flags |= (((uint8_t)ekf_report.useCompass) << 6);
|
rep.health_flags |= (((uint8_t)ekf_report.useCompass) << 6);
|
||||||
// rep.health_flags |= (((uint8_t)ekf_report.useAirspeed) << 7);
|
rep.health_flags |= (((uint8_t)ekf_report.useAirspeed) << 7);
|
||||||
|
|
||||||
rep.timeout_flags |= (((uint8_t)ekf_report.velTimeout) << 0);
|
rep.timeout_flags |= (((uint8_t)ekf_report.velTimeout) << 0);
|
||||||
rep.timeout_flags |= (((uint8_t)ekf_report.posTimeout) << 1);
|
rep.timeout_flags |= (((uint8_t)ekf_report.posTimeout) << 1);
|
||||||
|
@ -1465,25 +1465,6 @@ FixedwingEstimator::task_main()
|
||||||
_global_pos_pub = orb_advertise(ORB_ID(vehicle_global_position), &_global_pos);
|
_global_pos_pub = orb_advertise(ORB_ID(vehicle_global_position), &_global_pos);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (hrt_elapsed_time(&_wind.timestamp) > 99000) {
|
|
||||||
_wind.timestamp = _global_pos.timestamp;
|
|
||||||
_wind.windspeed_north = _ekf->states[14];
|
|
||||||
_wind.windspeed_east = _ekf->states[15];
|
|
||||||
_wind.covariance_north = 0.0f; // XXX get form filter
|
|
||||||
_wind.covariance_east = 0.0f;
|
|
||||||
|
|
||||||
/* lazily publish the wind estimate only once available */
|
|
||||||
if (_wind_pub > 0) {
|
|
||||||
/* publish the wind estimate */
|
|
||||||
orb_publish(ORB_ID(wind_estimate), _wind_pub, &_wind);
|
|
||||||
|
|
||||||
} else {
|
|
||||||
/* advertise and publish */
|
|
||||||
_wind_pub = orb_advertise(ORB_ID(wind_estimate), &_wind);
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
if (hrt_elapsed_time(&_wind.timestamp) > 99000) {
|
if (hrt_elapsed_time(&_wind.timestamp) > 99000) {
|
||||||
_wind.timestamp = _global_pos.timestamp;
|
_wind.timestamp = _global_pos.timestamp;
|
||||||
_wind.windspeed_north = _ekf->states[14];
|
_wind.windspeed_north = _ekf->states[14];
|
||||||
|
|
|
@ -3028,6 +3028,10 @@ void AttPosEKF::GetFilterState(struct ekf_status_report *err)
|
||||||
current_ekf_state.states[i] = states[i];
|
current_ekf_state.states[i] = states[i];
|
||||||
}
|
}
|
||||||
current_ekf_state.n_states = n_states;
|
current_ekf_state.n_states = n_states;
|
||||||
|
current_ekf_state.onGround = onGround;
|
||||||
|
current_ekf_state.staticMode = staticMode;
|
||||||
|
current_ekf_state.useCompass = useCompass;
|
||||||
|
current_ekf_state.useAirspeed = useAirspeed;
|
||||||
|
|
||||||
memcpy(err, ¤t_ekf_state, sizeof(*err));
|
memcpy(err, ¤t_ekf_state, sizeof(*err));
|
||||||
|
|
||||||
|
|
|
@ -68,6 +68,10 @@ struct ekf_status_report {
|
||||||
bool posTimeout;
|
bool posTimeout;
|
||||||
bool hgtTimeout;
|
bool hgtTimeout;
|
||||||
bool imuTimeout;
|
bool imuTimeout;
|
||||||
|
bool onGround;
|
||||||
|
bool staticMode;
|
||||||
|
bool useCompass;
|
||||||
|
bool useAirspeed;
|
||||||
uint32_t velFailTime;
|
uint32_t velFailTime;
|
||||||
uint32_t posFailTime;
|
uint32_t posFailTime;
|
||||||
uint32_t hgtFailTime;
|
uint32_t hgtFailTime;
|
||||||
|
|
|
@ -559,22 +559,39 @@ void Mavlink::mavlink_update_system(void)
|
||||||
_param_component_id = param_find("MAV_COMP_ID");
|
_param_component_id = param_find("MAV_COMP_ID");
|
||||||
_param_system_type = param_find("MAV_TYPE");
|
_param_system_type = param_find("MAV_TYPE");
|
||||||
_param_use_hil_gps = param_find("MAV_USEHILGPS");
|
_param_use_hil_gps = param_find("MAV_USEHILGPS");
|
||||||
_param_initialized = true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* update system and component id */
|
/* update system and component id */
|
||||||
int32_t system_id;
|
int32_t system_id;
|
||||||
param_get(_param_system_id, &system_id);
|
param_get(_param_system_id, &system_id);
|
||||||
|
|
||||||
if (system_id > 0 && system_id < 255) {
|
|
||||||
mavlink_system.sysid = system_id;
|
|
||||||
}
|
|
||||||
|
|
||||||
int32_t component_id;
|
int32_t component_id;
|
||||||
param_get(_param_component_id, &component_id);
|
param_get(_param_component_id, &component_id);
|
||||||
|
|
||||||
if (component_id > 0 && component_id < 255) {
|
|
||||||
mavlink_system.compid = component_id;
|
/* only allow system ID and component ID updates
|
||||||
|
* after reboot - not during operation */
|
||||||
|
if (!_param_initialized) {
|
||||||
|
if (system_id > 0 && system_id < 255) {
|
||||||
|
mavlink_system.sysid = system_id;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (component_id > 0 && component_id < 255) {
|
||||||
|
mavlink_system.compid = component_id;
|
||||||
|
}
|
||||||
|
|
||||||
|
_param_initialized = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* warn users that they need to reboot to take this
|
||||||
|
* into effect
|
||||||
|
*/
|
||||||
|
if (system_id != mavlink_system.sysid) {
|
||||||
|
send_statustext_critical("Save params and reboot to change SYSID");
|
||||||
|
}
|
||||||
|
|
||||||
|
if (component_id != mavlink_system.compid) {
|
||||||
|
send_statustext_critical("Save params and reboot to change COMPID");
|
||||||
}
|
}
|
||||||
|
|
||||||
int32_t system_type;
|
int32_t system_type;
|
||||||
|
|
|
@ -83,6 +83,18 @@ PARAM_DEFINE_INT32(CBRK_RATE_CTRL, 0);
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(CBRK_IO_SAFETY, 0);
|
PARAM_DEFINE_INT32(CBRK_IO_SAFETY, 0);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Circuit breaker for airspeed sensor
|
||||||
|
*
|
||||||
|
* Setting this parameter to 162128 will disable the check for an airspeed sensor.
|
||||||
|
* WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
|
||||||
|
*
|
||||||
|
* @min 0
|
||||||
|
* @max 162128
|
||||||
|
* @group Circuit Breaker
|
||||||
|
*/
|
||||||
|
PARAM_DEFINE_INT32(CBRK_AIRSPD_CHK, 0);
|
||||||
|
|
||||||
bool circuit_breaker_enabled(const char* breaker, int32_t magic)
|
bool circuit_breaker_enabled(const char* breaker, int32_t magic)
|
||||||
{
|
{
|
||||||
int32_t val;
|
int32_t val;
|
||||||
|
|
|
@ -52,6 +52,7 @@
|
||||||
#define CBRK_SUPPLY_CHK_KEY 894281
|
#define CBRK_SUPPLY_CHK_KEY 894281
|
||||||
#define CBRK_RATE_CTRL_KEY 140253
|
#define CBRK_RATE_CTRL_KEY 140253
|
||||||
#define CBRK_IO_SAFETY_KEY 22027
|
#define CBRK_IO_SAFETY_KEY 22027
|
||||||
|
#define CBRK_AIRSPD_CHK_KEY 162128
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
|
|
@ -226,6 +226,7 @@ struct vehicle_status_s {
|
||||||
uint16_t errors_count4;
|
uint16_t errors_count4;
|
||||||
|
|
||||||
bool circuit_breaker_engaged_power_check;
|
bool circuit_breaker_engaged_power_check;
|
||||||
|
bool circuit_breaker_engaged_airspd_check;
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
Loading…
Reference in New Issue