ardupilot/ArduSub/capabilities.cpp

16 lines
700 B
C++
Raw Normal View History

2016-01-14 15:30:56 -04:00
#include "Sub.h"
void Sub::init_capabilities()
{
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT);
2016-05-03 01:45:37 -03:00
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);
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_TERRAIN);
#endif
}