Merge pull request #2216 from DonLakeFlyer/CalESC

ESC Calibration
This commit is contained in:
Lorenz Meier 2015-05-22 22:27:11 +02:00
commit 0bd0f7dae5
4 changed files with 114 additions and 81 deletions

View File

@ -52,6 +52,7 @@
#define CAL_QGC_STARTED_MSG "[cal] calibration started: 1 %s" #define CAL_QGC_STARTED_MSG "[cal] calibration started: 1 %s"
#define CAL_QGC_DONE_MSG "[cal] calibration done: %s" #define CAL_QGC_DONE_MSG "[cal] calibration done: %s"
#define CAL_QGC_FAILED_MSG "[cal] calibration failed: %s" #define CAL_QGC_FAILED_MSG "[cal] calibration failed: %s"
#define CAL_QGC_WARNING_MSG "[cal] calibration warning: %s"
#define CAL_QGC_CANCELLED_MSG "[cal] calibration cancelled" #define CAL_QGC_CANCELLED_MSG "[cal] calibration cancelled"
#define CAL_QGC_PROGRESS_MSG "[cal] progress <%u>" #define CAL_QGC_PROGRESS_MSG "[cal] progress <%u>"
#define CAL_QGC_ORIENTATION_DETECTED_MSG "[cal] %s orientation detected" #define CAL_QGC_ORIENTATION_DETECTED_MSG "[cal] %s orientation detected"

View File

@ -326,6 +326,8 @@ int commander_main(int argc, char *argv[])
calib_ret = do_gyro_calibration(mavlink_fd); calib_ret = do_gyro_calibration(mavlink_fd);
} else if (!strcmp(argv[2], "level")) { } else if (!strcmp(argv[2], "level")) {
calib_ret = do_level_calibration(mavlink_fd); calib_ret = do_level_calibration(mavlink_fd);
} else if (!strcmp(argv[2], "esc")) {
calib_ret = do_esc_calibration(mavlink_fd, &armed);
} else { } else {
warnx("argument %s unsupported.", argv[2]); warnx("argument %s unsupported.", argv[2]);
} }
@ -2744,13 +2746,8 @@ void *commander_low_prio_loop(void *arg)
} else if ((int)(cmd.param7) == 1) { } else if ((int)(cmd.param7) == 1) {
/* do esc calibration */ /* do esc calibration */
calib_ret = check_if_batt_disconnected(mavlink_fd);
if(calib_ret == OK) {
answer_command(cmd,VEHICLE_CMD_RESULT_ACCEPTED); answer_command(cmd,VEHICLE_CMD_RESULT_ACCEPTED);
armed.in_esc_calibration_mode = true; calib_ret = do_esc_calibration(mavlink_fd, &armed);
calib_ret = do_esc_calibration(mavlink_fd);
armed.in_esc_calibration_mode = false;
}
} else if ((int)(cmd.param4) == 0) { } else if ((int)(cmd.param4) == 0) {
/* RC calibration ended - have we been in one worth confirming? */ /* RC calibration ended - have we been in one worth confirming? */

View File

@ -40,6 +40,8 @@
*/ */
#include "esc_calibration.h" #include "esc_calibration.h"
#include "calibration_messages.h"
#include <stdio.h> #include <stdio.h>
#include <stdlib.h> #include <stdlib.h>
#include <string.h> #include <string.h>
@ -63,91 +65,122 @@
#endif #endif
static const int ERROR = -1; static const int ERROR = -1;
int check_if_batt_disconnected(int mavlink_fd) { int do_esc_calibration(int mavlink_fd, struct actuator_armed_s* armed)
{
int return_code = OK;
int fd = -1;
struct battery_status_s battery; struct battery_status_s battery;
memset(&battery,0,sizeof(battery)); int batt_sub = -1;
int batt_sub = orb_subscribe(ORB_ID(battery_status)); bool batt_updated = false;
orb_copy(ORB_ID(battery_status), batt_sub, &battery); bool batt_connected = false;
if (battery.voltage_filtered_v > 3.0f && !(hrt_absolute_time() - battery.timestamp > 500000)) { hrt_abstime battery_connect_wait_timeout = 20000000;
mavlink_log_info(mavlink_fd, "Please disconnect battery and try again!"); hrt_abstime pwm_high_timeout = 5000000;
return ERROR; hrt_abstime timeout_start;
mavlink_and_console_log_info(mavlink_fd, CAL_QGC_STARTED_MSG, "esc");
batt_sub = orb_subscribe(ORB_ID(battery_status));
if (batt_sub < 0) {
mavlink_and_console_log_critical(mavlink_fd, CAL_QGC_FAILED_MSG, "Subscribe to battery");
goto Error;
} }
return OK;
}
// Make sure battery is disconnected
orb_copy(ORB_ID(battery_status), batt_sub, &battery);
if (battery.voltage_filtered_v > 3.0f) {
mavlink_and_console_log_critical(mavlink_fd, CAL_QGC_FAILED_MSG, "Disconnect battery and try again");
goto Error;
}
int do_esc_calibration(int mavlink_fd) { armed->in_esc_calibration_mode = true;
int fd = px4_open(PWM_OUTPUT0_DEVICE_PATH, 0); fd = px4_open(PWM_OUTPUT0_DEVICE_PATH, 0);
int ret;
if(fd < 0) { if (fd < 0) {
err(1,"Can't open %s", PWM_OUTPUT0_DEVICE_PATH); mavlink_and_console_log_critical(mavlink_fd, CAL_QGC_FAILED_MSG, "Can't open PWM device");
goto Error;
} }
/* tell IO/FMU that its ok to disable its safety with the switch */ /* tell IO/FMU that its ok to disable its safety with the switch */
ret = px4_ioctl(fd, PWM_SERVO_SET_ARM_OK, 0); if (px4_ioctl(fd, PWM_SERVO_SET_ARM_OK, 0) != OK) {
if (ret != OK) mavlink_and_console_log_critical(mavlink_fd, CAL_QGC_FAILED_MSG, "Unable to disable safety switch");
err(1, "PWM_SERVO_SET_ARM_OK"); goto Error;
}
/* tell IO/FMU that the system is armed (it will output values if safety is off) */ /* tell IO/FMU that the system is armed (it will output values if safety is off) */
ret = px4_ioctl(fd, PWM_SERVO_ARM, 0); if (px4_ioctl(fd, PWM_SERVO_ARM, 0) != OK) {
if (ret != OK) mavlink_and_console_log_critical(mavlink_fd, CAL_QGC_FAILED_MSG, "Unable to arm system");
err(1, "PWM_SERVO_ARM"); goto Error;
}
/* tell IO to switch off safety without using the safety switch */ /* tell IO to switch off safety without using the safety switch */
ret = px4_ioctl(fd, PWM_SERVO_SET_FORCE_SAFETY_OFF, 0); if (px4_ioctl(fd, PWM_SERVO_SET_FORCE_SAFETY_OFF, 0) != OK) {
if(ret!=0) { mavlink_and_console_log_critical(mavlink_fd, CAL_QGC_FAILED_MSG, "Unable to force safety off");
err(1,"PWM_SERVO_SET_FORCE_SAFETY_OFF"); goto Error;
} }
mavlink_log_info(mavlink_fd,"Please connect battery now"); mavlink_and_console_log_info(mavlink_fd, "[cal] Connect battery now");
struct battery_status_s battery; timeout_start = hrt_absolute_time();
memset(&battery,0,sizeof(battery));
int batt_sub = orb_subscribe(ORB_ID(battery_status));
orb_copy(ORB_ID(vehicle_command),batt_sub, &battery);
bool updated = false;
struct vehicle_command_s cmd; while (true) {
memset(&cmd, 0, sizeof(cmd)); // We are either waiting for the user to connect the battery. Or we are waiting to let the PWM
int cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); // sit high.
orb_copy(ORB_ID(vehicle_command),cmd_sub, &cmd); hrt_abstime timeout_wait = batt_connected ? pwm_high_timeout : battery_connect_wait_timeout;
/* wait for one of the following events: if (hrt_absolute_time() - timeout_start > timeout_wait) {
1) user has pressed the button in QGroundControl if (!batt_connected) {
2) timeout of 5 seconds is reached mavlink_and_console_log_critical(mavlink_fd, CAL_QGC_FAILED_MSG, "Timeout waiting for battery");
*/ goto Error;
hrt_abstime start_time = hrt_absolute_time(); }
while(true) { // PWM was high long enough
orb_check(batt_sub,&updated); break;
if(updated) { }
if (!batt_connected) {
orb_check(batt_sub, &batt_updated);
if (batt_updated) {
orb_copy(ORB_ID(battery_status), batt_sub, &battery); orb_copy(ORB_ID(battery_status), batt_sub, &battery);
} if (battery.voltage_filtered_v > 3.0f) {
// user has connected battery // Battery is connected, signal to user and start waiting again
if(battery.voltage_filtered_v > 3.0f) { batt_connected = true;
orb_check(cmd_sub,&updated); timeout_start = hrt_absolute_time();
if(updated) { mavlink_and_console_log_info(mavlink_fd, "[cal] Battery connected");
orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
}
if((int)(cmd.param7) == 2 && cmd.command == VEHICLE_CMD_PREFLIGHT_CALIBRATION) {
break;
} else if (hrt_absolute_time() - start_time > 5000000) {
// waited for 5 seconds, switch to low pwm
break;
} }
} }
else {
start_time = hrt_absolute_time();
} }
usleep(50000); usleep(50000);
} }
/* disarm */ Out:
ret = px4_ioctl(fd, PWM_SERVO_DISARM, 0); if (batt_sub != -1) {
if (ret != OK) orb_unsubscribe(batt_sub);
err(1, "PWM_SERVO_DISARM");
mavlink_log_info(mavlink_fd,"ESC calibration finished");
return OK;
} }
if (fd != -1) {
if (px4_ioctl(fd, PWM_SERVO_SET_FORCE_SAFETY_ON, 0) != OK) {
mavlink_and_console_log_info(mavlink_fd, CAL_QGC_WARNING_MSG, "Safety switch still off");
}
if (px4_ioctl(fd, PWM_SERVO_DISARM, 0) != OK) {
mavlink_and_console_log_info(mavlink_fd, CAL_QGC_WARNING_MSG, "Servos still armed");
}
if (px4_ioctl(fd, PWM_SERVO_CLEAR_ARM_OK, 0) != OK) {
mavlink_and_console_log_info(mavlink_fd, CAL_QGC_WARNING_MSG, "Safety switch still deactivated");
}
px4_close(fd);
}
armed->in_esc_calibration_mode = false;
if (return_code == OK) {
mavlink_and_console_log_info(mavlink_fd, CAL_QGC_DONE_MSG, "esc");
}
return return_code;
Error:
return_code = ERROR;
goto Out;
}

View File

@ -41,7 +41,9 @@
#ifndef ESC_CALIBRATION_H_ #ifndef ESC_CALIBRATION_H_
#define ESC_CALIBRATION_H_ #define ESC_CALIBRATION_H_
int check_if_batt_disconnected(int mavlink_fd);
int do_esc_calibration(int mavlink_fd); #include <uORB/topics/actuator_armed.h>
int do_esc_calibration(int mavlink_fd, struct actuator_armed_s* armed);
#endif #endif