diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 3696d86659..03764b3e82 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -133,7 +133,7 @@ private: AP_Scheduler scheduler = AP_Scheduler::create(); // mapping between input channels - RCMapper rcmap; + RCMapper rcmap = RCMapper::create(); // board specific config AP_BoardConfig BoardConfig; diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index c86b7d6a79..63cf0edc54 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -313,8 +313,8 @@ private: // altitude below which we do no navigation in auto takeoff float auto_takeoff_no_nav_alt_cm; - - RCMapper rcmap; + + RCMapper rcmap = RCMapper::create(); // board specific config AP_BoardConfig BoardConfig; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index ac46701f36..89659005aa 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -169,7 +169,7 @@ private: AP_Scheduler scheduler = AP_Scheduler::create(); // mapping between input channels - RCMapper rcmap; + RCMapper rcmap = RCMapper::create(); // board specific config AP_BoardConfig BoardConfig; diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 28061023db..5855dcc0ea 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -251,7 +251,7 @@ private: mode_reason_t prev_control_mode_reason = MODE_REASON_UNKNOWN; #if RCMAP_ENABLED == ENABLED - RCMapper rcmap; + RCMapper rcmap = RCMapper::create(); #endif // board specific config