Compare commits

..

1 Commits

Author SHA1 Message Date
Matthias Grob e2c80c7970 vehicle_command_ack: rename result_param1 to progress and comment usage
To avoid confusion:
- naming consistent with MAVLink definition
- comments about the few different ways the field is used
2024-06-18 16:44:11 +02:00
35 changed files with 136 additions and 577 deletions
+1 -1
View File
@@ -223,7 +223,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
data_plot.save()
data_plot.close()
# plot innovation flags summary
# plot innovation_check_flags summary
data_plot = CheckFlagsPlot(
status_flags_time, estimator_status_flags, [['reject_hor_vel', 'reject_hor_pos'], ['reject_ver_vel', 'reject_ver_pos',
'reject_hagl'],
+4
View File
@@ -39,6 +39,7 @@ CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
@@ -57,6 +58,7 @@ CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
@@ -68,6 +70,7 @@ CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
@@ -95,3 +98,4 @@ CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_FAKE_GPS=y
-1
View File
@@ -6,7 +6,6 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=n
CONFIG_DRIVERS_CAMERA_TRIGGER=n
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_MODULES_DIFFERENTIAL_DRIVE=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_PAYLOAD_DELIVERER=n
@@ -154,6 +154,7 @@
*(.text._ZN3Ekf20updateIMUBiasInhibitERKN9estimator9imuSampleE)
*(.text._ZN9Commander13dataLinkCheckEv)
*(.text._ZN17FlightModeManager10switchTaskE15FlightTaskIndex)
*(.text._ZNK3Ekf26get_innovation_test_statusERtRfS1_S1_S1_S1_S1_S1_)
*(.text._ZN12PX4Gyroscope9set_scaleEf)
*(.text._ZN12FailsafeBase6updateERKyRKNS_5StateEbbRK16failsafe_flags_s)
*(.text._ZN18MavlinkStreamDebug4sendEv)
-1
View File
@@ -40,7 +40,6 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_MODE_REGISTER=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
CONFIG_MODULES_PAYLOAD_DELIVERER=y
+20 -7
View File
@@ -69,14 +69,27 @@ uint32 filter_fault_flags # Bitmask to indicate EKF internal faults
float32 pos_horiz_accuracy # 1-Sigma estimated horizontal position accuracy relative to the estimators origin (m)
float32 pos_vert_accuracy # 1-Sigma estimated vertical position accuracy relative to the estimators origin (m)
uint16 innovation_check_flags # Bitmask to indicate pass/fail status of innovation consistency checks
# 0 - true if velocity observations have been rejected
# 1 - true if horizontal position observations have been rejected
# 2 - true if true if vertical position observations have been rejected
# 3 - true if the X magnetometer observation has been rejected
# 4 - true if the Y magnetometer observation has been rejected
# 5 - true if the Z magnetometer observation has been rejected
# 6 - true if the yaw observation has been rejected
# 7 - true if the airspeed observation has been rejected
# 8 - true if the synthetic sideslip observation has been rejected
# 9 - true if the height above ground observation has been rejected
# 10 - true if the X optical flow observation has been rejected
# 11 - true if the Y optical flow observation has been rejected
float32 mag_test_ratio # low-pass filtered ratio of the largest magnetometer innovation component to the innovation test limit
float32 vel_test_ratio # low-pass filtered ratio of the largest velocity innovation component to the innovation test limit
float32 pos_test_ratio # low-pass filtered ratio of the largest horizontal position innovation component to the innovation test limit
float32 hgt_test_ratio # low-pass filtered ratio of the vertical position innovation to the innovation test limit
float32 tas_test_ratio # low-pass filtered ratio of the true airspeed innovation to the innovation test limit
float32 hagl_test_ratio # low-pass filtered ratio of the height above ground innovation to the innovation test limit
float32 beta_test_ratio # low-pass filtered ratio of the synthetic sideslip innovation to the innovation test limit
float32 mag_test_ratio # ratio of the largest magnetometer innovation component to the innovation test limit
float32 vel_test_ratio # ratio of the largest velocity innovation component to the innovation test limit
float32 pos_test_ratio # ratio of the largest horizontal position innovation component to the innovation test limit
float32 hgt_test_ratio # ratio of the vertical position innovation to the innovation test limit
float32 tas_test_ratio # ratio of the true airspeed innovation to the innovation test limit
float32 hagl_test_ratio # ratio of the height above ground innovation to the innovation test limit
float32 beta_test_ratio # ratio of the synthetic sideslip innovation to the innovation test limit
uint16 solution_status_flags # Bitmask indicating which filter kinematic state outputs are valid for flight control use.
# 0 - True if the attitude estimate is good
+1 -1
View File
@@ -25,7 +25,7 @@ uint8 ORB_QUEUE_LENGTH = 4
uint32 command # Command that is being acknowledged
uint8 result # Command result
uint8 result_param1 # Also used as progress[%], it can be set with the reason why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS
uint8 progress # Also used as progress[%], it can be set with the reason why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS
int32 result_param2 # Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
uint8 target_system
uint16 target_component # Target component / mode executor
+2 -2
View File
@@ -74,9 +74,9 @@ ssize_t Serial::read(uint8_t *buffer, size_t buffer_size)
return _impl.read(buffer, buffer_size);
}
ssize_t Serial::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_ms)
ssize_t Serial::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
{
return _impl.readAtLeast(buffer, buffer_size, character_count, timeout_ms);
return _impl.readAtLeast(buffer, buffer_size, character_count, timeout_us);
}
ssize_t Serial::write(const void *buffer, size_t buffer_size)
@@ -62,7 +62,7 @@ public:
bool close();
ssize_t read(uint8_t *buffer, size_t buffer_size);
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_ms = 0);
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0);
ssize_t write(const void *buffer, size_t buffer_size);
@@ -251,7 +251,7 @@ ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
return ret;
}
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_ms)
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
{
if (!_open) {
PX4_ERR("Cannot readAtLeast from serial device until it has been opened");
@@ -264,7 +264,6 @@ ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t char
}
const hrt_abstime start_time_us = hrt_absolute_time();
hrt_abstime timeout_us = timeout_ms * 1000;
int total_bytes_read = 0;
while ((total_bytes_read < (int) character_count) && (hrt_elapsed_time(&start_time_us) < timeout_us)) {
@@ -244,7 +244,7 @@ ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
return ret;
}
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_ms)
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
{
if (!_open) {
PX4_ERR("Cannot readAtLeast from serial device until it has been opened");
@@ -257,7 +257,6 @@ ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t char
}
const hrt_abstime start_time_us = hrt_absolute_time();
hrt_abstime timeout_us = timeout_ms * 1000;
int total_bytes_read = 0;
while ((total_bytes_read < (int) character_count) && (hrt_elapsed_time(&start_time_us) < timeout_us)) {
+1 -2
View File
@@ -173,7 +173,7 @@ ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
return ret_read;
}
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_ms)
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
{
if (!_open) {
PX4_ERR("Cannot readAtLeast from serial device until it has been opened");
@@ -186,7 +186,6 @@ ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t char
}
const hrt_abstime start_time_us = hrt_absolute_time();
hrt_abstime timeout_us = timeout_ms * 1000;
int total_bytes_read = 0;
while (total_bytes_read < (int) character_count) {
-5
View File
@@ -290,11 +290,6 @@ inline bool isFinite(const float &value)
return PX4_ISFINITE(value);
}
inline bool isFinite(const matrix::Vector2f &value)
{
return value.isAllFinite();
}
inline bool isFinite(const matrix::Vector3f &value)
{
return value.isAllFinite();
@@ -251,7 +251,7 @@ void arm_auth_update(hrt_abstime now, bool param_update)
case vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED:
default:
switch (command_ack.result_param1) {
switch (command_ack.progress) { // It's not used as progress but as protocol parameter for arm authorization
case vehicle_command_ack_s::ARM_AUTH_DENIED_REASON_NONE:
/* Authorizer will send reason to ground station */
break;
@@ -151,8 +151,6 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed
#if defined(MODULE_NAME)
aid_src.timestamp = hrt_absolute_time();
_estimator_aid_src_aux_global_position_pub.publish(aid_src);
_test_ratio_filtered = math::max(fabsf(aid_src.test_ratio_filtered[0]), fabsf(aid_src.test_ratio_filtered[1]));
#endif // MODULE_NAME
} else if ((_state != State::stopped) && isTimedOut(_time_last_buffer_push, imu_delayed.time_us, (uint64_t)5e6)) {
@@ -74,8 +74,6 @@ public:
updateParams();
}
float test_ratio_filtered() const { return _test_ratio_filtered; }
private:
bool isTimedOut(uint64_t last_sensor_timestamp, uint64_t time_delayed_us, uint64_t timeout_period) const
{
@@ -108,8 +106,6 @@ private:
State _state{State::stopped};
float _test_ratio_filtered{INFINITY};
#if defined(MODULE_NAME)
struct reset_counters_s {
uint8_t lat_lon{};
@@ -245,7 +245,6 @@ void Ekf::controlMagFusion()
if (reset_heading) {
_control_status.flags.yaw_align = true;
resetAidSourceStatusZeroInnovation(aid_src);
}
_control_status.flags.mag = true;
+7 -11
View File
@@ -383,17 +383,13 @@ public:
*counter = _state_reset_status.reset_count.quat;
}
float getHeadingInnovationTestRatio() const;
float getVelocityInnovationTestRatio() const;
float getHorizontalPositionInnovationTestRatio() const;
float getVerticalPositionInnovationTestRatio() const;
float getAirspeedInnovationTestRatio() const;
float getSyntheticSideslipInnovationTestRatio() const;
float getHeightAboveGroundInnovationTestRatio() const;
// get EKF innovation consistency check status information comprising of:
// status - a bitmask integer containing the pass/fail status for each EKF measurement innovation consistency check
// Innovation Test Ratios - these are the ratio of the innovation to the acceptance threshold.
// A value > 1 indicates that the sensor measurement has exceeded the maximum acceptable level and has been rejected by the EKF
// Where a measurement type is a vector quantity, eg magnetometer, GPS position, etc, the maximum value is returned.
void get_innovation_test_status(uint16_t &status, float &mag, float &vel, float &pos, float &hgt, float &tas,
float &hagl, float &beta) const;
// return a bitmask integer that describes which state estimates are valid
void get_ekf_soln_status(uint16_t *status) const;
+44 -109
View File
@@ -301,196 +301,131 @@ void Ekf::resetAccelBias()
resetAccelBiasCov();
}
float Ekf::getHeadingInnovationTestRatio() const
void Ekf::get_innovation_test_status(uint16_t &status, float &mag, float &vel, float &pos, float &hgt, float &tas,
float &hagl, float &beta) const
{
// return the largest heading innovation test ratio
float test_ratio = 0.f;
// return the integer bitmask containing the consistency check pass/fail status
status = _innov_check_fail_status.value;
// return the largest magnetometer innovation test ratio
mag = 0.f;
#if defined(CONFIG_EKF2_MAGNETOMETER)
if (_control_status.flags.mag_hdg ||_control_status.flags.mag_3D) {
for (auto &test_ratio_filtered : _aid_src_mag.test_ratio_filtered) {
test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered));
}
mag = math::max(mag, sqrtf(Vector3f(_aid_src_mag.test_ratio).max()));
}
#endif // CONFIG_EKF2_MAGNETOMETER
#if defined(CONFIG_EKF2_GNSS_YAW)
if (_control_status.flags.gps_yaw) {
test_ratio = math::max(test_ratio, fabsf(_aid_src_gnss_yaw.test_ratio_filtered));
mag = math::max(mag, sqrtf(_aid_src_gnss_yaw.test_ratio));
}
#endif // CONFIG_EKF2_GNSS_YAW
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_yaw) {
test_ratio = math::max(test_ratio, fabsf(_aid_src_ev_yaw.test_ratio_filtered));
mag = math::max(mag, sqrtf(_aid_src_ev_yaw.test_ratio));
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
return sqrtf(test_ratio);
}
float Ekf::getVelocityInnovationTestRatio() const
{
// return the largest velocity innovation test ratio
float test_ratio = -1.f;
// return the largest velocity and position innovation test ratio
vel = NAN;
pos = NAN;
#if defined(CONFIG_EKF2_GNSS)
if (_control_status.flags.gps) {
for (int i = 0; i < 3; i++) {
test_ratio = math::max(test_ratio, fabsf(_aid_src_gnss_vel.test_ratio_filtered[i]));
}
float gps_vel = sqrtf(Vector3f(_aid_src_gnss_vel.test_ratio).max());
vel = math::max(gps_vel, FLT_MIN);
float gps_pos = sqrtf(Vector2f(_aid_src_gnss_pos.test_ratio).max());
pos = math::max(gps_pos, FLT_MIN);
}
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_vel) {
for (int i = 0; i < 3; i++) {
test_ratio = math::max(test_ratio, fabsf(_aid_src_ev_vel.test_ratio_filtered[i]));
}
float ev_vel = sqrtf(Vector3f(_aid_src_ev_vel.test_ratio).max());
vel = math::max(vel, ev_vel, FLT_MIN);
}
if (_control_status.flags.ev_pos) {
float ev_pos = sqrtf(Vector2f(_aid_src_ev_pos.test_ratio).max());
pos = math::max(pos, ev_pos, FLT_MIN);
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
#if defined(CONFIG_EKF2_OPTICAL_FLOW)
if (isOnlyActiveSourceOfHorizontalAiding(_control_status.flags.opt_flow)) {
for (auto &test_ratio_filtered : _aid_src_optical_flow.test_ratio_filtered) {
test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered));
}
float of_vel = sqrtf(Vector2f(_aid_src_optical_flow.test_ratio).max());
vel = math::max(of_vel, FLT_MIN);
}
#endif // CONFIG_EKF2_OPTICAL_FLOW
if (PX4_ISFINITE(test_ratio) && (test_ratio >= 0.f)) {
return sqrtf(test_ratio);
}
return NAN;
}
float Ekf::getHorizontalPositionInnovationTestRatio() const
{
// return the largest position innovation test ratio
float test_ratio = -1.f;
#if defined(CONFIG_EKF2_GNSS)
if (_control_status.flags.gps) {
for (auto &test_ratio_filtered : _aid_src_gnss_pos.test_ratio_filtered) {
test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered));
}
}
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_pos) {
for (auto &test_ratio_filtered : _aid_src_ev_pos.test_ratio_filtered) {
test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered));
}
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
#if defined(CONFIG_EKF2_AUX_GLOBAL_POSITION) && defined(MODULE_NAME)
if (_control_status.flags.aux_gpos) {
test_ratio = math::max(test_ratio, fabsf(_aux_global_position.test_ratio_filtered()));
}
#endif // CONFIG_EKF2_AUX_GLOBAL_POSITION
if (PX4_ISFINITE(test_ratio) && (test_ratio >= 0.f)) {
return sqrtf(test_ratio);
}
return NAN;
}
float Ekf::getVerticalPositionInnovationTestRatio() const
{
// return the combined vertical position innovation test ratio
float hgt_sum = 0.f;
int n_hgt_sources = 0;
#if defined(CONFIG_EKF2_BAROMETER)
if (_control_status.flags.baro_hgt) {
hgt_sum += sqrtf(fabsf(_aid_src_baro_hgt.test_ratio_filtered));
hgt_sum += sqrtf(_aid_src_baro_hgt.test_ratio);
n_hgt_sources++;
}
#endif // CONFIG_EKF2_BAROMETER
#if defined(CONFIG_EKF2_GNSS)
if (_control_status.flags.gps_hgt) {
hgt_sum += sqrtf(fabsf(_aid_src_gnss_hgt.test_ratio_filtered));
hgt_sum += sqrtf(_aid_src_gnss_hgt.test_ratio);
n_hgt_sources++;
}
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_RANGE_FINDER)
if (_control_status.flags.rng_hgt) {
hgt_sum += sqrtf(fabsf(_aid_src_rng_hgt.test_ratio_filtered));
hgt_sum += sqrtf(_aid_src_rng_hgt.test_ratio);
n_hgt_sources++;
}
#endif // CONFIG_EKF2_RANGE_FINDER
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_hgt) {
hgt_sum += sqrtf(fabsf(_aid_src_ev_hgt.test_ratio_filtered));
hgt_sum += sqrtf(_aid_src_ev_hgt.test_ratio);
n_hgt_sources++;
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
if (n_hgt_sources > 0) {
return math::max(hgt_sum / static_cast<float>(n_hgt_sources), FLT_MIN);
hgt = math::max(hgt_sum / static_cast<float>(n_hgt_sources), FLT_MIN);
} else {
hgt = NAN;
}
return NAN;
}
float Ekf::getAirspeedInnovationTestRatio() const
{
#if defined(CONFIG_EKF2_AIRSPEED)
if (_control_status.flags.fuse_aspd) {
// return the airspeed fusion innovation test ratio
return sqrtf(fabsf(_aid_src_airspeed.test_ratio_filtered));
}
// return the airspeed fusion innovation test ratio
tas = sqrtf(_aid_src_airspeed.test_ratio);
#endif // CONFIG_EKF2_AIRSPEED
return NAN;
}
float Ekf::getSyntheticSideslipInnovationTestRatio() const
{
#if defined(CONFIG_EKF2_SIDESLIP)
if (_control_status.flags.fuse_beta) {
// return the synthetic sideslip innovation test ratio
return sqrtf(fabsf(_aid_src_sideslip.test_ratio_filtered));
}
#endif // CONFIG_EKF2_SIDESLIP
return NAN;
}
float Ekf::getHeightAboveGroundInnovationTestRatio() const
{
float test_ratio = -1.f;
hagl = NAN;
#if defined(CONFIG_EKF2_TERRAIN)
# if defined(CONFIG_EKF2_RANGE_FINDER)
if (_hagl_sensor_status.flags.range_finder) {
// return the terrain height innovation test ratio
test_ratio = math::max(test_ratio, fabsf(_aid_src_terrain_range_finder.test_ratio_filtered));
hagl = sqrtf(_aid_src_terrain_range_finder.test_ratio);
}
#endif // CONFIG_EKF2_RANGE_FINDER
# if defined(CONFIG_EKF2_OPTICAL_FLOW)
if (_hagl_sensor_status.flags.flow) {
// return the terrain height innovation test ratio
for (auto &test_ratio_filtered : _aid_src_terrain_optical_flow.test_ratio_filtered) {
test_ratio = math::max(test_ratio, fabsf(test_ratio_filtered));
}
hagl = sqrtf(math::max(_aid_src_terrain_optical_flow.test_ratio[0], _aid_src_terrain_optical_flow.test_ratio[1]));
}
# endif // CONFIG_EKF2_OPTICAL_FLOW
#endif // CONFIG_EKF2_TERRAIN
if (PX4_ISFINITE(test_ratio) && (test_ratio >= 0.f)) {
return sqrtf(test_ratio);
}
return NAN;
#if defined(CONFIG_EKF2_SIDESLIP)
// return the synthetic sideslip innovation test ratio
beta = sqrtf(_aid_src_sideslip.test_ratio);
#endif // CONFIG_EKF2_SIDESLIP
}
void Ekf::get_ekf_soln_status(uint16_t *status) const
+9 -7
View File
@@ -1802,13 +1802,15 @@ void EKF2::PublishStatus(const hrt_abstime &timestamp)
status.control_mode_flags = _ekf.control_status().value;
status.filter_fault_flags = _ekf.fault_status().value;
status.mag_test_ratio = _ekf.getHeadingInnovationTestRatio();
status.vel_test_ratio = _ekf.getVelocityInnovationTestRatio();
status.pos_test_ratio = _ekf.getHorizontalPositionInnovationTestRatio();
status.hgt_test_ratio = _ekf.getVerticalPositionInnovationTestRatio();
status.tas_test_ratio = _ekf.getAirspeedInnovationTestRatio();
status.hagl_test_ratio = _ekf.getHeightAboveGroundInnovationTestRatio();
status.beta_test_ratio = _ekf.getSyntheticSideslipInnovationTestRatio();
uint16_t innov_check_flags_temp = 0;
_ekf.get_innovation_test_status(innov_check_flags_temp, status.mag_test_ratio,
status.vel_test_ratio, status.pos_test_ratio,
status.hgt_test_ratio, status.tas_test_ratio,
status.hagl_test_ratio, status.beta_test_ratio);
// Bit mismatch between ecl and Firmware, combine the 2 first bits to preserve msg definition
// TODO: legacy use only, those flags are also in estimator_status_flags
status.innovation_check_flags = (innov_check_flags_temp >> 1) | (innov_check_flags_temp & 0x1);
_ekf.get_ekf_lpos_accuracy(&status.pos_horiz_accuracy, &status.pos_vert_accuracy);
_ekf.get_ekf_soln_status(&status.solution_status_flags);
+1 -1
View File
@@ -518,7 +518,7 @@ InputMavlinkGimbalV2::update(unsigned int timeout_ms, ControlData &control_data,
// We can't return early instead because we need to copy all topics that triggered poll.
bool exit_loop = false;
UpdateResult update_result = UpdateResult::NoUpdate;
UpdateResult update_result = already_active ? UpdateResult::UpdatedActive : UpdateResult::NoUpdate;
while (!exit_loop && poll_timeout >= 0) {
+1 -1
View File
@@ -2604,7 +2604,7 @@ void Mavlink::handleAndGetCurrentCommandAck()
mavlink_command_ack_t msg{};
msg.result = command_ack.result;
msg.command = command_ack.command;
msg.progress = command_ack.result_param1;
msg.progress = command_ack.progress;
msg.result_param2 = command_ack.result_param2;
msg.target_system = command_ack.target_system;
msg.target_component = command_ack.target_component;
+2 -2
View File
@@ -127,7 +127,7 @@ MavlinkReceiver::acknowledge(uint8_t sysid, uint8_t compid, uint16_t command, ui
command_ack.result = result;
command_ack.target_system = sysid;
command_ack.target_component = compid;
command_ack.result_param1 = progress;
command_ack.progress = progress;
_cmd_ack_pub.publish(command_ack);
}
@@ -771,7 +771,7 @@ MavlinkReceiver::handle_message_command_ack(mavlink_message_t *msg)
command_ack.command = ack.command;
command_ack.result = ack.result;
command_ack.from_external = true;
command_ack.result_param1 = ack.progress;
command_ack.progress = ack.progress;
command_ack.target_system = ack.target_system;
command_ack.target_component = ack.target_component;
@@ -309,7 +309,8 @@ private:
if (_estimator_status_sub.update(&estimator_status)) {
if (estimator_status.gps_check_fail_flags > 0 ||
estimator_status.filter_fault_flags > 0) {
estimator_status.filter_fault_flags > 0 ||
estimator_status.innovation_check_flags > 0) {
msg->failure_flags |= HL_FAILURE_FLAG_ESTIMATOR;
}
@@ -42,11 +42,14 @@
using namespace matrix;
MulticopterPositionControl::MulticopterPositionControl(bool vtol) :
SuperBlock(nullptr, "MPC"),
ModuleParams(nullptr),
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers),
_vehicle_attitude_setpoint_pub(vtol ? ORB_ID(mc_virtual_attitude_setpoint) : ORB_ID(vehicle_attitude_setpoint))
_vehicle_attitude_setpoint_pub(vtol ? ORB_ID(mc_virtual_attitude_setpoint) : ORB_ID(vehicle_attitude_setpoint)),
_vel_x_deriv(this, "VELD"),
_vel_y_deriv(this, "VELD"),
_vel_z_deriv(this, "VELD")
{
_sample_interval_s.update(0.01f); // 100 Hz default
parameters_update(true);
_tilt_limit_slew_rate.setSlewRate(.2f);
_takeoff_status_pub.advertise();
@@ -80,42 +83,7 @@ void MulticopterPositionControl::parameters_update(bool force)
// update parameters from storage
ModuleParams::updateParams();
float sample_freq_hz = 1.f / _sample_interval_s.mean();
// velocity notch filter
if ((_param_mpc_vel_nf_frq.get() > 0.f) && (_param_mpc_vel_nf_bw.get() > 0.f)) {
_vel_xy_notch_filter.setParameters(sample_freq_hz, _param_mpc_vel_nf_frq.get(), _param_mpc_vel_nf_bw.get());
_vel_z_notch_filter.setParameters(sample_freq_hz, _param_mpc_vel_nf_frq.get(), _param_mpc_vel_nf_bw.get());
} else {
_vel_xy_notch_filter.disable();
_vel_z_notch_filter.disable();
}
// velocity xy/z low pass filter
if (_param_mpc_vel_lp.get() > 0.f) {
_vel_xy_lp_filter.setCutoffFreq(sample_freq_hz, _param_mpc_vel_lp.get());
_vel_z_lp_filter.setCutoffFreq(sample_freq_hz, _param_mpc_vel_lp.get());
} else {
// disable filtering
_vel_xy_lp_filter.setAlpha(1.f);
_vel_z_lp_filter.setAlpha(1.f);
}
// velocity derivative xy/z low pass filter
if (_param_mpc_veld_lp.get() > 0.f) {
_vel_deriv_xy_lp_filter.setCutoffFreq(sample_freq_hz, _param_mpc_veld_lp.get());
_vel_deriv_z_lp_filter.setCutoffFreq(sample_freq_hz, _param_mpc_veld_lp.get());
} else {
// disable filtering
_vel_deriv_xy_lp_filter.setAlpha(1.f);
_vel_deriv_z_lp_filter.setAlpha(1.f);
}
SuperBlock::updateParams();
int num_changed = 0;
@@ -308,7 +276,7 @@ void MulticopterPositionControl::parameters_update(bool force)
}
PositionControlStates MulticopterPositionControl::set_vehicle_states(const vehicle_local_position_s
&vehicle_local_position, const float dt_s)
&vehicle_local_position)
{
PositionControlStates states;
@@ -332,42 +300,29 @@ PositionControlStates MulticopterPositionControl::set_vehicle_states(const vehic
const Vector2f velocity_xy(vehicle_local_position.vx, vehicle_local_position.vy);
if (vehicle_local_position.v_xy_valid && velocity_xy.isAllFinite()) {
const Vector2f vel_xy_prev = _vel_xy_lp_filter.getState();
// vel xy notch filter, then low pass filter
states.velocity.xy() = _vel_xy_lp_filter.update(_vel_xy_notch_filter.apply(velocity_xy));
// vel xy derivative low pass filter
states.acceleration.xy() = _vel_deriv_xy_lp_filter.update((_vel_xy_lp_filter.getState() - vel_xy_prev) / dt_s);
states.velocity.xy() = velocity_xy;
states.acceleration(0) = _vel_x_deriv.update(velocity_xy(0));
states.acceleration(1) = _vel_y_deriv.update(velocity_xy(1));
} else {
states.velocity(0) = states.velocity(1) = NAN;
states.acceleration(0) = states.acceleration(1) = NAN;
// reset filters to prevent acceleration spikes when regaining velocity
_vel_xy_lp_filter.reset({});
_vel_xy_notch_filter.reset();
_vel_deriv_xy_lp_filter.reset({});
// reset derivatives to prevent acceleration spikes when regaining velocity
_vel_x_deriv.reset();
_vel_y_deriv.reset();
}
if (PX4_ISFINITE(vehicle_local_position.vz) && vehicle_local_position.v_z_valid) {
const float vel_z_prev = _vel_z_lp_filter.getState();
// vel z notch filter, then low pass filter
states.velocity(2) = _vel_z_lp_filter.update(_vel_z_notch_filter.apply(vehicle_local_position.vz));
// vel z derivative low pass filter
states.acceleration(2) = _vel_deriv_z_lp_filter.update((_vel_z_lp_filter.getState() - vel_z_prev) / dt_s);
states.velocity(2) = vehicle_local_position.vz;
states.acceleration(2) = _vel_z_deriv.update(states.velocity(2));
} else {
states.velocity(2) = NAN;
states.acceleration(2) = NAN;
// reset filters to prevent acceleration spikes when regaining velocity
_vel_z_lp_filter.reset({});
_vel_z_notch_filter.reset();
_vel_deriv_z_lp_filter.reset({});
// reset derivative to prevent acceleration spikes when regaining velocity
_vel_z_deriv.reset();
}
states.yaw = vehicle_local_position.heading;
@@ -396,7 +351,8 @@ void MulticopterPositionControl::Run()
math::constrain(((vehicle_local_position.timestamp_sample - _time_stamp_last_loop) * 1e-6f), 0.002f, 0.04f);
_time_stamp_last_loop = vehicle_local_position.timestamp_sample;
_sample_interval_s.update(dt);
// set _dt in controllib Block for BlockDerivative
setDt(dt);
if (_vehicle_control_mode_sub.updated()) {
const bool previous_position_control_enabled = _vehicle_control_mode.flag_multicopter_position_control_enabled;
@@ -424,7 +380,7 @@ void MulticopterPositionControl::Run()
}
}
PositionControlStates states{set_vehicle_states(vehicle_local_position, dt)};
PositionControlStates states{set_vehicle_states(vehicle_local_position)};
// if a goto setpoint available this publishes a trajectory setpoint to go there
if (_goto_control.checkForSetpoint(vehicle_local_position.timestamp_sample,
@@ -682,13 +638,12 @@ void MulticopterPositionControl::adjustSetpointForEKFResets(const vehicle_local_
}
if (vehicle_local_position.vxy_reset_counter != _vxy_reset_counter) {
_vel_xy_lp_filter.reset(_vel_xy_lp_filter.getState() + Vector2f(vehicle_local_position.delta_vxy));
_vel_xy_notch_filter.reset();
_vel_x_deriv.reset();
_vel_y_deriv.reset();
}
if (vehicle_local_position.vz_reset_counter != _vz_reset_counter) {
_vel_z_lp_filter.reset(_vel_z_lp_filter.getState() + vehicle_local_position.delta_vz);
_vel_z_notch_filter.reset();
_vel_z_deriv.reset();
}
// save latest reset counters
@@ -42,9 +42,7 @@
#include "GotoControl/GotoControl.hpp"
#include <drivers/drv_hrt.h>
#include <lib/mathlib/math/filter/AlphaFilter.hpp>
#include <lib/mathlib/math/filter/NotchFilter.hpp>
#include <lib/mathlib/math/WelfordMean.hpp>
#include <lib/controllib/blocks.hpp>
#include <lib/perf/perf_counter.h>
#include <lib/slew_rate/SlewRateYaw.hpp>
#include <lib/systemlib/mavlink_log.h>
@@ -70,8 +68,8 @@
using namespace time_literals;
class MulticopterPositionControl : public ModuleBase<MulticopterPositionControl>, public ModuleParams,
public px4::ScheduledWorkItem
class MulticopterPositionControl : public ModuleBase<MulticopterPositionControl>, public control::SuperBlock,
public ModuleParams, public px4::ScheduledWorkItem
{
public:
MulticopterPositionControl(bool vtol = false);
@@ -150,11 +148,6 @@ private:
(ParamBool<px4::params::MPC_USE_HTE>) _param_mpc_use_hte,
(ParamBool<px4::params::MPC_ACC_DECOUPLE>) _param_mpc_acc_decouple,
(ParamFloat<px4::params::MPC_VEL_LP>) _param_mpc_vel_lp,
(ParamFloat<px4::params::MPC_VEL_NF_FRQ>) _param_mpc_vel_nf_frq,
(ParamFloat<px4::params::MPC_VEL_NF_BW>) _param_mpc_vel_nf_bw,
(ParamFloat<px4::params::MPC_VELD_LP>) _param_mpc_veld_lp,
// Takeoff / Land
(ParamFloat<px4::params::COM_SPOOLUP_TIME>) _param_com_spoolup_time, /**< time to let motors spool up after arming */
(ParamBool<px4::params::COM_THROW_EN>) _param_com_throw_en, /**< throw launch enabled */
@@ -192,16 +185,9 @@ private:
(ParamFloat<px4::params::MPC_YAWRAUTO_ACC>) _param_mpc_yawrauto_acc
);
math::WelfordMean<float> _sample_interval_s{};
AlphaFilter<matrix::Vector2f> _vel_xy_lp_filter{};
AlphaFilter<float> _vel_z_lp_filter{};
math::NotchFilter<matrix::Vector2f> _vel_xy_notch_filter{};
math::NotchFilter<float> _vel_z_notch_filter{};
AlphaFilter<matrix::Vector2f> _vel_deriv_xy_lp_filter{};
AlphaFilter<float> _vel_deriv_z_lp_filter{};
control::BlockDerivative _vel_x_deriv; /**< velocity derivative in x */
control::BlockDerivative _vel_y_deriv; /**< velocity derivative in y */
control::BlockDerivative _vel_z_deriv; /**< velocity derivative in z */
GotoControl _goto_control; ///< class for handling smooth goto position setpoints
PositionControl _control; ///< class for core PID position control
@@ -238,7 +224,7 @@ private:
/**
* Check for validity of positon/velocity states.
*/
PositionControlStates set_vehicle_states(const vehicle_local_position_s &local_pos, const float dt_s);
PositionControlStates set_vehicle_states(const vehicle_local_position_s &local_pos);
/**
* Generate setpoint to bridge no executable setpoint being available.
@@ -75,56 +75,11 @@ PARAM_DEFINE_INT32(MPC_USE_HTE, 1);
PARAM_DEFINE_FLOAT(MPC_THR_XY_MARG, 0.3f);
/**
* Velocity low pass cutoff frequency
*
* A value of 0 disables the filter.
* Numerical velocity derivative low pass cutoff frequency
*
* @unit Hz
* @min 0
* @max 50
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_VEL_LP, 0.0f);
/**
* Velocity notch filter frequency
*
* The center frequency for the 2nd order notch filter on the velocity.
* A value of 0 disables the filter.
*
* @unit Hz
* @min 0
* @max 50
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_VEL_NF_FRQ, 0.0f);
/**
* Velocity notch filter bandwidth
*
* A value of 0 disables the filter.
*
* @unit Hz
* @min 0
* @max 50
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_VEL_NF_BW, 5.0f);
/**
* Velocity derivative low pass cutoff frequency
*
* A value of 0 disables the filter.
*
* @unit Hz
* @min 0
* @max 50
* @max 10
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control
-40
View File
@@ -1,40 +0,0 @@
############################################################################
#
# Copyright (c) 2015 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.
#
############################################################################
px4_add_module(
MODULE modules__mode_register
MAIN mode_register
SRCS
ModeRegister.cpp
ModeRegister.hpp
DEPENDS
)
-5
View File
@@ -1,5 +0,0 @@
menuconfig MODULES_MODE_REGISTER
bool "mode_register"
default n
---help---
Enable support for internal mode reigstration
-180
View File
@@ -1,180 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2024 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.
*
****************************************************************************/
#include "ModeRegister.hpp"
#include <px4_platform_common/log.h>
ModeRegister::ModeRegister() :
ModuleParams(nullptr),
WorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers),
_loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle"))
{
// PX4_INFO("Hello Mode Register");
doRegister();
}
ModeRegister::~ModeRegister()
{
perf_free(_loop_perf);
}
bool
ModeRegister::init()
{
if (!_register_ext_component_reply_sub.registerCallback()) {
PX4_ERR("callback registration failed");
return false;
}
return true;
}
bool ModeRegister::doRegister()
{
// assert(!_registration->registered());
// if (!_skip_message_compatibility_check &&
// !messageCompatibilityCheck(node(), {ALL_PX4_ROS2_MESSAGES}, topicNamespacePrefix()))
// {
// return false;
// }
// onAboutToRegister();
register_ext_component_request_s request;
strcpy(request.name, "Internal Mode");
request.register_arming_check = true;
request.register_mode = true;
request.register_mode_executor = true;
request.enable_replace_internal_mode = true;
request.replace_internal_mode = true;
request.activate_mode_immediately = false;
request.px4_ros2_api_version = 1;
request.request_id = 123;
_register_ext_component_request_pub.publish(request);
// _health_and_arming_checks.overrideRegistration(_registration);
// const RegistrationSettings settings = getRegistrationSettings();
bool ret = true;
// = _registration->doRegister(settings);
// if (ret) {
// if (!onRegistered()) {
// ret = false;
// }
// }
return ret;
}
void
ModeRegister::Run()
{
if (should_exit()) {
_register_ext_component_reply_sub.unregisterCallback();
exit_and_cleanup();
return;
}
perf_begin(_loop_perf);
PX4_INFO("Fuuuuuuuuuck");
if (!_requested) {
PX4_INFO("Do Register");
doRegister();
_requested = true;
}
register_ext_component_reply_s reply;
if (_register_ext_component_reply_sub.update(&reply)) {
PX4_INFO("Replied!");
PX4_INFO(" - success: %f", double(reply.success));
}
perf_end(_loop_perf);
}
int ModeRegister::task_spawn(int argc, char *argv[])
{
ModeRegister *instance = new ModeRegister();
if (instance) {
_object.store(instance);
_task_id = task_id_is_work_queue;
if (instance->init()) {
return PX4_OK;
}
} else {
PX4_ERR("alloc failed");
}
delete instance;
_object.store(nullptr);
_task_id = -1;
return PX4_ERROR;
}
int ModeRegister::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");
}
int ModeRegister::print_usage(const char *reason)
{
if (reason) {
PX4_WARN("%s\n", reason);
}
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
This implements an internal mode registration.
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("mode_register", "controller");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
return 0;
}
extern "C" __EXPORT int mode_register_main(int argc, char *argv[])
{
return ModeRegister::main(argc, argv);
}
@@ -1,47 +0,0 @@
#pragma once
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/Publication.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionCallback.hpp>
#include <uORB/topics/register_ext_component_reply.h>
#include <uORB/topics/register_ext_component_request.h>
#include <uORB/topics/unregister_ext_component.h>
class ModeRegister : public ModuleBase<ModeRegister>, public ModuleParams, public px4::WorkItem
{
public:
ModeRegister();
~ModeRegister() override;
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
/** @see ModuleBase */
static int custom_command(int argc, char *argv[]);
/** @see ModuleBase */
static int print_usage(const char *reason = nullptr);
bool doRegister();
bool init();
private:
void Run() override;
uORB::SubscriptionCallbackWorkItem _register_ext_component_reply_sub{this, ORB_ID(register_ext_component_reply)};
uORB::Publication<register_ext_component_request_s> _register_ext_component_request_pub{ORB_ID(register_ext_component_request)};
uORB::Publication<unregister_ext_component_s> _unregister_ext_component_pub{ORB_ID(unregister_ext_component)};
bool _requested{false};
perf_counter_t _loop_perf; /**< loop duration performance counter */
};
+1 -1
View File
@@ -1418,7 +1418,7 @@ void Navigator::publish_vehicle_command_ack(const vehicle_command_s &cmd, uint8_
command_ack.from_external = false;
command_ack.result = result;
command_ack.result_param1 = 0;
command_ack.progress = 0;
command_ack.result_param2 = 0;
_vehicle_cmd_ack_pub.publish(command_ack);
@@ -255,7 +255,7 @@ bool PayloadDeliverer::send_gripper_vehicle_command_ack(const hrt_abstime now, c
switch (command_result) {
case vehicle_command_ack_s::VEHICLE_CMD_RESULT_IN_PROGRESS:
// Fill in the progress percentage field for IN_PROGRESS ack message
vcmd_ack.result_param1 = UINT8_MAX;
vcmd_ack.progress = UINT8_MAX; // unkown progress according to MAVLink definition
break;
}