int TemperatureCalibrationBaro::finish_sensor_instance(PerSensorData &data, int sensor_index) { if (!data.hot_soaked || data.tempcal_complete) { return 0; } double res[POLYFIT_ORDER + 1] = {}; data.P[0].fit(res); res[POLYFIT_ORDER] = 0.0; // normalise the correction to be zero at the reference temperature by setting the X^0 coefficient to zero PX4_INFO("Result baro %u %.20f %.20f %.20f %.20f %.20f %.20f", sensor_index, (double)res[0], (double)res[1], (double)res[2], (double)res[3], (double)res[4], (double)res[5]); data.tempcal_complete = true; char str[30]; float param = 0.0f; int result = PX4_OK; set_parameter("TC_B%d_ID", sensor_index, &data.device_id); for (unsigned coef_index = 0; coef_index <= POLYFIT_ORDER; coef_index++) { sprintf(str, "TC_B%d_X%d", sensor_index, (POLYFIT_ORDER - coef_index)); param = (float)res[coef_index]; result = param_set_no_notification(param_find(str), ¶m); if (result != PX4_OK) { PX4_ERR("unable to reset %s", str); } } set_parameter("TC_B%d_TMAX", sensor_index, &data.high_temp); set_parameter("TC_B%d_TMIN", sensor_index, &data.low_temp); set_parameter("TC_B%d_TREF", sensor_index, &data.ref_temp); return 0; }
int TemperatureCalibrationAccel::finish() { for (unsigned uorb_index = 0; uorb_index < _num_sensor_instances; uorb_index++) { finish_sensor_instance(_data[uorb_index], uorb_index); } int32_t enabled = 1; int result = param_set_no_notification(param_find("TC_A_ENABLE"), &enabled); if (result != PX4_OK) { PX4_ERR("unable to reset TC_A_ENABLE (%i)", result); } return result; }
int TemperatureCalibrationAccel::finish_sensor_instance(PerSensorData &data, int sensor_index) { if (!data.hot_soaked || data.tempcal_complete) { return 0; } double res[3][4] = {}; data.P[0].fit(res[0]); res[0][3] = 0.0; // normalise the correction to be zero at the reference temperature PX4_INFO("Result Accel %d Axis 0: %.20f %.20f %.20f %.20f", sensor_index, (double)res[0][0], (double)res[0][1], (double)res[0][2], (double)res[0][3]); data.P[1].fit(res[1]); res[1][3] = 0.0; // normalise the correction to be zero at the reference temperature PX4_INFO("Result Accel %d Axis 1: %.20f %.20f %.20f %.20f", sensor_index, (double)res[1][0], (double)res[1][1], (double)res[1][2], (double)res[1][3]); data.P[2].fit(res[2]); res[2][3] = 0.0; // normalise the correction to be zero at the reference temperature PX4_INFO("Result Accel %d Axis 2: %.20f %.20f %.20f %.20f", sensor_index, (double)res[2][0], (double)res[2][1], (double)res[2][2], (double)res[2][3]); data.tempcal_complete = true; char str[30]; float param = 0.0f; int result = PX4_OK; set_parameter("TC_A%d_ID", sensor_index, &data.device_id); for (unsigned axis_index = 0; axis_index < 3; axis_index++) { for (unsigned coef_index = 0; coef_index <= 3; coef_index++) { sprintf(str, "TC_A%d_X%d_%d", sensor_index, 3 - coef_index, axis_index); param = (float)res[axis_index][coef_index]; result = param_set_no_notification(param_find(str), ¶m); if (result != PX4_OK) { PX4_ERR("unable to reset %s", str); } } } set_parameter("TC_A%d_TMAX", sensor_index, &data.high_temp); set_parameter("TC_A%d_TMIN", sensor_index, &data.low_temp); set_parameter("TC_A%d_TREF", sensor_index, &data.ref_temp); return 0; }
int do_mag_calibration(int mavlink_fd) { mavlink_and_console_log_info(mavlink_fd, CAL_QGC_STARTED_MSG, sensor_name); struct mag_scale mscale_null = { 0.0f, 1.0f, 0.0f, 1.0f, 0.0f, 1.0f, }; int result = OK; // Determine which mags are available and reset each int32_t device_ids[max_mags]; char str[30]; for (size_t i=0; i<max_mags; i++) { device_ids[i] = 0; // signals no mag } for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) { // 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])); if (result != OK) { mavlink_and_console_log_info(mavlink_fd, "[cal] Unable to reset CAL_MAG%u_ID", cur_mag); break; } // Attempt to open mag (void)sprintf(str, "%s%u", MAG_BASE_DEVICE_PATH, cur_mag); int fd = px4_open(str, O_RDONLY); if (fd < 0) { continue; } // Get device id for this mag device_ids[cur_mag] = px4_ioctl(fd, DEVIOCGDEVICEID, 0); // Reset mag scale result = px4_ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null); if (result != OK) { mavlink_and_console_log_critical(mavlink_fd, CAL_ERROR_RESET_CAL_MSG, cur_mag); } /* calibrate range */ if (result == OK) { result = px4_ioctl(fd, MAGIOCCALIBRATE, fd); if (result != OK) { mavlink_and_console_log_info(mavlink_fd, "[cal] Skipped scale calibration, sensor %u", cur_mag); /* this is non-fatal - mark it accordingly */ result = OK; } } px4_close(fd); } // Calibrate all mags at the same time if (result == OK) { switch (mag_calibrate_all(mavlink_fd, device_ids)) { case calibrate_return_cancelled: // Cancel message already displayed, we're done here result = ERROR; break; case calibrate_return_ok: /* auto-save to EEPROM */ result = param_save_default(); /* if there is a any preflight-check system response, let the barrage of messages through */ usleep(200000); if (result == OK) { mavlink_and_console_log_info(mavlink_fd, CAL_QGC_PROGRESS_MSG, 100); mavlink_and_console_log_info(mavlink_fd, CAL_QGC_DONE_MSG, sensor_name); break; } else { mavlink_and_console_log_critical(mavlink_fd, CAL_ERROR_SAVE_PARAMS_MSG); } // Fall through default: mavlink_and_console_log_critical(mavlink_fd, CAL_QGC_FAILED_MSG, sensor_name); break; } } /* give this message enough time to propagate */ usleep(600000); return result; }
calibrate_return mag_calibrate_all(int mavlink_fd, int32_t (&device_ids)[max_mags]) { calibrate_return result = calibrate_return_ok; mag_worker_data_t worker_data; worker_data.mavlink_fd = mavlink_fd; worker_data.done_count = 0; worker_data.calibration_points_perside = 40; worker_data.calibration_interval_perside_seconds = 20; worker_data.calibration_interval_perside_useconds = worker_data.calibration_interval_perside_seconds * 1000 * 1000; // Collect: Right-side up, Left Side, Nose down worker_data.side_data_collected[DETECT_ORIENTATION_RIGHTSIDE_UP] = false; worker_data.side_data_collected[DETECT_ORIENTATION_LEFT] = false; worker_data.side_data_collected[DETECT_ORIENTATION_NOSE_DOWN] = false; worker_data.side_data_collected[DETECT_ORIENTATION_TAIL_DOWN] = false; worker_data.side_data_collected[DETECT_ORIENTATION_UPSIDE_DOWN] = false; worker_data.side_data_collected[DETECT_ORIENTATION_RIGHT] = false; for (size_t cur_mag=0; cur_mag<max_mags; cur_mag++) { // Initialize to no subscription worker_data.sub_mag[cur_mag] = -1; // Initialize to no memory allocated worker_data.x[cur_mag] = NULL; worker_data.y[cur_mag] = NULL; worker_data.z[cur_mag] = NULL; worker_data.calibration_counter_total[cur_mag] = 0; } const unsigned int calibration_points_maxcount = calibration_sides * worker_data.calibration_points_perside; char str[30]; for (size_t cur_mag=0; cur_mag<max_mags; cur_mag++) { worker_data.x[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.y[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.z[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); if (worker_data.x[cur_mag] == NULL || worker_data.y[cur_mag] == NULL || worker_data.z[cur_mag] == NULL) { mavlink_and_console_log_critical(mavlink_fd, "[cal] ERROR: out of memory"); result = calibrate_return_error; } } // Setup subscriptions to mag sensors if (result == calibrate_return_ok) { for (unsigned cur_mag=0; cur_mag<max_mags; cur_mag++) { if (device_ids[cur_mag] != 0) { // Mag in this slot is available worker_data.sub_mag[cur_mag] = orb_subscribe_multi(ORB_ID(sensor_mag), cur_mag); if (worker_data.sub_mag[cur_mag] < 0) { mavlink_and_console_log_critical(mavlink_fd, "[cal] Mag #%u not found, abort", cur_mag); result = calibrate_return_error; break; } } } } // Limit update rate to get equally spaced measurements over time (in ms) if (result == calibrate_return_ok) { for (unsigned cur_mag=0; cur_mag<max_mags; cur_mag++) { if (device_ids[cur_mag] != 0) { // Mag in this slot is available unsigned int orb_interval_msecs = (worker_data.calibration_interval_perside_useconds / 1000) / worker_data.calibration_points_perside; //mavlink_and_console_log_info(mavlink_fd, "Orb interval %u msecs", orb_interval_msecs); orb_set_interval(worker_data.sub_mag[cur_mag], orb_interval_msecs); } } } if (result == calibrate_return_ok) { int cancel_sub = calibrate_cancel_subscribe(); result = calibrate_from_orientation(mavlink_fd, // Mavlink fd to write output cancel_sub, // Subscription to vehicle_command for cancel support worker_data.side_data_collected, // Sides to calibrate mag_calibration_worker, // Calibration worker &worker_data, // Opaque data for calibration worked true); // true: lenient still detection calibrate_cancel_unsubscribe(cancel_sub); } // Close subscriptions for (unsigned cur_mag=0; cur_mag<max_mags; cur_mag++) { if (worker_data.sub_mag[cur_mag] >= 0) { px4_close(worker_data.sub_mag[cur_mag]); } } // Calculate calibration values for each mag float sphere_x[max_mags]; float sphere_y[max_mags]; float sphere_z[max_mags]; float sphere_radius[max_mags]; // Sphere fit the data to get calibration values if (result == calibrate_return_ok) { for (unsigned cur_mag=0; cur_mag<max_mags; cur_mag++) { if (device_ids[cur_mag] != 0) { // Mag in this slot is available and we should have values for it to calibrate sphere_fit_least_squares(worker_data.x[cur_mag], worker_data.y[cur_mag], worker_data.z[cur_mag], worker_data.calibration_counter_total[cur_mag], 100, 0.0f, &sphere_x[cur_mag], &sphere_y[cur_mag], &sphere_z[cur_mag], &sphere_radius[cur_mag]); if (!PX4_ISFINITE(sphere_x[cur_mag]) || !PX4_ISFINITE(sphere_y[cur_mag]) || !PX4_ISFINITE(sphere_z[cur_mag])) { mavlink_and_console_log_critical(mavlink_fd, "[cal] ERROR: NaN in sphere fit for mag #%u", cur_mag); result = calibrate_return_error; } } } } // Print uncalibrated data points if (result == calibrate_return_ok) { printf("RAW DATA:\n--------------------\n"); for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { printf("RAW: MAG %u with %u samples:\n", (unsigned)cur_mag, (unsigned)worker_data.calibration_counter_total[cur_mag]); for (size_t i = 0; i < worker_data.calibration_counter_total[cur_mag]; i++) { float x = worker_data.x[cur_mag][i]; float y = worker_data.y[cur_mag][i]; float z = worker_data.z[cur_mag][i]; printf("%8.4f, %8.4f, %8.4f\n", (double)x, (double)y, (double)z); } printf(">>>>>>>\n"); } printf("CALIBRATED DATA:\n--------------------\n"); for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { printf("Calibrated: MAG %u with %u samples:\n", (unsigned)cur_mag, (unsigned)worker_data.calibration_counter_total[cur_mag]); for (size_t i = 0; i < worker_data.calibration_counter_total[cur_mag]; i++) { float x = worker_data.x[cur_mag][i] - sphere_x[cur_mag]; float y = worker_data.y[cur_mag][i] - sphere_y[cur_mag]; float z = worker_data.z[cur_mag][i] - sphere_z[cur_mag]; printf("%8.4f, %8.4f, %8.4f\n", (double)x, (double)y, (double)z); } printf("SPHERE RADIUS: %8.4f\n", (double)sphere_radius[cur_mag]); printf(">>>>>>>\n"); } } // Data points are no longer needed for (size_t cur_mag=0; cur_mag<max_mags; cur_mag++) { free(worker_data.x[cur_mag]); free(worker_data.y[cur_mag]); free(worker_data.z[cur_mag]); } if (result == calibrate_return_ok) { for (unsigned cur_mag=0; cur_mag<max_mags; cur_mag++) { if (device_ids[cur_mag] != 0) { int fd_mag = -1; struct mag_scale mscale; // Set new scale (void)sprintf(str, "%s%u", MAG_BASE_DEVICE_PATH, cur_mag); fd_mag = px4_open(str, 0); if (fd_mag < 0) { mavlink_and_console_log_critical(mavlink_fd, "[cal] ERROR: unable to open mag device #%u", cur_mag); result = calibrate_return_error; } if (result == calibrate_return_ok) { if (px4_ioctl(fd_mag, MAGIOCGSCALE, (long unsigned int)&mscale) != OK) { mavlink_and_console_log_critical(mavlink_fd, "[cal] ERROR: failed to get current calibration #%u", cur_mag); result = calibrate_return_error; } } if (result == calibrate_return_ok) { mscale.x_offset = sphere_x[cur_mag]; mscale.y_offset = sphere_y[cur_mag]; mscale.z_offset = sphere_z[cur_mag]; if (px4_ioctl(fd_mag, MAGIOCSSCALE, (long unsigned int)&mscale) != OK) { mavlink_and_console_log_critical(mavlink_fd, CAL_ERROR_APPLY_CAL_MSG, cur_mag); result = calibrate_return_error; } } // Mag device no longer needed if (fd_mag >= 0) { px4_close(fd_mag); } if (result == calibrate_return_ok) { bool failed = false; /* set parameters */ (void)sprintf(str, "CAL_MAG%u_ID", cur_mag); failed |= (OK != param_set_no_notification(param_find(str), &(device_ids[cur_mag]))); (void)sprintf(str, "CAL_MAG%u_XOFF", cur_mag); failed |= (OK != param_set_no_notification(param_find(str), &(mscale.x_offset))); (void)sprintf(str, "CAL_MAG%u_YOFF", cur_mag); failed |= (OK != param_set_no_notification(param_find(str), &(mscale.y_offset))); (void)sprintf(str, "CAL_MAG%u_ZOFF", cur_mag); failed |= (OK != param_set_no_notification(param_find(str), &(mscale.z_offset))); (void)sprintf(str, "CAL_MAG%u_XSCALE", cur_mag); failed |= (OK != param_set_no_notification(param_find(str), &(mscale.x_scale))); (void)sprintf(str, "CAL_MAG%u_YSCALE", cur_mag); failed |= (OK != param_set_no_notification(param_find(str), &(mscale.y_scale))); (void)sprintf(str, "CAL_MAG%u_ZSCALE", cur_mag); failed |= (OK != param_set_no_notification(param_find(str), &(mscale.z_scale))); if (failed) { mavlink_and_console_log_critical(mavlink_fd, CAL_ERROR_SET_PARAMS_MSG, cur_mag); result = calibrate_return_error; } else { mavlink_and_console_log_info(mavlink_fd, "[cal] mag #%u off: x:%.2f y:%.2f z:%.2f Ga", cur_mag, (double)mscale.x_offset, (double)mscale.y_offset, (double)mscale.z_offset); mavlink_and_console_log_info(mavlink_fd, "[cal] mag #%u scale: x:%.2f y:%.2f z:%.2f", cur_mag, (double)mscale.x_scale, (double)mscale.y_scale, (double)mscale.z_scale); } } } } } return result; }
calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub) { calibrate_return result = calibrate_return_ok; mag_worker_data_t worker_data; worker_data.mavlink_log_pub = mavlink_log_pub; worker_data.done_count = 0; worker_data.calibration_points_perside = calibration_total_points / calibration_sides; worker_data.calibration_interval_perside_seconds = calibraton_duration_seconds / calibration_sides; worker_data.calibration_interval_perside_useconds = worker_data.calibration_interval_perside_seconds * 1000 * 1000; // Collect: Right-side up, Left Side, Nose down worker_data.side_data_collected[DETECT_ORIENTATION_RIGHTSIDE_UP] = false; worker_data.side_data_collected[DETECT_ORIENTATION_LEFT] = false; worker_data.side_data_collected[DETECT_ORIENTATION_NOSE_DOWN] = false; worker_data.side_data_collected[DETECT_ORIENTATION_TAIL_DOWN] = true; worker_data.side_data_collected[DETECT_ORIENTATION_UPSIDE_DOWN] = true; worker_data.side_data_collected[DETECT_ORIENTATION_RIGHT] = true; calibration_log_info(mavlink_log_pub, "[cal] %s side done, rotate to a different side", detect_orientation_str(DETECT_ORIENTATION_TAIL_DOWN)); usleep(100000); calibration_log_info(mavlink_log_pub, "[cal] %s side done, rotate to a different side", detect_orientation_str(DETECT_ORIENTATION_TAIL_DOWN)); usleep(100000); calibration_log_info(mavlink_log_pub, "[cal] %s side done, rotate to a different side", detect_orientation_str(DETECT_ORIENTATION_UPSIDE_DOWN)); usleep(100000); calibration_log_info(mavlink_log_pub, "[cal] %s side done, rotate to a different side", detect_orientation_str(DETECT_ORIENTATION_UPSIDE_DOWN)); usleep(100000); calibration_log_info(mavlink_log_pub, "[cal] %s side done, rotate to a different side", detect_orientation_str(DETECT_ORIENTATION_RIGHT)); usleep(100000); calibration_log_info(mavlink_log_pub, "[cal] %s side done, rotate to a different side", detect_orientation_str(DETECT_ORIENTATION_RIGHT)); usleep(100000); for (size_t cur_mag=0; cur_mag<max_mags; cur_mag++) { // Initialize to no subscription worker_data.sub_mag[cur_mag] = -1; // Initialize to no memory allocated worker_data.x[cur_mag] = NULL; worker_data.y[cur_mag] = NULL; worker_data.z[cur_mag] = NULL; worker_data.calibration_counter_total[cur_mag] = 0; } const unsigned int calibration_points_maxcount = calibration_sides * worker_data.calibration_points_perside; char str[30]; for (size_t cur_mag=0; cur_mag<max_mags; cur_mag++) { worker_data.x[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.y[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.z[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); if (worker_data.x[cur_mag] == NULL || worker_data.y[cur_mag] == NULL || worker_data.z[cur_mag] == NULL) { calibration_log_critical(mavlink_log_pub, "[cal] ERROR: out of memory"); result = calibrate_return_error; } } // Setup subscriptions to mag sensors if (result == calibrate_return_ok) { // We should not try to subscribe if the topic doesn't actually exist and can be counted. const unsigned mag_count = orb_group_count(ORB_ID(sensor_mag)); for (unsigned cur_mag = 0; cur_mag < mag_count; cur_mag++) { // Mag in this slot is available worker_data.sub_mag[cur_mag] = orb_subscribe_multi(ORB_ID(sensor_mag), cur_mag); #ifdef __PX4_QURT // 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); device_ids[cur_mag] = mag_report.device_id; #endif if (worker_data.sub_mag[cur_mag] < 0) { calibration_log_critical(mavlink_log_pub, "[cal] Mag #%u not found, abort", cur_mag); result = calibrate_return_error; break; } if (device_ids[cur_mag] != 0) { // Get priority int32_t prio; orb_priority(worker_data.sub_mag[cur_mag], &prio); if (prio > device_prio_max) { device_prio_max = prio; device_id_primary = device_ids[cur_mag]; } } else { calibration_log_critical(mavlink_log_pub, "[cal] Mag #%u no device id, abort", cur_mag); result = calibrate_return_error; break; } } } // Limit update rate to get equally spaced measurements over time (in ms) if (result == calibrate_return_ok) { for (unsigned cur_mag=0; cur_mag<max_mags; cur_mag++) { if (device_ids[cur_mag] != 0) { // Mag in this slot is available unsigned int orb_interval_msecs = (worker_data.calibration_interval_perside_useconds / 1000) / worker_data.calibration_points_perside; //calibration_log_info(mavlink_log_pub, "Orb interval %u msecs", orb_interval_msecs); orb_set_interval(worker_data.sub_mag[cur_mag], orb_interval_msecs); } } } if (result == calibrate_return_ok) { int cancel_sub = calibrate_cancel_subscribe(); result = calibrate_from_orientation(mavlink_log_pub, // uORB handle to write output cancel_sub, // Subscription to vehicle_command for cancel support worker_data.side_data_collected, // Sides to calibrate mag_calibration_worker, // Calibration worker &worker_data, // Opaque data for calibration worked true); // true: lenient still detection calibrate_cancel_unsubscribe(cancel_sub); } // Close subscriptions for (unsigned cur_mag=0; cur_mag<max_mags; cur_mag++) { if (worker_data.sub_mag[cur_mag] >= 0) { px4_close(worker_data.sub_mag[cur_mag]); } } // Calculate calibration values for each mag float sphere_x[max_mags]; float sphere_y[max_mags]; float sphere_z[max_mags]; float sphere_radius[max_mags]; // Sphere fit the data to get calibration values if (result == calibrate_return_ok) { for (unsigned cur_mag=0; cur_mag<max_mags; cur_mag++) { if (device_ids[cur_mag] != 0) { // Mag in this slot is available and we should have values for it to calibrate sphere_fit_least_squares(worker_data.x[cur_mag], worker_data.y[cur_mag], worker_data.z[cur_mag], worker_data.calibration_counter_total[cur_mag], 100, 0.0f, &sphere_x[cur_mag], &sphere_y[cur_mag], &sphere_z[cur_mag], &sphere_radius[cur_mag]); if (!PX4_ISFINITE(sphere_x[cur_mag]) || !PX4_ISFINITE(sphere_y[cur_mag]) || !PX4_ISFINITE(sphere_z[cur_mag])) { calibration_log_emergency(mavlink_log_pub, "ERROR: Retry calibration (sphere NaN, #%u)", cur_mag); result = calibrate_return_error; } if (fabsf(sphere_x[cur_mag]) > MAG_MAX_OFFSET_LEN || fabsf(sphere_y[cur_mag]) > MAG_MAX_OFFSET_LEN || fabsf(sphere_z[cur_mag]) > MAG_MAX_OFFSET_LEN) { calibration_log_emergency(mavlink_log_pub, "ERROR: Replace %s mag fault", (internal[cur_mag]) ? "autopilot, internal" : "GPS unit, external"); calibration_log_info(mavlink_log_pub, "Excessive offsets: %8.4f, %8.4f, %8.4f, #%u", (double)sphere_x[cur_mag], (double)sphere_y[cur_mag], (double)sphere_z[cur_mag], cur_mag); result = calibrate_return_ok; } } } } // Print uncalibrated data points if (result == calibrate_return_ok) { // DO NOT REMOVE! Critical validation data! // printf("RAW DATA:\n--------------------\n"); // for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { // if (worker_data.calibration_counter_total[cur_mag] == 0) { // continue; // } // printf("RAW: MAG %u with %u samples:\n", (unsigned)cur_mag, (unsigned)worker_data.calibration_counter_total[cur_mag]); // for (size_t i = 0; i < worker_data.calibration_counter_total[cur_mag]; i++) { // float x = worker_data.x[cur_mag][i]; // float y = worker_data.y[cur_mag][i]; // float z = worker_data.z[cur_mag][i]; // printf("%8.4f, %8.4f, %8.4f\n", (double)x, (double)y, (double)z); // } // printf(">>>>>>>\n"); // } // printf("CALIBRATED DATA:\n--------------------\n"); // for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { // if (worker_data.calibration_counter_total[cur_mag] == 0) { // continue; // } // printf("Calibrated: MAG %u with %u samples:\n", (unsigned)cur_mag, (unsigned)worker_data.calibration_counter_total[cur_mag]); // for (size_t i = 0; i < worker_data.calibration_counter_total[cur_mag]; i++) { // float x = worker_data.x[cur_mag][i] - sphere_x[cur_mag]; // float y = worker_data.y[cur_mag][i] - sphere_y[cur_mag]; // float z = worker_data.z[cur_mag][i] - sphere_z[cur_mag]; // printf("%8.4f, %8.4f, %8.4f\n", (double)x, (double)y, (double)z); // } // printf("SPHERE RADIUS: %8.4f\n", (double)sphere_radius[cur_mag]); // printf(">>>>>>>\n"); // } } // Data points are no longer needed for (size_t cur_mag=0; cur_mag<max_mags; cur_mag++) { free(worker_data.x[cur_mag]); free(worker_data.y[cur_mag]); free(worker_data.z[cur_mag]); } if (result == calibrate_return_ok) { (void)param_set_no_notification(param_find("CAL_MAG_PRIME"), &(device_id_primary)); for (unsigned cur_mag=0; cur_mag<max_mags; cur_mag++) { if (device_ids[cur_mag] != 0) { struct mag_calibration_s mscale; #ifndef __PX4_QURT int fd_mag = -1; // Set new scale (void)sprintf(str, "%s%u", MAG_BASE_DEVICE_PATH, cur_mag); fd_mag = px4_open(str, 0); if (fd_mag < 0) { calibration_log_critical(mavlink_log_pub, "[cal] ERROR: unable to open mag device #%u", cur_mag); result = calibrate_return_error; } if (result == calibrate_return_ok) { if (px4_ioctl(fd_mag, MAGIOCGSCALE, (long unsigned int)&mscale) != OK) { calibration_log_critical(mavlink_log_pub, "[cal] ERROR: failed to get current calibration #%u", cur_mag); result = calibrate_return_error; } } #endif if (result == calibrate_return_ok) { mscale.x_offset = sphere_x[cur_mag]; mscale.y_offset = sphere_y[cur_mag]; mscale.z_offset = sphere_z[cur_mag]; #ifndef __PX4_QURT 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; } #endif } #ifndef __PX4_QURT // Mag device no longer needed if (fd_mag >= 0) { px4_close(fd_mag); } #endif if (result == calibrate_return_ok) { bool failed = false; /* set parameters */ (void)sprintf(str, "CAL_MAG%u_ID", cur_mag); failed |= (OK != param_set_no_notification(param_find(str), &(device_ids[cur_mag]))); (void)sprintf(str, "CAL_MAG%u_XOFF", cur_mag); failed |= (OK != param_set_no_notification(param_find(str), &(mscale.x_offset))); (void)sprintf(str, "CAL_MAG%u_YOFF", cur_mag); failed |= (OK != param_set_no_notification(param_find(str), &(mscale.y_offset))); (void)sprintf(str, "CAL_MAG%u_ZOFF", cur_mag); failed |= (OK != param_set_no_notification(param_find(str), &(mscale.z_offset))); (void)sprintf(str, "CAL_MAG%u_XSCALE", cur_mag); // FIXME: scaling is not used right now on QURT #ifndef __PX4_QURT failed |= (OK != param_set_no_notification(param_find(str), &(mscale.x_scale))); (void)sprintf(str, "CAL_MAG%u_YSCALE", cur_mag); failed |= (OK != param_set_no_notification(param_find(str), &(mscale.y_scale))); (void)sprintf(str, "CAL_MAG%u_ZSCALE", cur_mag); failed |= (OK != param_set_no_notification(param_find(str), &(mscale.z_scale))); #endif if (failed) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_SET_PARAMS_MSG, cur_mag); result = calibrate_return_error; } else { calibration_log_info(mavlink_log_pub, "[cal] mag #%u off: x:%.2f y:%.2f z:%.2f Ga", cur_mag, (double)mscale.x_offset, (double)mscale.y_offset, (double)mscale.z_offset); #ifndef __PX4_QURT calibration_log_info(mavlink_log_pub, "[cal] mag #%u scale: x:%.2f y:%.2f z:%.2f", cur_mag, (double)mscale.x_scale, (double)mscale.y_scale, (double)mscale.z_scale); #endif usleep(200000); } } } } } return result; }
int do_mag_calibration(orb_advert_t *mavlink_log_pub) { calibration_log_info(mavlink_log_pub, CAL_QGC_STARTED_MSG, sensor_name); struct mag_calibration_s mscale_null; mscale_null.x_offset = 0.0f; mscale_null.x_scale = 1.0f; mscale_null.y_offset = 0.0f; mscale_null.y_scale = 1.0f; mscale_null.z_offset = 0.0f; mscale_null.z_scale = 1.0f; int result = OK; // Determine which mags are available and reset each char str[30]; for (size_t i=0; i < max_mags; i++) { device_ids[i] = 0; // signals no mag } _last_mag_progress = 0; for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) { #ifndef __PX4_QURT // 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])); if (result != OK) { calibration_log_info(mavlink_log_pub, "[cal] Unable to reset CAL_MAG%u_ID", cur_mag); break; } #else (void)sprintf(str, "CAL_MAG%u_XOFF", cur_mag); result = param_set(param_find(str), &mscale_null.x_offset); if (result != OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_MAG%u_YOFF", cur_mag); result = param_set(param_find(str), &mscale_null.y_offset); if (result != OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_MAG%u_ZOFF", cur_mag); result = param_set(param_find(str), &mscale_null.z_offset); if (result != OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_MAG%u_XSCALE", cur_mag); result = param_set(param_find(str), &mscale_null.x_scale); if (result != OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_MAG%u_YSCALE", cur_mag); result = param_set(param_find(str), &mscale_null.y_scale); if (result != OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_MAG%u_ZSCALE", cur_mag); result = param_set(param_find(str), &mscale_null.z_scale); if (result != OK) { PX4_ERR("unable to reset %s", str); } #endif /* for calibration, commander will run on apps, so orb messages are used to get info from dsp */ #ifndef __PX4_QURT // Attempt to open mag (void)sprintf(str, "%s%u", MAG_BASE_DEVICE_PATH, cur_mag); int fd = px4_open(str, O_RDONLY); if (fd < 0) { continue; } // Get device id for this mag device_ids[cur_mag] = px4_ioctl(fd, DEVIOCGDEVICEID, 0); internal[cur_mag] = (px4_ioctl(fd, MAGIOCGEXTERNAL, 0) <= 0); // Reset mag scale result = px4_ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null); if (result != OK) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_RESET_CAL_MSG, cur_mag); } /* calibrate range */ if (result == OK) { result = px4_ioctl(fd, MAGIOCCALIBRATE, fd); if (result != OK) { calibration_log_info(mavlink_log_pub, "[cal] Skipped scale calibration, sensor %u", cur_mag); /* this is non-fatal - mark it accordingly */ result = OK; } } px4_close(fd); #endif } // Calibrate all mags at the same time if (result == OK) { switch (mag_calibrate_all(mavlink_log_pub)) { case calibrate_return_cancelled: // Cancel message already displayed, we're done here result = ERROR; break; case calibrate_return_ok: /* auto-save to EEPROM */ result = param_save_default(); /* if there is a any preflight-check system response, let the barrage of messages through */ usleep(200000); if (result == OK) { calibration_log_info(mavlink_log_pub, CAL_QGC_PROGRESS_MSG, 100); usleep(20000); calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, sensor_name); usleep(20000); break; } else { calibration_log_critical(mavlink_log_pub, CAL_ERROR_SAVE_PARAMS_MSG); usleep(20000); } // Fall through default: calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, sensor_name); usleep(20000); break; } } /* give this message enough time to propagate */ usleep(600000); return result; }
int do_level_calibration(orb_advert_t *mavlink_log_pub) { const unsigned cal_time = 5; const unsigned cal_hz = 100; unsigned settle_time = 30; bool success = false; int att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); struct vehicle_attitude_s att; memset(&att, 0, sizeof(att)); calibration_log_info(mavlink_log_pub, CAL_QGC_STARTED_MSG, "level"); param_t roll_offset_handle = param_find("SENS_BOARD_X_OFF"); param_t pitch_offset_handle = param_find("SENS_BOARD_Y_OFF"); param_t board_rot_handle = param_find("SENS_BOARD_ROT"); // save old values if calibration fails float roll_offset_current; float pitch_offset_current; int32_t board_rot_current = 0; param_get(roll_offset_handle, &roll_offset_current); param_get(pitch_offset_handle, &pitch_offset_current); param_get(board_rot_handle, &board_rot_current); // give attitude some time to settle if there have been changes to the board rotation parameters if (board_rot_current == 0 && fabsf(roll_offset_current) < FLT_EPSILON && fabsf(pitch_offset_current) < FLT_EPSILON ) { settle_time = 0; } float zero = 0.0f; param_set_no_notification(roll_offset_handle, &zero); param_set_no_notification(pitch_offset_handle, &zero); param_notify_changes(); px4_pollfd_struct_t fds[1]; fds[0].fd = att_sub; fds[0].events = POLLIN; float roll_mean = 0.0f; float pitch_mean = 0.0f; unsigned counter = 0; // sleep for some time hrt_abstime start = hrt_absolute_time(); while(hrt_elapsed_time(&start) < settle_time * 1000000) { calibration_log_info(mavlink_log_pub, CAL_QGC_PROGRESS_MSG, (int)(90*hrt_elapsed_time(&start)/1e6f/(float)settle_time)); sleep(settle_time / 10); } start = hrt_absolute_time(); // average attitude for 5 seconds while(hrt_elapsed_time(&start) < cal_time * 1000000) { int pollret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100); if (pollret <= 0) { // attitude estimator is not running calibration_log_critical(mavlink_log_pub, "attitude estimator not running - check system boot"); calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, "level"); goto out; } orb_copy(ORB_ID(vehicle_attitude), att_sub, &att); matrix::Eulerf euler = matrix::Quatf(att.q); roll_mean += euler.phi(); pitch_mean += euler.theta(); counter++; } calibration_log_info(mavlink_log_pub, CAL_QGC_PROGRESS_MSG, 100); if (counter > (cal_time * cal_hz / 2 )) { roll_mean /= counter; pitch_mean /= counter; } else { calibration_log_info(mavlink_log_pub, "not enough measurements taken"); success = false; goto out; } if (fabsf(roll_mean) > 0.8f ) { calibration_log_critical(mavlink_log_pub, "excess roll angle"); } else if (fabsf(pitch_mean) > 0.8f ) { calibration_log_critical(mavlink_log_pub, "excess pitch angle"); } else { roll_mean *= (float)M_RAD_TO_DEG; pitch_mean *= (float)M_RAD_TO_DEG; param_set_no_notification(roll_offset_handle, &roll_mean); param_set_no_notification(pitch_offset_handle, &pitch_mean); param_notify_changes(); success = true; } out: if (success) { calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, "level"); return 0; } else { // set old parameters param_set_no_notification(roll_offset_handle, &roll_offset_current); param_set_no_notification(pitch_offset_handle, &pitch_offset_current); param_notify_changes(); calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, "level"); return 1; } }
int do_accel_calibration(orb_advert_t *mavlink_log_pub) { #ifdef __PX4_NUTTX int fd; #endif calibration_log_info(mavlink_log_pub, CAL_QGC_STARTED_MSG, sensor_name); struct accel_calibration_s accel_scale; accel_scale.x_offset = 0.0f; accel_scale.x_scale = 1.0f; accel_scale.y_offset = 0.0f; accel_scale.y_scale = 1.0f; accel_scale.z_offset = 0.0f; accel_scale.z_scale = 1.0f; int res = PX4_OK; char str[30]; /* reset all sensors */ for (unsigned s = 0; s < max_accel_sens; s++) { #ifdef __PX4_NUTTX sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, s); /* reset all offsets to zero and all scales to one */ fd = px4_open(str, 0); if (fd < 0) { continue; } device_id[s] = px4_ioctl(fd, DEVIOCGDEVICEID, 0); res = px4_ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale); px4_close(fd); if (res != PX4_OK) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_RESET_CAL_MSG, s); } #else (void)sprintf(str, "CAL_ACC%u_XOFF", s); res = param_set_no_notification(param_find(str), &accel_scale.x_offset); if (res != PX4_OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_ACC%u_YOFF", s); res = param_set_no_notification(param_find(str), &accel_scale.y_offset); if (res != PX4_OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_ACC%u_ZOFF", s); res = param_set_no_notification(param_find(str), &accel_scale.z_offset); if (res != PX4_OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_ACC%u_XSCALE", s); res = param_set_no_notification(param_find(str), &accel_scale.x_scale); if (res != PX4_OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_ACC%u_YSCALE", s); res = param_set_no_notification(param_find(str), &accel_scale.y_scale); if (res != PX4_OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_ACC%u_ZSCALE", s); res = param_set_no_notification(param_find(str), &accel_scale.z_scale); if (res != PX4_OK) { PX4_ERR("unable to reset %s", str); } param_notify_changes(); #endif } float accel_offs[max_accel_sens][3]; float accel_T[max_accel_sens][3][3]; unsigned active_sensors = 0; /* measure and calculate offsets & scales */ if (res == PX4_OK) { calibrate_return cal_return = do_accel_calibration_measurements(mavlink_log_pub, accel_offs, accel_T, &active_sensors); if (cal_return == calibrate_return_cancelled) { // Cancel message already displayed, nothing left to do return PX4_ERROR; } else if (cal_return == calibrate_return_ok) { res = PX4_OK; } else { res = PX4_ERROR; } } if (res != PX4_OK) { if (active_sensors == 0) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_SENSOR_MSG); } return PX4_ERROR; } /* measurements completed successfully, rotate calibration values */ param_t board_rotation_h = param_find("SENS_BOARD_ROT"); int32_t board_rotation_int; param_get(board_rotation_h, &(board_rotation_int)); enum Rotation board_rotation_id = (enum Rotation)board_rotation_int; math::Matrix<3, 3> board_rotation; get_rot_matrix(board_rotation_id, &board_rotation); math::Matrix<3, 3> board_rotation_t = board_rotation.transposed(); bool tc_locked[3] = {false}; // true when the thermal parameter instance has already been adjusted by the calibrator for (unsigned uorb_index = 0; uorb_index < active_sensors; uorb_index++) { /* handle individual sensors, one by one */ math::Vector<3> accel_offs_vec(accel_offs[uorb_index]); math::Vector<3> accel_offs_rotated = board_rotation_t * accel_offs_vec; math::Matrix<3, 3> accel_T_mat(accel_T[uorb_index]); math::Matrix<3, 3> accel_T_rotated = board_rotation_t * accel_T_mat * board_rotation; accel_scale.x_offset = accel_offs_rotated(0); accel_scale.x_scale = accel_T_rotated(0, 0); accel_scale.y_offset = accel_offs_rotated(1); accel_scale.y_scale = accel_T_rotated(1, 1); accel_scale.z_offset = accel_offs_rotated(2); accel_scale.z_scale = accel_T_rotated(2, 2); bool failed = false; failed = failed || (PX4_OK != param_set_no_notification(param_find("CAL_ACC_PRIME"), &(device_id_primary))); PX4_INFO("found offset %d: x: %.6f, y: %.6f, z: %.6f", uorb_index, (double)accel_scale.x_offset, (double)accel_scale.y_offset, (double)accel_scale.z_offset); PX4_INFO("found scale %d: x: %.6f, y: %.6f, z: %.6f", uorb_index, (double)accel_scale.x_scale, (double)accel_scale.y_scale, (double)accel_scale.z_scale); /* check if thermal compensation is enabled */ int32_t tc_enabled_int; param_get(param_find("TC_A_ENABLE"), &(tc_enabled_int)); if (tc_enabled_int == 1) { /* Get struct containing sensor thermal compensation data */ struct sensor_correction_s sensor_correction; /**< sensor thermal corrections */ memset(&sensor_correction, 0, sizeof(sensor_correction)); int sensor_correction_sub = orb_subscribe(ORB_ID(sensor_correction)); orb_copy(ORB_ID(sensor_correction), sensor_correction_sub, &sensor_correction); orb_unsubscribe(sensor_correction_sub); /* don't allow a parameter instance to be calibrated more than once by another uORB instance */ if (!tc_locked[sensor_correction.accel_mapping[uorb_index]]) { tc_locked[sensor_correction.accel_mapping[uorb_index]] = true; /* update the _X0_ terms to include the additional offset */ int32_t handle; float val; for (unsigned axis_index = 0; axis_index < 3; axis_index++) { val = 0.0f; (void)sprintf(str, "TC_A%u_X0_%u", sensor_correction.accel_mapping[uorb_index], axis_index); handle = param_find(str); param_get(handle, &val); if (axis_index == 0) { val += accel_scale.x_offset; } else if (axis_index == 1) { val += accel_scale.y_offset; } else if (axis_index == 2) { val += accel_scale.z_offset; } failed |= (PX4_OK != param_set_no_notification(handle, &val)); } /* update the _SCL_ terms to include the scale factor */ for (unsigned axis_index = 0; axis_index < 3; axis_index++) { val = 1.0f; (void)sprintf(str, "TC_A%u_SCL_%u", sensor_correction.accel_mapping[uorb_index], axis_index); handle = param_find(str); if (axis_index == 0) { val = accel_scale.x_scale; } else if (axis_index == 1) { val = accel_scale.y_scale; } else if (axis_index == 2) { val = accel_scale.z_scale; } failed |= (PX4_OK != param_set_no_notification(handle, &val)); } param_notify_changes(); } // Ensure the calibration values used by the driver are at default settings when we are using thermal calibration data accel_scale.x_offset = 0.f; accel_scale.y_offset = 0.f; accel_scale.z_offset = 0.f; accel_scale.x_scale = 1.f; accel_scale.y_scale = 1.f; accel_scale.z_scale = 1.f; } // save the driver level calibration data (void)sprintf(str, "CAL_ACC%u_XOFF", uorb_index); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(accel_scale.x_offset))); (void)sprintf(str, "CAL_ACC%u_YOFF", uorb_index); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(accel_scale.y_offset))); (void)sprintf(str, "CAL_ACC%u_ZOFF", uorb_index); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(accel_scale.z_offset))); (void)sprintf(str, "CAL_ACC%u_XSCALE", uorb_index); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(accel_scale.x_scale))); (void)sprintf(str, "CAL_ACC%u_YSCALE", uorb_index); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(accel_scale.y_scale))); (void)sprintf(str, "CAL_ACC%u_ZSCALE", uorb_index); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(accel_scale.z_scale))); (void)sprintf(str, "CAL_ACC%u_ID", uorb_index); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(device_id[uorb_index]))); if (failed) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_SET_PARAMS_MSG, uorb_index); return PX4_ERROR; } #ifdef __PX4_NUTTX sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, uorb_index); fd = px4_open(str, 0); if (fd < 0) { calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, "sensor does not exist"); res = PX4_ERROR; } else { res = px4_ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale); px4_close(fd); } if (res != PX4_OK) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_APPLY_CAL_MSG, uorb_index); } #endif } if (res == PX4_OK) { /* if there is a any preflight-check system response, let the barrage of messages through */ usleep(200000); calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, sensor_name); } else { calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, sensor_name); } /* give this message enough time to propagate */ usleep(600000); return res; }
int do_accel_calibration(orb_advert_t *mavlink_log_pub) { #if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI) int fd; #endif calibration_log_info(mavlink_log_pub, CAL_QGC_STARTED_MSG, sensor_name); struct accel_calibration_s accel_scale; accel_scale.x_offset = 0.0f; accel_scale.x_scale = 1.0f; accel_scale.y_offset = 0.0f; accel_scale.y_scale = 1.0f; accel_scale.z_offset = 0.0f; accel_scale.z_scale = 1.0f; int res = OK; char str[30]; /* reset all sensors */ for (unsigned s = 0; s < max_accel_sens; s++) { #if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI) sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, s); /* reset all offsets to zero and all scales to one */ fd = px4_open(str, 0); if (fd < 0) { continue; } device_id[s] = px4_ioctl(fd, DEVIOCGDEVICEID, 0); res = px4_ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale); px4_close(fd); if (res != OK) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_RESET_CAL_MSG, s); } #else (void)sprintf(str, "CAL_ACC%u_XOFF", s); res = param_set(param_find(str), &accel_scale.x_offset); if (res != OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_ACC%u_YOFF", s); res = param_set(param_find(str), &accel_scale.y_offset); if (res != OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_ACC%u_ZOFF", s); res = param_set(param_find(str), &accel_scale.z_offset); if (res != OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_ACC%u_XSCALE", s); res = param_set(param_find(str), &accel_scale.x_scale); if (res != OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_ACC%u_YSCALE", s); res = param_set(param_find(str), &accel_scale.y_scale); if (res != OK) { PX4_ERR("unable to reset %s", str); } (void)sprintf(str, "CAL_ACC%u_ZSCALE", s); res = param_set(param_find(str), &accel_scale.z_scale); if (res != OK) { PX4_ERR("unable to reset %s", str); } #endif } float accel_offs[max_accel_sens][3]; float accel_T[max_accel_sens][3][3]; unsigned active_sensors; /* measure and calculate offsets & scales */ if (res == OK) { calibrate_return cal_return = do_accel_calibration_measurements(mavlink_log_pub, accel_offs, accel_T, &active_sensors); if (cal_return == calibrate_return_cancelled) { // Cancel message already displayed, nothing left to do return ERROR; } else if (cal_return == calibrate_return_ok) { res = OK; } else { res = ERROR; } } if (res != OK) { if (active_sensors == 0) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_SENSOR_MSG); } return ERROR; } /* measurements completed successfully, rotate calibration values */ param_t board_rotation_h = param_find("SENS_BOARD_ROT"); int32_t board_rotation_int; param_get(board_rotation_h, &(board_rotation_int)); enum Rotation board_rotation_id = (enum Rotation)board_rotation_int; math::Matrix<3, 3> board_rotation; get_rot_matrix(board_rotation_id, &board_rotation); math::Matrix<3, 3> board_rotation_t = board_rotation.transposed(); for (unsigned i = 0; i < active_sensors; i++) { /* handle individual sensors, one by one */ math::Vector<3> accel_offs_vec(accel_offs[i]); math::Vector<3> accel_offs_rotated = board_rotation_t * accel_offs_vec; math::Matrix<3, 3> accel_T_mat(accel_T[i]); math::Matrix<3, 3> accel_T_rotated = board_rotation_t * accel_T_mat * board_rotation; accel_scale.x_offset = accel_offs_rotated(0); accel_scale.x_scale = accel_T_rotated(0, 0); accel_scale.y_offset = accel_offs_rotated(1); accel_scale.y_scale = accel_T_rotated(1, 1); accel_scale.z_offset = accel_offs_rotated(2); accel_scale.z_scale = accel_T_rotated(2, 2); bool failed = false; failed = failed || (OK != param_set_no_notification(param_find("CAL_ACC_PRIME"), &(device_id_primary))); PX4_DEBUG("found offset %d: x: %.6f, y: %.6f, z: %.6f", i, (double)accel_scale.x_offset, (double)accel_scale.y_offset, (double)accel_scale.z_offset); PX4_DEBUG("found scale %d: x: %.6f, y: %.6f, z: %.6f", i, (double)accel_scale.x_scale, (double)accel_scale.y_scale, (double)accel_scale.z_scale); /* set parameters */ (void)sprintf(str, "CAL_ACC%u_XOFF", i); failed |= (OK != param_set_no_notification(param_find(str), &(accel_scale.x_offset))); (void)sprintf(str, "CAL_ACC%u_YOFF", i); failed |= (OK != param_set_no_notification(param_find(str), &(accel_scale.y_offset))); (void)sprintf(str, "CAL_ACC%u_ZOFF", i); failed |= (OK != param_set_no_notification(param_find(str), &(accel_scale.z_offset))); (void)sprintf(str, "CAL_ACC%u_XSCALE", i); failed |= (OK != param_set_no_notification(param_find(str), &(accel_scale.x_scale))); (void)sprintf(str, "CAL_ACC%u_YSCALE", i); 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))); (void)sprintf(str, "CAL_ACC%u_ID", i); failed |= (OK != param_set_no_notification(param_find(str), &(device_id[i]))); if (failed) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_SET_PARAMS_MSG, i); return ERROR; } #if !defined(__PX4_QURT) && !defined(__PX4_POSIX_EAGLE) && !defined(__PX4_POSIX_RPI) sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, i); fd = px4_open(str, 0); if (fd < 0) { calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, "sensor does not exist"); res = ERROR; } else { res = px4_ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale); px4_close(fd); } if (res != OK) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_APPLY_CAL_MSG, i); } #endif } if (res == OK) { /* auto-save to EEPROM */ res = param_save_default(); if (res != OK) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_SAVE_PARAMS_MSG); } /* if there is a any preflight-check system response, let the barrage of messages through */ usleep(200000); calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, sensor_name); } else { calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, sensor_name); } /* give this message enough time to propagate */ usleep(600000); return res; }
calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub) { calibrate_return result = calibrate_return_ok; mag_worker_data_t worker_data; worker_data.mavlink_log_pub = mavlink_log_pub; worker_data.done_count = 0; worker_data.calibration_points_perside = calibration_total_points / calibration_sides; worker_data.calibration_interval_perside_seconds = calibraton_duration_seconds / calibration_sides; worker_data.calibration_interval_perside_useconds = worker_data.calibration_interval_perside_seconds * 1000 * 1000; // Collect: As defined by configuration // start with a full mask, all six bits set uint32_t cal_mask = (1 << 6) - 1; param_get(param_find("CAL_MAG_SIDES"), &cal_mask); calibration_sides = 0; for (unsigned i = 0; i < (sizeof(worker_data.side_data_collected) / sizeof(worker_data.side_data_collected[0])); i++) { if ((cal_mask & (1 << i)) > 0) { // mark as missing worker_data.side_data_collected[i] = false; calibration_sides++; } else { // mark as completed from the beginning worker_data.side_data_collected[i] = true; calibration_log_info(mavlink_log_pub, "[cal] %s side done, rotate to a different side", detect_orientation_str(static_cast<enum detect_orientation_return>(i))); usleep(100000); } } for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { // Initialize to no subscription worker_data.sub_mag[cur_mag] = -1; // Initialize to no memory allocated worker_data.x[cur_mag] = nullptr; worker_data.y[cur_mag] = nullptr; worker_data.z[cur_mag] = nullptr; worker_data.calibration_counter_total[cur_mag] = 0; } const unsigned int calibration_points_maxcount = calibration_sides * worker_data.calibration_points_perside; char str[30]; for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { worker_data.x[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.y[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.z[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); if (worker_data.x[cur_mag] == nullptr || worker_data.y[cur_mag] == nullptr || worker_data.z[cur_mag] == nullptr) { calibration_log_critical(mavlink_log_pub, "[cal] ERROR: out of memory"); result = calibrate_return_error; } } // Setup subscriptions to mag sensors if (result == calibrate_return_ok) { // We should not try to subscribe if the topic doesn't actually exist and can be counted. const unsigned mag_count = orb_group_count(ORB_ID(sensor_mag)); // Warn that we will not calibrate more than max_mags magnetometers if (mag_count > max_mags) { calibration_log_critical(mavlink_log_pub, "[cal] Detected %u mags, but will calibrate only %u", mag_count, max_mags); } for (unsigned cur_mag = 0; cur_mag < mag_count && cur_mag < max_mags; cur_mag++) { // 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) || 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); device_ids[cur_mag] = mag_report.device_id; #endif if (worker_data.sub_mag[cur_mag] < 0) { calibration_log_critical(mavlink_log_pub, "[cal] Mag #%u not found, abort", cur_mag); result = calibrate_return_error; break; } if (device_ids[cur_mag] != 0) { // Get priority int32_t prio; orb_priority(worker_data.sub_mag[cur_mag], &prio); if (prio > device_prio_max) { device_prio_max = prio; device_id_primary = device_ids[cur_mag]; } } else { calibration_log_critical(mavlink_log_pub, "[cal] Mag #%u no device id, abort", cur_mag); result = calibrate_return_error; break; } } } // Limit update rate to get equally spaced measurements over time (in ms) if (result == calibrate_return_ok) { for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) { if (device_ids[cur_mag] != 0) { // Mag in this slot is available unsigned int orb_interval_msecs = (worker_data.calibration_interval_perside_useconds / 1000) / worker_data.calibration_points_perside; //calibration_log_info(mavlink_log_pub, "Orb interval %u msecs", orb_interval_msecs); orb_set_interval(worker_data.sub_mag[cur_mag], orb_interval_msecs); } } } if (result == calibrate_return_ok) { int cancel_sub = calibrate_cancel_subscribe(); result = calibrate_from_orientation(mavlink_log_pub, // uORB handle to write output cancel_sub, // Subscription to vehicle_command for cancel support worker_data.side_data_collected, // Sides to calibrate mag_calibration_worker, // Calibration worker &worker_data, // Opaque data for calibration worked true); // true: lenient still detection calibrate_cancel_unsubscribe(cancel_sub); } // Close subscriptions for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) { if (worker_data.sub_mag[cur_mag] >= 0) { px4_close(worker_data.sub_mag[cur_mag]); } } // Calculate calibration values for each mag float sphere_x[max_mags]; float sphere_y[max_mags]; float sphere_z[max_mags]; float sphere_radius[max_mags]; float diag_x[max_mags]; float diag_y[max_mags]; float diag_z[max_mags]; float offdiag_x[max_mags]; float offdiag_y[max_mags]; float offdiag_z[max_mags]; for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) { sphere_x[cur_mag] = 0.0f; sphere_y[cur_mag] = 0.0f; sphere_z[cur_mag] = 0.0f; sphere_radius[cur_mag] = 0.2f; diag_x[cur_mag] = 1.0f; diag_y[cur_mag] = 1.0f; diag_z[cur_mag] = 1.0f; offdiag_x[cur_mag] = 0.0f; offdiag_y[cur_mag] = 0.0f; offdiag_z[cur_mag] = 0.0f; } // Sphere fit the data to get calibration values if (result == calibrate_return_ok) { for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) { if (device_ids[cur_mag] != 0) { // Mag in this slot is available and we should have values for it to calibrate ellipsoid_fit_least_squares(worker_data.x[cur_mag], worker_data.y[cur_mag], worker_data.z[cur_mag], worker_data.calibration_counter_total[cur_mag], 100, 0.0f, &sphere_x[cur_mag], &sphere_y[cur_mag], &sphere_z[cur_mag], &sphere_radius[cur_mag], &diag_x[cur_mag], &diag_y[cur_mag], &diag_z[cur_mag], &offdiag_x[cur_mag], &offdiag_y[cur_mag], &offdiag_z[cur_mag]); result = check_calibration_result(sphere_x[cur_mag], sphere_y[cur_mag], sphere_z[cur_mag], sphere_radius[cur_mag], diag_x[cur_mag], diag_y[cur_mag], diag_z[cur_mag], offdiag_x[cur_mag], offdiag_y[cur_mag], offdiag_z[cur_mag], mavlink_log_pub, cur_mag); if (result == calibrate_return_error) { break; } } } } // Print uncalibrated data points if (result == calibrate_return_ok) { // DO NOT REMOVE! Critical validation data! // printf("RAW DATA:\n--------------------\n"); // for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { // if (worker_data.calibration_counter_total[cur_mag] == 0) { // continue; // } // printf("RAW: MAG %u with %u samples:\n", (unsigned)cur_mag, (unsigned)worker_data.calibration_counter_total[cur_mag]); // for (size_t i = 0; i < worker_data.calibration_counter_total[cur_mag]; i++) { // float x = worker_data.x[cur_mag][i]; // float y = worker_data.y[cur_mag][i]; // float z = worker_data.z[cur_mag][i]; // printf("%8.4f, %8.4f, %8.4f\n", (double)x, (double)y, (double)z); // } // printf(">>>>>>>\n"); // } // printf("CALIBRATED DATA:\n--------------------\n"); // for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { // if (worker_data.calibration_counter_total[cur_mag] == 0) { // continue; // } // printf("Calibrated: MAG %u with %u samples:\n", (unsigned)cur_mag, (unsigned)worker_data.calibration_counter_total[cur_mag]); // for (size_t i = 0; i < worker_data.calibration_counter_total[cur_mag]; i++) { // float x = worker_data.x[cur_mag][i] - sphere_x[cur_mag]; // float y = worker_data.y[cur_mag][i] - sphere_y[cur_mag]; // float z = worker_data.z[cur_mag][i] - sphere_z[cur_mag]; // printf("%8.4f, %8.4f, %8.4f\n", (double)x, (double)y, (double)z); // } // printf("SPHERE RADIUS: %8.4f\n", (double)sphere_radius[cur_mag]); // printf(">>>>>>>\n"); // } } // Data points are no longer needed for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { free(worker_data.x[cur_mag]); free(worker_data.y[cur_mag]); free(worker_data.z[cur_mag]); } if (result == calibrate_return_ok) { for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) { if (device_ids[cur_mag] != 0) { struct mag_calibration_s mscale; mscale.x_scale = 1.0; mscale.y_scale = 1.0; mscale.z_scale = 1.0; #if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) int fd_mag = -1; // Set new scale (void)sprintf(str, "%s%u", MAG_BASE_DEVICE_PATH, cur_mag); fd_mag = px4_open(str, 0); if (fd_mag < 0) { calibration_log_critical(mavlink_log_pub, "[cal] ERROR: unable to open mag device #%u", cur_mag); result = calibrate_return_error; } if (result == calibrate_return_ok) { if (px4_ioctl(fd_mag, MAGIOCGSCALE, (long unsigned int)&mscale) != PX4_OK) { calibration_log_critical(mavlink_log_pub, "[cal] ERROR: failed to get current calibration #%u", cur_mag); result = calibrate_return_error; } } #endif if (result == calibrate_return_ok) { mscale.x_offset = sphere_x[cur_mag]; mscale.y_offset = sphere_y[cur_mag]; mscale.z_offset = sphere_z[cur_mag]; mscale.x_scale = diag_x[cur_mag]; mscale.y_scale = diag_y[cur_mag]; mscale.z_scale = diag_z[cur_mag]; #if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP) if (px4_ioctl(fd_mag, MAGIOCSSCALE, (long unsigned int)&mscale) != PX4_OK) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_APPLY_CAL_MSG, cur_mag); result = calibrate_return_error; } #endif } #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); } #endif if (result == calibrate_return_ok) { bool failed = false; /* set parameters */ (void)sprintf(str, "CAL_MAG%u_ID", cur_mag); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(device_ids[cur_mag]))); (void)sprintf(str, "CAL_MAG%u_XOFF", cur_mag); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(mscale.x_offset))); (void)sprintf(str, "CAL_MAG%u_YOFF", cur_mag); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(mscale.y_offset))); (void)sprintf(str, "CAL_MAG%u_ZOFF", cur_mag); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(mscale.z_offset))); // FIXME: scaling is not used right now on QURT #ifndef __PX4_QURT (void)sprintf(str, "CAL_MAG%u_XSCALE", cur_mag); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(mscale.x_scale))); (void)sprintf(str, "CAL_MAG%u_YSCALE", cur_mag); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(mscale.y_scale))); (void)sprintf(str, "CAL_MAG%u_ZSCALE", cur_mag); failed |= (PX4_OK != param_set_no_notification(param_find(str), &(mscale.z_scale))); #endif if (failed) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_SET_PARAMS_MSG, cur_mag); result = calibrate_return_error; } else { calibration_log_info(mavlink_log_pub, "[cal] mag #%u off: x:%.2f y:%.2f z:%.2f Ga", cur_mag, (double)mscale.x_offset, (double)mscale.y_offset, (double)mscale.z_offset); #ifndef __PX4_QURT calibration_log_info(mavlink_log_pub, "[cal] mag #%u scale: x:%.2f y:%.2f z:%.2f", cur_mag, (double)mscale.x_scale, (double)mscale.y_scale, (double)mscale.z_scale); #endif usleep(200000); } } } } // Trigger a param set on the last step so the whole // system updates (void)param_set(param_find("CAL_MAG_PRIME"), &(device_id_primary)); } return result; }
bool ParameterTest::exportImportAll() { static constexpr float MAGIC_FLOAT_VAL = 0.217828f; // backup current parameters const char *param_file_name = PX4_STORAGEDIR "/param_backup"; int fd = open(param_file_name, O_WRONLY | O_CREAT, PX4_O_MODE_666); if (fd < 0) { PX4_ERR("open '%s' failed (%i)", param_file_name, errno); return false; } int result = param_export(fd, false); if (result != PX4_OK) { PX4_ERR("param_export failed"); close(fd); return false; } close(fd); bool ret = true; int N = param_count(); // set all params to corresponding param_t value for (unsigned i = 0; i < N; i++) { param_t p = param_for_index(i); if (p == PARAM_INVALID) { PX4_ERR("param invalid: %d(%d)", p, i); break; } if (param_type(p) == PARAM_TYPE_INT32) { const int32_t set_val = p; if (param_set_no_notification(p, &set_val) != PX4_OK) { PX4_ERR("param_set_no_notification failed for: %d", p); ut_assert("param_set_no_notification failed", false); } int32_t get_val = 0; if (param_get(p, &get_val) != PX4_OK) { PX4_ERR("param_get failed for: %d", p); ut_assert("param_set_no_notification failed", false); } ut_compare("value for param doesn't match default value", p, get_val); } if (param_type(p) == PARAM_TYPE_FLOAT) { const float set_val = (float)p + MAGIC_FLOAT_VAL; if (param_set_no_notification(p, &set_val) != PX4_OK) { PX4_ERR("param_set_no_notification failed for: %d", p); ut_assert("param_set_no_notification failed", false); } float get_val = 0.0f; if (param_get(p, &get_val) != PX4_OK) { PX4_ERR("param_get failed for: %d", p); ut_assert("param_set_no_notification failed", false); } ut_compare("value for param doesn't match default value", p, (float)p + MAGIC_FLOAT_VAL); } } // save if (param_save_default() != PX4_OK) { PX4_ERR("param_save_default failed"); return false; } // zero all params and verify, but don't save for (unsigned i = 0; i < N; i++) { param_t p = param_for_index(i); if (param_type(p) == PARAM_TYPE_INT32) { const int32_t set_val = 0; if (param_set_no_notification(p, &set_val) != PX4_OK) { PX4_ERR("param set failed: %d", p); ut_assert("param_set_no_notification failed", false); } int32_t get_val = -1; if (param_get(p, &get_val) != PX4_OK) { PX4_ERR("param_get failed for: %d", p); ut_assert("param_set_no_notification failed", false); } ut_compare("value for param doesn't match default value", set_val, get_val); } if (param_type(p) == PARAM_TYPE_FLOAT) { float set_val = 0.0f; if (param_set_no_notification(p, &set_val) != PX4_OK) { PX4_ERR("param set failed: %d", p); ut_assert("param_set_no_notification failed", false); } float get_val = -1.0f; if (param_get(p, &get_val) != PX4_OK) { PX4_ERR("param_get failed for: %d", p); ut_assert("param_set_no_notification failed", false); } ut_compare("value for param doesn't match default value", set_val, get_val); } } // load saved params if (param_load_default() != PX4_OK) { PX4_ERR("param_save_default failed"); ret = true; } // check every param for (unsigned i = 0; i < N; i++) { param_t p = param_for_index(i); if (param_type(p) == PARAM_TYPE_INT32) { int32_t get_val = 0; if (param_get(p, &get_val) != PX4_OK) { PX4_ERR("param_get failed for: %d", p); ut_assert("param_set_no_notification failed", false); } ut_compare("value for param doesn't match default value", p, get_val); } if (param_type(p) == PARAM_TYPE_FLOAT) { float get_val = 0.0f; if (param_get(p, &get_val) != PX4_OK) { PX4_ERR("param_get failed for: %d", p); ut_assert("param_set_no_notification failed", false); } ut_compare("value for param doesn't match default value", p, (float)p + MAGIC_FLOAT_VAL); } } param_reset_all(); // restore original params fd = open(param_file_name, O_RDONLY); if (fd < 0) { PX4_ERR("open '%s' failed (%i)", param_file_name, errno); return false; } result = param_import(fd); close(fd); if (result < 0) { PX4_ERR("importing from '%s' failed (%i)", param_file_name, result); return false; } // save if (param_save_default() != PX4_OK) { PX4_ERR("param_save_default failed"); return false; } return ret; }
bool ParameterTest::exportImport() { static constexpr float MAGIC_FLOAT_VAL = 0.314159f; bool ret = true; param_t test_params[] = {p0, p1, p2, p3, p4}; // set all params to corresponding param_t value for (auto p : test_params) { if (param_type(p) == PARAM_TYPE_INT32) { const int32_t set_val = p; if (param_set_no_notification(p, &set_val) != PX4_OK) { PX4_ERR("param_set_no_notification failed for: %d", p); ut_assert("param_set_no_notification failed", false); } int32_t get_val = 0; if (param_get(p, &get_val) != PX4_OK) { PX4_ERR("param_get failed for: %d", p); ut_assert("param_set_no_notification failed", false); } ut_compare("value for param doesn't match default value", p, get_val); } if (param_type(p) == PARAM_TYPE_FLOAT) { const float set_val = (float)p + MAGIC_FLOAT_VAL; if (param_set_no_notification(p, &set_val) != PX4_OK) { PX4_ERR("param_set_no_notification failed for: %d", p); ut_assert("param_set_no_notification failed", false); } float get_val = 0.0f; if (param_get(p, &get_val) != PX4_OK) { PX4_ERR("param_get failed for: %d", p); ut_assert("param_set_no_notification failed", false); } ut_compare("value for param doesn't match default value", p, (float)p + MAGIC_FLOAT_VAL); } } // save if (param_save_default() != PX4_OK) { PX4_ERR("param_save_default failed"); return false; } // zero all params and verify, but don't save for (auto p : test_params) { if (param_type(p) == PARAM_TYPE_INT32) { const int32_t set_val = 0; if (param_set_no_notification(p, &set_val) != PX4_OK) { PX4_ERR("param_set_no_notification failed for: %d", p); ut_assert("param_set_no_notification failed", false); } int32_t get_val = -1; if (param_get(p, &get_val) != PX4_OK) { PX4_ERR("param_get failed for: %d", p); ut_assert("param_set_no_notification failed", false); } ut_compare("value for param doesn't match default value", set_val, get_val); } if (param_type(p) == PARAM_TYPE_FLOAT) { const float set_val = 0.0f; if (param_set_no_notification(p, &set_val) != PX4_OK) { PX4_ERR("param_set_no_notification failed for: %d", p); ut_assert("param_set_no_notification failed", false); } float get_val = -1.0f; if (param_get(p, &get_val) != PX4_OK) { PX4_ERR("param_get failed for: %d", p); ut_assert("param_set_no_notification failed", false); } ut_compare_float("value for param doesn't match default value", set_val, get_val, 0.001f); } } // load saved params if (param_load_default() != PX4_OK) { PX4_ERR("param_save_default failed"); ret = true; } // check every param for (auto p : test_params) { if (param_type(p) == PARAM_TYPE_INT32) { int32_t get_val = 0.0f; if (param_get(p, &get_val) != PX4_OK) { PX4_ERR("param_get failed for: %d", p); ut_assert("param_set_no_notification failed", false); } ut_compare("value for param doesn't match default value", p, get_val); } if (param_type(p) == PARAM_TYPE_FLOAT) { float get_val = 0.0f; if (param_get(p, &get_val) != PX4_OK) { PX4_ERR("param_get failed for: %d", p); ut_assert("param_set_no_notification failed", false); } ut_compare_float("value for param doesn't match default value", p, (float)p + MAGIC_FLOAT_VAL, 0.001f); } } return ret; }
void CameraTrigger::cycle_trampoline(void *arg) { CameraTrigger *trig = reinterpret_cast<CameraTrigger *>(arg); // default loop polling interval int poll_interval_usec = 5000; if (trig->_command_sub < 0) { trig->_command_sub = orb_subscribe(ORB_ID(vehicle_command)); } bool updated = false; orb_check(trig->_command_sub, &updated); struct vehicle_command_s cmd; unsigned cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED; bool need_ack = false; // this flag is set when the polling loop is slowed down to allow the camera to power on trig->_turning_on = false; // these flags are used to detect state changes in the command loop bool main_state = trig->_trigger_enabled; bool pause_state = trig->_trigger_paused; // Command handling if (updated) { orb_copy(ORB_ID(vehicle_command), trig->_command_sub, &cmd); if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_DIGICAM_CONTROL) { need_ack = true; if (commandParamToInt(cmd.param7) == 1) { // test shots are not logged or forwarded to GCS for geotagging trig->_test_shot = true; } if (commandParamToInt((float)cmd.param5) == 1) { // Schedule shot trig->_one_shot = true; } cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED; } else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_TRIGGER_CONTROL) { need_ack = true; if (commandParamToInt(cmd.param3) == 1) { // pause triggger trig->_trigger_paused = true; } else if (commandParamToInt(cmd.param3) == 0) { trig->_trigger_paused = false; } if (commandParamToInt(cmd.param2) == 1) { // reset trigger sequence trig->_trigger_seq = 0; } if (commandParamToInt(cmd.param1) == 1) { trig->_trigger_enabled = true; } else if (commandParamToInt(cmd.param1) == 0) { trig->_trigger_enabled = false; } cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED; } else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST) { need_ack = true; /* * TRANSITIONAL SUPPORT ADDED AS OF 11th MAY 2017 (v1.6 RELEASE) */ if (cmd.param1 > 0.0f) { trig->_distance = cmd.param1; param_set_no_notification(trig->_p_distance, &(trig->_distance)); trig->_trigger_enabled = true; trig->_trigger_paused = false; } else if (commandParamToInt(cmd.param1) == 0) { trig->_trigger_paused = true; } else if (commandParamToInt(cmd.param1) == -1) { trig->_trigger_enabled = false; } // We can only control the shutter integration time of the camera in GPIO mode (for now) if (cmd.param2 > 0.0f) { if (trig->_camera_interface_mode == CAMERA_INTERFACE_MODE_GPIO) { trig->_activation_time = cmd.param2; param_set_no_notification(trig->_p_activation_time, &(trig->_activation_time)); } } // Trigger once immediately if param is set if (cmd.param3 > 0.0f) { // Schedule shot trig->_one_shot = true; } cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED; } else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL) { need_ack = true; if (cmd.param1 > 0.0f) { trig->_interval = cmd.param1; param_set_no_notification(trig->_p_interval, &(trig->_interval)); } // We can only control the shutter integration time of the camera in GPIO mode if (cmd.param2 > 0.0f) { if (trig->_camera_interface_mode == CAMERA_INTERFACE_MODE_GPIO) { trig->_activation_time = cmd.param2; param_set_no_notification(trig->_p_activation_time, &(trig->_activation_time)); } } cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED; } } // State change handling if ((main_state != trig->_trigger_enabled) || (pause_state != trig->_trigger_paused) || trig->_one_shot) { if (trig->_trigger_enabled || trig->_one_shot) { // Just got enabled via a command // If camera isn't already powered on, we enable power to it if (!trig->_camera_interface->is_powered_on() && trig->_camera_interface->has_power_control()) { trig->toggle_power(); trig->enable_keep_alive(true); // Give the camera time to turn on before starting to send trigger signals poll_interval_usec = 3000000; trig->_turning_on = true; } } else if (!trig->_trigger_enabled || trig->_trigger_paused) { // Just got disabled/paused via a command // Power off the camera if we are disabled if (trig->_camera_interface->is_powered_on() && trig->_camera_interface->has_power_control() && !trig->_trigger_enabled) { trig->enable_keep_alive(false); trig->toggle_power(); } // cancel all calls for both disabled and paused hrt_cancel(&trig->_engagecall); hrt_cancel(&trig->_disengagecall); // ensure that the pin is off hrt_call_after(&trig->_disengagecall, 0, (hrt_callout)&CameraTrigger::disengage, trig); // reset distance counter if needed if (trig->_trigger_mode == TRIGGER_MODE_DISTANCE_ON_CMD || trig->_trigger_mode == TRIGGER_MODE_DISTANCE_ALWAYS_ON) { // this will force distance counter reinit on getting enabled/unpaused trig->_valid_position = false; } } // only run on state changes, not every loop iteration if (trig->_trigger_mode == TRIGGER_MODE_INTERVAL_ON_CMD) { // update intervalometer state and reset calls trig->update_intervalometer(); } } // run every loop iteration and trigger if needed if (trig->_trigger_mode == TRIGGER_MODE_DISTANCE_ON_CMD || trig->_trigger_mode == TRIGGER_MODE_DISTANCE_ALWAYS_ON) { // update distance counter and trigger trig->update_distance(); } // One shot command-based capture handling if (trig->_one_shot && !trig->_turning_on) { // One-shot trigger trig->shoot_once(); trig->_one_shot = false; if (trig->_test_shot) { trig->_test_shot = false; } } // Command ACK handling if (updated && need_ack) { vehicle_command_ack_s command_ack = {}; command_ack.timestamp = hrt_absolute_time(); command_ack.command = cmd.command; command_ack.result = (uint8_t)cmd_result; command_ack.target_system = cmd.source_system; command_ack.target_component = cmd.source_component; if (trig->_cmd_ack_pub == nullptr) { trig->_cmd_ack_pub = orb_advertise_queue(ORB_ID(vehicle_command_ack), &command_ack, vehicle_command_ack_s::ORB_QUEUE_LENGTH); } else { orb_publish(ORB_ID(vehicle_command_ack), trig->_cmd_ack_pub, &command_ack); } } work_queue(LPWORK, &_work, (worker_t)&CameraTrigger::cycle_trampoline, camera_trigger::g_camera_trigger, USEC2TICK(poll_interval_usec)); }
CameraTrigger::CameraTrigger() : _engagecall {}, _disengagecall {}, _engage_turn_on_off_call {}, _disengage_turn_on_off_call {}, _keepalivecall_up {}, _keepalivecall_down {}, _activation_time(0.5f /* ms */), _interval(100.0f /* ms */), _distance(25.0f /* m */), _trigger_seq(0), _trigger_enabled(false), _trigger_paused(false), _one_shot(false), _test_shot(false), _turning_on(false), _last_shoot_position(0.0f, 0.0f), _valid_position(false), _command_sub(-1), _lpos_sub(-1), _trigger_pub(nullptr), _cmd_ack_pub(nullptr), _trigger_mode(TRIGGER_MODE_NONE), _cam_cap_fback(0), _camera_interface_mode(CAMERA_INTERFACE_MODE_GPIO), _camera_interface(nullptr) { // Initiate camera interface based on camera_interface_mode if (_camera_interface != nullptr) { delete (_camera_interface); // set to zero to ensure parser is not used while not instantiated _camera_interface = nullptr; } memset(&_work, 0, sizeof(_work)); // Parameters _p_interval = param_find("TRIG_INTERVAL"); _p_distance = param_find("TRIG_DISTANCE"); _p_activation_time = param_find("TRIG_ACT_TIME"); _p_mode = param_find("TRIG_MODE"); _p_interface = param_find("TRIG_INTERFACE"); _p_cam_cap_fback = param_find("CAM_CAP_FBACK"); param_get(_p_activation_time, &_activation_time); param_get(_p_interval, &_interval); param_get(_p_distance, &_distance); param_get(_p_mode, (int32_t *)&_trigger_mode); param_get(_p_interface, (int32_t *)&_camera_interface_mode); param_get(_p_cam_cap_fback, (int32_t *)&_cam_cap_fback); switch (_camera_interface_mode) { #ifdef __PX4_NUTTX case CAMERA_INTERFACE_MODE_GPIO: _camera_interface = new CameraInterfaceGPIO(); break; case CAMERA_INTERFACE_MODE_GENERIC_PWM: _camera_interface = new CameraInterfacePWM(); break; case CAMERA_INTERFACE_MODE_SEAGULL_MAP2_PWM: _camera_interface = new CameraInterfaceSeagull(); break; #endif case CAMERA_INTERFACE_MODE_MAVLINK: // start an interface that does nothing. Instead mavlink will listen to the camera_trigger uORB message _camera_interface = new CameraInterface(); break; default: PX4_ERR("unknown camera interface mode: %i", (int)_camera_interface_mode); break; } // Enforce a lower bound on the activation interval in PWM modes to not miss // engage calls in-between 50Hz PWM pulses. (see PX4 PR #6973) if ((_activation_time < 40.0f) && (_camera_interface_mode == CAMERA_INTERFACE_MODE_GENERIC_PWM || _camera_interface_mode == CAMERA_INTERFACE_MODE_SEAGULL_MAP2_PWM)) { _activation_time = 40.0f; PX4_WARN("Trigger interval too low for PWM interface, setting to 40 ms"); param_set_no_notification(_p_activation_time, &(_activation_time)); } // Advertise critical publishers here, because we cannot advertise in interrupt context struct camera_trigger_s trigger = {}; if (!_cam_cap_fback) { _trigger_pub = orb_advertise(ORB_ID(camera_trigger), &trigger); } else { _trigger_pub = orb_advertise(ORB_ID(camera_trigger_secondary), &trigger); } }