ArduPlane: 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 2f5314a1a6
commit 7c4cf41ebc
5 changed files with 11 additions and 11 deletions

View File

@ -26,7 +26,7 @@
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpmf-conversions"
#define SCHED_TASK(func) AP_HAL_CLASSPROC_VOID(&plane, &Plane::func)
#define SCHED_TASK(func) FUNCTOR_BIND_VOID(&plane, &Plane::func, void)
/*
scheduler table - all regular tasks are listed here, along with how

View File

@ -1288,7 +1288,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_SET_MODE:
{
handle_set_mode(msg, AP_HAL_CLASSPROC(&plane, &Plane::mavlink_set_mode));
handle_set_mode(msg, FUNCTOR_BIND(&plane, &Plane::mavlink_set_mode, bool, uint8_t));
break;
}
@ -1704,7 +1704,7 @@ void Plane::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(&Plane::run_cli):NULL);
gcs[i].update(g.cli_enabled == 1 ? FUNCTOR_BIND_MEMBER(&Plane::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(&plane, &Plane::print_log_menu, bool));
bool Plane::print_log_menu(void)
{
@ -493,8 +493,8 @@ void Plane::Log_Read(uint16_t log_num, int16_t start_page, int16_t end_page)
cliSerial->println_P(PSTR(HAL_BOARD_NAME));
DataFlash.LogReadProcess(log_num, start_page, end_page,
AP_HAL_MEMBERPROC(&Plane::print_flight_mode),
DataFlash.LogReadProcess(log_num, start_page, end_page,
FUNCTOR_BIND_MEMBER(&Plane::print_flight_mode, void, AP_HAL::BetterStream *, uint8_t),
cliSerial);
}
#endif // CLI_ENABLED

View File

@ -58,9 +58,9 @@ Plane::Plane(void) :
flight_stage(AP_SpdHgtControl::FLIGHT_NORMAL),
aerodynamic_load_factor(1.0f),
mission(ahrs,
AP_HAL_MEMBERPROC(&Plane::start_command_callback),
AP_HAL_MEMBERPROC(&Plane::verify_command_callback),
AP_HAL_MEMBERPROC(&Plane::exit_mission_callback)),
FUNCTOR_BIND_MEMBER(&Plane::start_command_callback, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&Plane::verify_command_callback, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&Plane::exit_mission_callback, void)),
#if AP_TERRAIN_AVAILABLE
terrain(ahrs, mission, rally),
#endif
@ -72,7 +72,7 @@ Plane::Plane(void) :
#if MOUNT == ENABLED
camera_mount(ahrs, current_loc),
#endif
arming(ahrs, barometer, compass, home_is_set, AP_HAL_MEMBERPROC(&Plane::gcs_send_text_P)),
arming(ahrs, barometer, compass, home_is_set, FUNCTOR_BIND_MEMBER(&Plane::gcs_send_text_P, void, gcs_severity, const prog_char_t *)),
param_loader(var_info)
{
elevon.trim1 = 1500;

View File

@ -918,7 +918,7 @@ public:
int8_t test_shell(uint8_t argc, const Menu::arg *argv);
};
#define MENU_FUNC(func) AP_HAL_CLASSPROC(&plane, &Plane::func)
#define MENU_FUNC(func) FUNCTOR_BIND(&plane, &Plane::func, int8_t, uint8_t, const Menu::arg *)
extern const AP_HAL::HAL& hal;
extern Plane plane;