APMrover2: use functor macros

Functor is not yet being used but let's make is macro fallback to the
previous Delegate implementation for easy of transition between the two.
This commit is contained in:
Lucas De Marchi 2015-05-24 20:24:11 -03:00 committed by Andrew Tridgell
parent c894a1349e
commit 2f5314a1a6
6 changed files with 12 additions and 11 deletions

View File

@ -40,7 +40,7 @@ Rover rover;
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpmf-conversions"
#define SCHED_TASK(func) AP_HAL_CLASSPROC_VOID(&rover, &Rover::func)
#define SCHED_TASK(func) FUNCTOR_BIND_VOID(&rover, &Rover::func, void)
/*
scheduler table - all regular tasks should be listed here, along

View File

@ -995,7 +995,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_SET_MODE:
{
handle_set_mode(msg, AP_HAL_CLASSPROC(&rover, &Rover::mavlink_set_mode));
handle_set_mode(msg, FUNCTOR_BIND(&rover, &Rover::mavlink_set_mode, bool, uint8_t));
break;
}
@ -1287,7 +1287,7 @@ void Rover::gcs_update(void)
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {
#if CLI_ENABLED == ENABLED
gcs[i].update(g.cli_enabled==1?AP_HAL_MEMBERPROC(&Rover::run_cli):NULL);
gcs[i].update(g.cli_enabled == 1 ? FUNCTOR_BIND_MEMBER(&Rover::run_cli, void, AP_HAL::UARTDriver *) : NULL);
#else
gcs[i].update(NULL);
#endif

View File

@ -20,7 +20,7 @@ static const struct Menu::command log_menu_commands[] PROGMEM = {
};
// A Macro to create the Menu
MENU2(log_menu, "Log", log_menu_commands, MENU_FUNC(print_log_menu));
MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&rover, &Rover::print_log_menu, bool));
bool Rover::print_log_menu(void)
{
@ -413,8 +413,8 @@ void Rover::Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
cliSerial->println_P(PSTR(HAL_BOARD_NAME));
DataFlash.LogReadProcess(log_num, start_page, end_page,
AP_HAL_MEMBERPROC(&Rover::print_mode),
DataFlash.LogReadProcess(log_num, start_page, end_page,
FUNCTOR_BIND_MEMBER(&Rover::print_mode, void, AP_HAL::BetterStream *, uint8_t),
cliSerial);
}
#endif // CLI_ENABLED

View File

@ -38,10 +38,10 @@ Rover::Rover(void) :
L1_controller(ahrs),
nav_controller(&L1_controller),
steerController(ahrs),
mission(ahrs,
AP_HAL_MEMBERPROC(&Rover::start_command),
AP_HAL_MEMBERPROC(&Rover::verify_command),
AP_HAL_MEMBERPROC(&Rover::exit_mission)),
mission(ahrs,
FUNCTOR_BIND_MEMBER(&Rover::start_command, bool, const AP_Mission::Mission_Command&),
FUNCTOR_BIND_MEMBER(&Rover::verify_command, bool, const AP_Mission::Mission_Command&),
FUNCTOR_BIND_MEMBER(&Rover::exit_mission, void)),
num_gcs(MAVLINK_COMM_NUM_BUFFERS),
ServoRelayEvents(relay),
#if CAMERA == ENABLED

View File

@ -533,7 +533,7 @@ public:
#endif
};
#define MENU_FUNC(func) AP_HAL_CLASSPROC(&rover, &Rover::func)
#define MENU_FUNC(func) FUNCTOR_BIND(&rover, &Rover::func, int8_t, uint8_t, const Menu::arg *)
extern const AP_HAL::HAL& hal;
extern Rover rover;

View File

@ -26,6 +26,7 @@ int8_t Rover::main_menu_help(uint8_t argc, const Menu::arg *argv)
}
// Command/function table for the top-level menu.
static const struct Menu::command main_menu_commands[] PROGMEM = {
// command function called
// ======= ===============