mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-21 14:27:35 +08:00
Merge branch 'master' into rc_failsafe
This commit is contained in:
@@ -73,7 +73,7 @@ int do_mag_calibration(int mavlink_fd)
|
||||
|
||||
/* maximum 500 values */
|
||||
const unsigned int calibration_maxcount = 500;
|
||||
unsigned int calibration_counter = 0;
|
||||
unsigned int calibration_counter;
|
||||
|
||||
struct mag_scale mscale_null = {
|
||||
0.0f,
|
||||
@@ -99,28 +99,34 @@ int do_mag_calibration(int mavlink_fd)
|
||||
res = ioctl(fd, MAGIOCCALIBRATE, fd);
|
||||
|
||||
if (res != OK) {
|
||||
mavlink_log_critical(mavlink_fd, "ERROR: failed to calibrate scale");
|
||||
mavlink_log_critical(mavlink_fd, "Skipped scale calibration");
|
||||
/* this is non-fatal - mark it accordingly */
|
||||
res = OK;
|
||||
}
|
||||
}
|
||||
|
||||
close(fd);
|
||||
|
||||
float *x;
|
||||
float *y;
|
||||
float *z;
|
||||
float *x = NULL;
|
||||
float *y = NULL;
|
||||
float *z = NULL;
|
||||
|
||||
if (res == OK) {
|
||||
/* allocate memory */
|
||||
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20);
|
||||
|
||||
x = (float *)malloc(sizeof(float) * calibration_maxcount);
|
||||
y = (float *)malloc(sizeof(float) * calibration_maxcount);
|
||||
z = (float *)malloc(sizeof(float) * calibration_maxcount);
|
||||
x = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_maxcount));
|
||||
y = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_maxcount));
|
||||
z = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_maxcount));
|
||||
|
||||
if (x == NULL || y == NULL || z == NULL) {
|
||||
mavlink_log_critical(mavlink_fd, "ERROR: out of memory");
|
||||
res = ERROR;
|
||||
return res;
|
||||
}
|
||||
} else {
|
||||
/* exit */
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
if (res == OK) {
|
||||
@@ -136,6 +142,8 @@ int do_mag_calibration(int mavlink_fd)
|
||||
|
||||
mavlink_log_info(mavlink_fd, "rotate in a figure 8 around all axis");
|
||||
|
||||
calibration_counter = 0;
|
||||
|
||||
while (hrt_absolute_time() < calibration_deadline &&
|
||||
calibration_counter < calibration_maxcount) {
|
||||
|
||||
@@ -178,6 +186,7 @@ int do_mag_calibration(int mavlink_fd)
|
||||
float sphere_radius;
|
||||
|
||||
if (res == OK) {
|
||||
|
||||
/* sphere fit */
|
||||
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 70);
|
||||
sphere_fit_least_squares(x, y, z, calibration_counter, 100, 0.0f, &sphere_x, &sphere_y, &sphere_z, &sphere_radius);
|
||||
@@ -270,7 +279,7 @@ int do_mag_calibration(int mavlink_fd)
|
||||
} else {
|
||||
mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
|
||||
}
|
||||
|
||||
return res;
|
||||
}
|
||||
|
||||
return res;
|
||||
}
|
||||
|
||||
@@ -451,7 +451,7 @@ FixedwingPositionControl::parameters_update()
|
||||
_tecs.set_speed_weight(_parameters.speed_weight);
|
||||
_tecs.set_pitch_damping(_parameters.pitch_damping);
|
||||
_tecs.set_indicated_airspeed_min(_parameters.airspeed_min);
|
||||
_tecs.set_indicated_airspeed_max(_parameters.airspeed_min);
|
||||
_tecs.set_indicated_airspeed_max(_parameters.airspeed_max);
|
||||
_tecs.set_max_climb_rate(_parameters.max_climb_rate);
|
||||
|
||||
/* sanity check parameters */
|
||||
@@ -501,7 +501,6 @@ FixedwingPositionControl::vehicle_airspeed_poll()
|
||||
orb_copy(ORB_ID(airspeed), _airspeed_sub, &_airspeed);
|
||||
_airspeed_valid = true;
|
||||
_airspeed_last_valid = hrt_absolute_time();
|
||||
return true;
|
||||
|
||||
} else {
|
||||
|
||||
@@ -514,7 +513,7 @@ FixedwingPositionControl::vehicle_airspeed_poll()
|
||||
/* update TECS state */
|
||||
_tecs.enable_airspeed(_airspeed_valid);
|
||||
|
||||
return false;
|
||||
return airspeed_updated;
|
||||
}
|
||||
|
||||
void
|
||||
|
||||
@@ -249,8 +249,10 @@ ORBDevNode::close(struct file *filp)
|
||||
} else {
|
||||
SubscriberData *sd = filp_to_sd(filp);
|
||||
|
||||
if (sd != nullptr)
|
||||
if (sd != nullptr) {
|
||||
hrt_cancel(&sd->update_call);
|
||||
delete sd;
|
||||
}
|
||||
}
|
||||
|
||||
return CDev::close(filp);
|
||||
|
||||
Reference in New Issue
Block a user