mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 09:28:58 +00:00
Code cleanup and ifdefs required for qurt build
Code that was previously out of tree that was #if 0, is now #ifdef __PX4_QURT. These changes were required for flight using the qurt build. Changes include code cleanup for shmem_posix.c. Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
committed by
Julian Oes
parent
8634452d6d
commit
fea910d45a
@@ -175,7 +175,9 @@ typedef struct {
|
||||
|
||||
int do_accel_calibration(int mavlink_fd)
|
||||
{
|
||||
#ifndef __PX4_QURT
|
||||
int fd;
|
||||
#endif
|
||||
|
||||
mavlink_and_console_log_info(mavlink_fd, CAL_QGC_STARTED_MSG, sensor_name);
|
||||
|
||||
@@ -192,6 +194,7 @@ int do_accel_calibration(int mavlink_fd)
|
||||
|
||||
char str[30];
|
||||
|
||||
#ifndef __PX4_QURT
|
||||
/* reset all sensors */
|
||||
for (unsigned s = 0; s < max_accel_sens; s++) {
|
||||
sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, s);
|
||||
@@ -211,6 +214,7 @@ int do_accel_calibration(int mavlink_fd)
|
||||
mavlink_and_console_log_critical(mavlink_fd, CAL_ERROR_RESET_CAL_MSG, s);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
float accel_offs[max_accel_sens][3];
|
||||
float accel_T[max_accel_sens][3][3];
|
||||
@@ -277,14 +281,17 @@ int do_accel_calibration(int mavlink_fd)
|
||||
failed |= (OK != param_set_no_notification(param_find(str), &(accel_scale.y_scale)));
|
||||
(void)sprintf(str, "CAL_ACC%u_ZSCALE", i);
|
||||
failed |= (OK != param_set_no_notification(param_find(str), &(accel_scale.z_scale)));
|
||||
#ifndef __PX4_QURT
|
||||
(void)sprintf(str, "CAL_ACC%u_ID", i);
|
||||
failed |= (OK != param_set_no_notification(param_find(str), &(device_id[i])));
|
||||
#endif
|
||||
|
||||
if (failed) {
|
||||
mavlink_and_console_log_critical(mavlink_fd, CAL_ERROR_SET_PARAMS_MSG, i);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
#ifndef __PX4_QURT
|
||||
sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, i);
|
||||
fd = px4_open(str, 0);
|
||||
|
||||
@@ -299,6 +306,7 @@ int do_accel_calibration(int mavlink_fd)
|
||||
if (res != OK) {
|
||||
mavlink_and_console_log_critical(mavlink_fd, CAL_ERROR_APPLY_CAL_MSG, i);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
if (res == OK) {
|
||||
|
||||
Reference in New Issue
Block a user