diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index f1c12a5545..621e866de9 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -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 diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 3e45450eac..3a9020157b 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -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; iprintln_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 diff --git a/ArduPlane/Plane.cpp b/ArduPlane/Plane.cpp index 0a18cb23ec..2a14657424 100644 --- a/ArduPlane/Plane.cpp +++ b/ArduPlane/Plane.cpp @@ -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; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 7c87467c6c..bbddca18c9 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -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;