mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Enable commander module for Parrot Bebop
This commit is contained in:
parent
0b7fa4f5ad
commit
6aa8fcdf53
@ -175,7 +175,7 @@ typedef struct {
|
||||
|
||||
int do_accel_calibration(orb_advert_t *mavlink_log_pub)
|
||||
{
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
int fd;
|
||||
#endif
|
||||
|
||||
@ -195,7 +195,7 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub)
|
||||
|
||||
/* reset all sensors */
|
||||
for (unsigned s = 0; s < max_accel_sens; s++) {
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, s);
|
||||
/* reset all offsets to zero and all scales to one */
|
||||
fd = px4_open(str, 0);
|
||||
@ -329,7 +329,7 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub)
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, i);
|
||||
fd = px4_open(str, 0);
|
||||
|
||||
@ -419,7 +419,7 @@ calibrate_return do_accel_calibration_measurements(orb_advert_t *mavlink_log_pub
|
||||
break;
|
||||
}
|
||||
|
||||
#if defined(__PX4_QURT) || defined(__PX4_POSIX_EAGLE) || defined(__PX4_POSIX_RPI)
|
||||
#if defined(__PX4_QURT) || defined(__PX4_POSIX_EAGLE) || defined(__PX4_POSIX_RPI) || defined(__PX4_POSIX_BEBOP)
|
||||
// For QURT respectively the driver framework, we need to get the device ID by copying one report.
|
||||
struct accel_report accel_report;
|
||||
orb_copy(ORB_ID(sensor_accel), worker_data.subs[i], &accel_report);
|
||||
|
||||
@ -185,7 +185,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
|
||||
|
||||
// Reset all offsets to 0 and scales to 1
|
||||
(void)memcpy(&worker_data.gyro_scale[s], &gyro_scale_zero, sizeof(gyro_scale_zero));
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
sprintf(str, "%s%u", GYRO_BASE_DEVICE_PATH, s);
|
||||
int fd = px4_open(str, 0);
|
||||
if (fd >= 0) {
|
||||
@ -238,7 +238,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
|
||||
for (unsigned s = 0; s < gyro_count; s++) {
|
||||
|
||||
worker_data.gyro_sensor_sub[s] = orb_subscribe_multi(ORB_ID(sensor_gyro), s);
|
||||
#if defined(__PX4_QURT) || defined(__PX4_POSIX_EAGLE) || defined(__PX4_POSIX_RPI)
|
||||
#if defined(__PX4_QURT) || defined(__PX4_POSIX_EAGLE) || defined(__PX4_POSIX_RPI) || defined(__PX4_POSIX_BEBOP)
|
||||
// For QURT respectively the driver framework, we need to get the device ID by copying one report.
|
||||
struct gyro_report gyro_report;
|
||||
orb_copy(ORB_ID(sensor_gyro), worker_data.gyro_sensor_sub[s], &gyro_report);
|
||||
@ -336,7 +336,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
|
||||
(void)sprintf(str, "CAL_GYRO%u_ID", s);
|
||||
failed |= (OK != param_set_no_notification(param_find(str), &(worker_data.device_id[s])));
|
||||
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
/* apply new scaling and offsets */
|
||||
(void)sprintf(str, "%s%u", GYRO_BASE_DEVICE_PATH, s);
|
||||
int fd = px4_open(str, 0);
|
||||
|
||||
@ -124,7 +124,7 @@ int do_mag_calibration(orb_advert_t *mavlink_log_pub)
|
||||
_last_mag_progress = 0;
|
||||
|
||||
for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) {
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
// Reset mag id to mag not available
|
||||
(void)sprintf(str, "CAL_MAG%u_ID", cur_mag);
|
||||
result = param_set_no_notification(param_find(str), &(device_ids[cur_mag]));
|
||||
@ -166,7 +166,7 @@ int do_mag_calibration(orb_advert_t *mavlink_log_pub)
|
||||
#endif
|
||||
|
||||
/* for calibration, commander will run on apps, so orb messages are used to get info from dsp */
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
// Attempt to open mag
|
||||
(void)sprintf(str, "%s%u", MAG_BASE_DEVICE_PATH, cur_mag);
|
||||
int fd = px4_open(str, O_RDONLY);
|
||||
@ -508,7 +508,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub)
|
||||
// Mag in this slot is available
|
||||
worker_data.sub_mag[cur_mag] = orb_subscribe_multi(ORB_ID(sensor_mag), cur_mag);
|
||||
|
||||
#if defined(__PX4_QURT) || defined(__PX4_POSIX_RPI)
|
||||
#if defined(__PX4_QURT) || defined(__PX4_POSIX_RPI) || defined(__PX4_POSIX_BEBOP)
|
||||
// For QURT respectively the driver framework, we need to get the device ID by copying one report.
|
||||
struct mag_report mag_report;
|
||||
orb_copy(ORB_ID(sensor_mag), worker_data.sub_mag[cur_mag], &mag_report);
|
||||
@ -664,7 +664,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub)
|
||||
for (unsigned cur_mag=0; cur_mag<max_mags; cur_mag++) {
|
||||
if (device_ids[cur_mag] != 0) {
|
||||
struct mag_calibration_s mscale;
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
int fd_mag = -1;
|
||||
|
||||
// Set new scale
|
||||
@ -688,7 +688,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub)
|
||||
mscale.y_offset = sphere_y[cur_mag];
|
||||
mscale.z_offset = sphere_z[cur_mag];
|
||||
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
if (px4_ioctl(fd_mag, MAGIOCSSCALE, (long unsigned int)&mscale) != OK) {
|
||||
calibration_log_critical(mavlink_log_pub, CAL_ERROR_APPLY_CAL_MSG, cur_mag);
|
||||
result = calibrate_return_error;
|
||||
@ -696,7 +696,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub)
|
||||
#endif
|
||||
}
|
||||
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
// Mag device no longer needed
|
||||
if (fd_mag >= 0) {
|
||||
px4_close(fd_mag);
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user