diff --git a/ArduCopter/capabilities.cpp b/ArduCopter/capabilities.cpp index 0a3b4b0aa1..186dd7ca26 100644 --- a/ArduCopter/capabilities.cpp +++ b/ArduCopter/capabilities.cpp @@ -4,13 +4,13 @@ void Copter::init_capabilities(void) { - hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT); - hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT); - hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_INT); - hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED); - hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT); - hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION); - hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET); + hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT | + MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | + MAV_PROTOCOL_CAPABILITY_MISSION_INT | + MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED | + MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT | + MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION | + MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET); #if AP_TERRAIN_AVAILABLE && AC_TERRAIN hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_TERRAIN); #endif