forked from Archive/PX4-Autopilot
msg: rename sensor_bias -> estimator_sensor_bias
This commit is contained in:
parent
db49e5abcd
commit
10410fc868
|
@ -61,6 +61,7 @@ set(msg_files
|
|||
esc_report.msg
|
||||
esc_status.msg
|
||||
estimator_innovations.msg
|
||||
estimator_sensor_bias.msg
|
||||
estimator_status.msg
|
||||
follow_target.msg
|
||||
geofence_result.msg
|
||||
|
@ -108,7 +109,6 @@ set(msg_files
|
|||
sensor_accel_integrated.msg
|
||||
sensor_accel_status.msg
|
||||
sensor_baro.msg
|
||||
sensor_bias.msg
|
||||
sensor_combined.msg
|
||||
sensor_correction.msg
|
||||
sensor_gyro.msg
|
||||
|
|
|
@ -147,7 +147,7 @@ rtps:
|
|||
- msg: sensor_baro
|
||||
id: 63
|
||||
send: true
|
||||
- msg: sensor_bias
|
||||
- msg: estimator_sensor_bias
|
||||
id: 64
|
||||
- msg: sensor_combined
|
||||
id: 65
|
||||
|
|
|
@ -56,15 +56,15 @@
|
|||
#include <uORB/SubscriptionCallback.hpp>
|
||||
#include <uORB/topics/airspeed.h>
|
||||
#include <uORB/topics/distance_sensor.h>
|
||||
#include <uORB/topics/estimator_innovations.h>
|
||||
#include <uORB/topics/ekf2_timestamps.h>
|
||||
#include <uORB/topics/ekf_gps_position.h>
|
||||
#include <uORB/topics/estimator_status.h>
|
||||
#include <uORB/topics/ekf_gps_drift.h>
|
||||
#include <uORB/topics/ekf_gps_position.h>
|
||||
#include <uORB/topics/estimator_innovations.h>
|
||||
#include <uORB/topics/estimator_sensor_bias.h>
|
||||
#include <uORB/topics/estimator_status.h>
|
||||
#include <uORB/topics/landing_target_pose.h>
|
||||
#include <uORB/topics/optical_flow.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/sensor_bias.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
#include <uORB/topics/sensor_selection.h>
|
||||
#include <uORB/topics/vehicle_air_data.h>
|
||||
|
@ -263,20 +263,20 @@ private:
|
|||
vehicle_land_detected_s _vehicle_land_detected{};
|
||||
vehicle_status_s _vehicle_status{};
|
||||
|
||||
uORB::Publication<estimator_innovations_s> _estimator_innovations_pub{ORB_ID(estimator_innovations)};
|
||||
uORB::Publication<estimator_innovations_s> _estimator_innovation_variances_pub{ORB_ID(estimator_innovation_variances)};
|
||||
uORB::Publication<estimator_innovations_s> _estimator_innovation_test_ratios_pub{ORB_ID(estimator_innovation_test_ratios)};
|
||||
uORB::Publication<ekf2_timestamps_s> _ekf2_timestamps_pub{ORB_ID(ekf2_timestamps)};
|
||||
uORB::Publication<ekf_gps_drift_s> _ekf_gps_drift_pub{ORB_ID(ekf_gps_drift)};
|
||||
uORB::Publication<ekf_gps_position_s> _blended_gps_pub{ORB_ID(ekf_gps_position)};
|
||||
uORB::Publication<estimator_innovations_s> _estimator_innovation_test_ratios_pub{ORB_ID(estimator_innovation_test_ratios)};
|
||||
uORB::Publication<estimator_innovations_s> _estimator_innovation_variances_pub{ORB_ID(estimator_innovation_variances)};
|
||||
uORB::Publication<estimator_innovations_s> _estimator_innovations_pub{ORB_ID(estimator_innovations)};
|
||||
uORB::Publication<estimator_sensor_bias_s> _estimator_sensor_bias_pub{ORB_ID(estimator_sensor_bias)};
|
||||
uORB::Publication<estimator_status_s> _estimator_status_pub{ORB_ID(estimator_status)};
|
||||
uORB::Publication<sensor_bias_s> _sensor_bias_pub{ORB_ID(sensor_bias)};
|
||||
uORB::Publication<vehicle_attitude_s> _att_pub{ORB_ID(vehicle_attitude)};
|
||||
uORB::Publication<vehicle_odometry_s> _vehicle_odometry_pub{ORB_ID(vehicle_odometry)};
|
||||
uORB::PublicationMulti<wind_estimate_s> _wind_pub{ORB_ID(wind_estimate)};
|
||||
uORB::PublicationData<vehicle_global_position_s> _vehicle_global_position_pub{ORB_ID(vehicle_global_position)};
|
||||
uORB::PublicationData<vehicle_local_position_s> _vehicle_local_position_pub{ORB_ID(vehicle_local_position)};
|
||||
uORB::PublicationData<vehicle_odometry_s> _vehicle_visual_odometry_aligned_pub{ORB_ID(vehicle_visual_odometry_aligned)};
|
||||
uORB::PublicationMulti<wind_estimate_s> _wind_pub{ORB_ID(wind_estimate)};
|
||||
|
||||
Ekf _ekf;
|
||||
|
||||
|
@ -753,7 +753,7 @@ void Ekf2::Run()
|
|||
imuSample imu_sample_new {};
|
||||
|
||||
hrt_abstime imu_dt = 0; // for tracking time slip later
|
||||
sensor_bias_s bias{};
|
||||
estimator_sensor_bias_s bias{};
|
||||
|
||||
if (_imu_sub_index >= 0) {
|
||||
vehicle_imu_s imu;
|
||||
|
@ -1490,7 +1490,7 @@ void Ekf2::Run()
|
|||
bias.mag_bias[1] = _last_valid_mag_cal[1];
|
||||
bias.mag_bias[2] = _last_valid_mag_cal[2];
|
||||
|
||||
_sensor_bias_pub.publish(bias);
|
||||
_estimator_sensor_bias_pub.publish(bias);
|
||||
}
|
||||
|
||||
// publish estimator status
|
||||
|
|
|
@ -43,21 +43,21 @@
|
|||
#pragma once
|
||||
|
||||
#include <float.h>
|
||||
#include <lib/hysteresis/hysteresis.h>
|
||||
#include <math.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <lib/hysteresis/hysteresis.h>
|
||||
#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/module.h>
|
||||
#include <px4_platform_common/module_params.h>
|
||||
#include <px4_platform_common/module_params.h>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/Publication.hpp>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/actuator_armed.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/sensor_bias.h>
|
||||
#include <uORB/topics/vehicle_acceleration.h>
|
||||
#include <uORB/topics/vehicle_land_detected.h>
|
||||
#include <uORB/topics/vehicle_local_position.h>
|
||||
|
|
|
@ -58,6 +58,7 @@ void LoggedTopics::add_default_topics()
|
|||
add_topic("estimator_innovation_test_ratios", 200);
|
||||
add_topic("estimator_innovation_variances", 200);
|
||||
add_topic("estimator_innovations", 200);
|
||||
add_topic("estimator_sensor_bias", 1000);
|
||||
add_topic("estimator_status", 200);
|
||||
add_topic("home_position");
|
||||
add_topic("input_rc", 200);
|
||||
|
@ -70,7 +71,6 @@ void LoggedTopics::add_default_topics()
|
|||
add_topic("radio_status");
|
||||
add_topic("rate_ctrl_status", 200);
|
||||
add_topic("safety", 1000);
|
||||
add_topic("sensor_bias", 1000);
|
||||
add_topic("sensor_combined", 100);
|
||||
add_topic("sensor_correction", 1000);
|
||||
add_topic("sensor_preflight", 200);
|
||||
|
|
|
@ -70,6 +70,7 @@
|
|||
#include <uORB/topics/debug_vect.h>
|
||||
#include <uORB/topics/differential_pressure.h>
|
||||
#include <uORB/topics/distance_sensor.h>
|
||||
#include <uORB/topics/estimator_sensor_bias.h>
|
||||
#include <uORB/topics/estimator_status.h>
|
||||
#include <uORB/topics/geofence_result.h>
|
||||
#include <uORB/topics/home_position.h>
|
||||
|
@ -84,7 +85,6 @@
|
|||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
#include <uORB/topics/sensor_accel_integrated.h>
|
||||
#include <uORB/topics/sensor_accel_status.h>
|
||||
#include <uORB/topics/sensor_bias.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
#include <uORB/topics/sensor_gyro_integrated.h>
|
||||
#include <uORB/topics/sensor_mag.h>
|
||||
|
@ -816,7 +816,7 @@ protected:
|
|||
explicit MavlinkStreamHighresIMU(Mavlink *mavlink) : MavlinkStream(mavlink),
|
||||
_sensor_sub(_mavlink->add_orb_subscription(ORB_ID(sensor_combined))),
|
||||
_sensor_time(0),
|
||||
_bias_sub(_mavlink->add_orb_subscription(ORB_ID(sensor_bias))),
|
||||
_bias_sub(_mavlink->add_orb_subscription(ORB_ID(estimator_sensor_bias))),
|
||||
_differential_pressure_sub(_mavlink->add_orb_subscription(ORB_ID(differential_pressure))),
|
||||
_magnetometer_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_magnetometer))),
|
||||
_air_data_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_air_data))),
|
||||
|
@ -864,7 +864,7 @@ protected:
|
|||
_baro_timestamp = air_data.timestamp;
|
||||
}
|
||||
|
||||
sensor_bias_s bias = {};
|
||||
estimator_sensor_bias_s bias{};
|
||||
_bias_sub->update(&bias);
|
||||
|
||||
differential_pressure_s differential_pressure = {};
|
||||
|
|
|
@ -79,10 +79,10 @@ void VehicleAcceleration::Stop()
|
|||
|
||||
void VehicleAcceleration::SensorBiasUpdate(bool force)
|
||||
{
|
||||
if (_sensor_bias_sub.updated() || force) {
|
||||
sensor_bias_s bias;
|
||||
if (_estimator_sensor_bias_sub.updated() || force) {
|
||||
estimator_sensor_bias_s bias;
|
||||
|
||||
if (_sensor_bias_sub.copy(&bias)) {
|
||||
if (_estimator_sensor_bias_sub.copy(&bias)) {
|
||||
if (bias.accel_device_id == _selected_sensor_device_id) {
|
||||
_bias = Vector3f{bias.accel_bias};
|
||||
|
||||
|
|
|
@ -36,19 +36,18 @@
|
|||
#include <lib/conversion/rotation.h>
|
||||
#include <lib/mathlib/math/Limits.hpp>
|
||||
#include <lib/matrix/matrix/math.hpp>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/log.h>
|
||||
#include <px4_platform_common/module_params.h>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/px4_work_queue/WorkItem.hpp>
|
||||
#include <uORB/Publication.hpp>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/SubscriptionCallback.hpp>
|
||||
#include <uORB/topics/estimator_sensor_bias.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/sensor_bias.h>
|
||||
#include <uORB/topics/sensor_accel.h>
|
||||
#include <uORB/topics/sensor_correction.h>
|
||||
#include <uORB/topics/sensor_selection.h>
|
||||
|
||||
#include <uORB/topics/sensor_accel.h>
|
||||
#include <uORB/topics/vehicle_acceleration.h>
|
||||
|
||||
class VehicleAcceleration : public ModuleParams, public px4::WorkItem
|
||||
|
@ -84,7 +83,7 @@ private:
|
|||
uORB::Publication<vehicle_acceleration_s> _vehicle_acceleration_pub{ORB_ID(vehicle_acceleration)};
|
||||
|
||||
uORB::Subscription _params_sub{ORB_ID(parameter_update)};
|
||||
uORB::Subscription _sensor_bias_sub{ORB_ID(sensor_bias)};
|
||||
uORB::Subscription _estimator_sensor_bias_sub{ORB_ID(estimator_sensor_bias)};
|
||||
uORB::Subscription _sensor_correction_sub{ORB_ID(sensor_correction)};
|
||||
|
||||
uORB::SubscriptionCallbackWorkItem _sensor_selection_sub{this, ORB_ID(sensor_selection)};
|
||||
|
|
|
@ -79,10 +79,10 @@ void VehicleAngularVelocity::Stop()
|
|||
|
||||
void VehicleAngularVelocity::SensorBiasUpdate(bool force)
|
||||
{
|
||||
if (_sensor_bias_sub.updated() || force) {
|
||||
sensor_bias_s bias;
|
||||
if (_estimator_sensor_bias_sub.updated() || force) {
|
||||
estimator_sensor_bias_s bias;
|
||||
|
||||
if (_sensor_bias_sub.copy(&bias)) {
|
||||
if (_estimator_sensor_bias_sub.copy(&bias)) {
|
||||
if (bias.gyro_device_id == _selected_sensor_device_id) {
|
||||
_bias = Vector3f{bias.gyro_bias};
|
||||
|
||||
|
|
|
@ -36,19 +36,18 @@
|
|||
#include <lib/conversion/rotation.h>
|
||||
#include <lib/mathlib/math/Limits.hpp>
|
||||
#include <lib/matrix/matrix/math.hpp>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/log.h>
|
||||
#include <px4_platform_common/module_params.h>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/px4_work_queue/WorkItem.hpp>
|
||||
#include <uORB/Publication.hpp>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/SubscriptionCallback.hpp>
|
||||
#include <uORB/topics/estimator_sensor_bias.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/sensor_bias.h>
|
||||
#include <uORB/topics/sensor_correction.h>
|
||||
#include <uORB/topics/sensor_selection.h>
|
||||
|
||||
#include <uORB/topics/sensor_gyro.h>
|
||||
#include <uORB/topics/sensor_selection.h>
|
||||
#include <uORB/topics/vehicle_angular_velocity.h>
|
||||
|
||||
class VehicleAngularVelocity : public ModuleParams, public px4::WorkItem
|
||||
|
@ -84,7 +83,7 @@ private:
|
|||
uORB::Publication<vehicle_angular_velocity_s> _vehicle_angular_velocity_pub{ORB_ID(vehicle_angular_velocity)};
|
||||
|
||||
uORB::Subscription _params_sub{ORB_ID(parameter_update)};
|
||||
uORB::Subscription _sensor_bias_sub{ORB_ID(sensor_bias)};
|
||||
uORB::Subscription _estimator_sensor_bias_sub{ORB_ID(estimator_sensor_bias)};
|
||||
uORB::Subscription _sensor_correction_sub{ORB_ID(sensor_correction)};
|
||||
|
||||
uORB::SubscriptionCallbackWorkItem _sensor_selection_sub{this, ORB_ID(sensor_selection)};
|
||||
|
|
Loading…
Reference in New Issue