Skip to content

Commit

Permalink
Add esc_calib to as an app in cli
Browse files Browse the repository at this point in the history
Usage Notes:
- when in cli mode select setup
- inside setup use esc_calib <chan_mask> to launch esc calibration
  e.g. esc_calib 1010 : enable calibration for Motor 2 and Motor 4
  • Loading branch information
bugobliterator committed Jul 7, 2014
1 parent ccb7ea0 commit e2e25f1
Show file tree
Hide file tree
Showing 2 changed files with 163 additions and 1 deletion.
25 changes: 25 additions & 0 deletions ArduCopter/config.h
Expand Up @@ -647,7 +647,32 @@
#ifndef HYBRID_BRAKE_ANGLE_DEFAULT
# define HYBRID_BRAKE_ANGLE_DEFAULT 3000 // default HYBRID_BRAKE_ANGLE param value. Max lean angle during braking in centi-degrees
#endif
//////////////////////////////////////////////////////////////////////////////
// Callibration Limits
//
#ifndef PWM_CALIB_MIN
# define PWM_CALIB_MIN 1000
#endif

#ifndef PWM_CALIB_MAX
# define PWM_CALIB_MAX 2000
#endif

#ifndef PWM_HIGHEST_MAX
# define PWM_HIGHEST_MAX 2200
#endif

#ifndef PWM_LOWEST_MAX
# define PWM_LOWEST_MAX 1200
#endif

#ifndef PWM_HIGHEST_MIN
# define PWM_HIGHEST_MIN 1800
#endif

#ifndef PWM_LOWEST_MIN
# define PWM_LOWEST_MIN 800
#endif
//////////////////////////////////////////////////////////////////////////////
// Throttle control gains
//
Expand Down
139 changes: 138 additions & 1 deletion ArduCopter/setup.pde
Expand Up @@ -5,14 +5,15 @@
// Functions called from the setup menu
static int8_t setup_factory (uint8_t argc, const Menu::arg *argv);
static int8_t setup_show (uint8_t argc, const Menu::arg *argv);

static int8_t esc_calib (uint8_t argc, const Menu::arg *argv);

// Command/function table for the setup menu
const struct Menu::command setup_menu_commands[] PROGMEM = {
// command function called
// ======= ===============
{"reset", setup_factory},
{"show", setup_show},
{"esc_calib", esc_calib},
};

// Create the setup menu object.
Expand Down Expand Up @@ -98,6 +99,142 @@ setup_show(uint8_t argc, const Menu::arg *argv)
return(0);
}

static int8_t
esc_calib(uint8_t argc,const Menu::arg *argv)
{


char c;
unsigned max_channels = 0;
uint32_t set_mask = 0;

uint16_t pwm_high = PWM_CALIB_MAX;
uint16_t pwm_low = PWM_CALIB_MIN;


if (argc < 2) {
cliSerial->printf_P(PSTR("Pls provide Channel Mask\n"
"\tusage: esc_calib 1010 - enables calibration for 2nd and 4th Motor\n"));
return(0);
}



set_mask = strtol (argv[1].str, NULL, 2);
if (set_mask == 0)
cliSerial->printf_P(PSTR("no channels chosen"));
//cliSerial->printf_P(PSTR("\n%d\n"),set_mask);
set_mask<<=1;
/* wait 50 ms */
hal.scheduler->delay(50);


cliSerial->printf_P(PSTR("\nATTENTION, please remove or fix propellers before starting calibration!\n"
"\n"
"Make sure\n"
"\t - that the ESCs are not powered\n"
"\t - that safety is off\n"
"\t - that the controllers are stopped\n"
"\n"
"Do you want to start calibration now: y or n?\n"));

/* wait for user input */
while (1) {
c= cliSerial->read();
if (c == 'y' || c == 'Y') {

break;

} else if (c == 0x03 || c == 0x63 || c == 'q') {
cliSerial->printf_P(PSTR("ESC calibration exited\n"));
return(0);

} else if (c == 'n' || c == 'N') {
cliSerial->printf_P(PSTR("ESC calibration aborted\n"));
return(0);

}

/* rate limit to ~ 20 Hz */
hal.scheduler->delay(50);
}


/* get number of channels available on the device */
max_channels = AP_MOTORS_MAX_NUM_MOTORS;

/* tell IO/FMU that the system is armed (it will output values if safety is off) */
motors.armed(true);


cliSerial->printf_P(PSTR("Outputs armed\n"));


/* wait for user confirmation */
cliSerial->printf_P(PSTR("\nHigh PWM set: %d\n"
"\n"
"Connect battery now and hit c+ENTER after the ESCs confirm the first calibration step\n"
"\n"), pwm_high);

while (1) {
/* set max PWM */
for (unsigned i = 0; i < max_channels; i++) {

if (set_mask & 1<<i) {
motors.output_test(i, pwm_high);
}
}
c = cliSerial->read();

if (c == 'c') {
break;

} else if (c == 0x03 || c == 0x63 || c == 'q') {
cliSerial->printf_P(PSTR("ESC calibration exited\n"));
return(0);
}

/* rate limit to ~ 20 Hz */
hal.scheduler->delay(50);
}

cliSerial->printf_P(PSTR("Low PWM set: %d\n"
"\n"
"Hit c+Enter when finished\n"
"\n"), pwm_low);

while (1) {

/* set disarmed PWM */
for (unsigned i = 0; i < max_channels; i++) {
if (set_mask & 1<<i) {
motors.output_test(i, pwm_low);
}
}
c = cliSerial->read();

if (c == 'c') {

break;

} else if (c == 0x03 || c == 0x63 || c == 'q') {
cliSerial->printf_P(PSTR("ESC calibration exited\n"));
return(0);
}

/* rate limit to ~ 20 Hz */
hal.scheduler->delay(50);
}

/* disarm */
motors.armed(false);

cliSerial->printf_P(PSTR("Outputs disarmed\n"));

cliSerial->printf_P(PSTR("ESC calibration finished\n"));

return(0);
}
/***************************************************************************/
// CLI reports
/***************************************************************************/
Expand Down

0 comments on commit e2e25f1

Please sign in to comment.