Copter: init vehicle capabilities

This commit is contained in:
Randy Mackay 2015-07-30 15:44:18 +09:00
parent 7d2c0079ff
commit 6765aedb5b
4 changed files with 11 additions and 14 deletions

View File

@ -946,7 +946,7 @@ private:
void print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode); void print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode);
void log_init(void); void log_init(void);
void run_cli(AP_HAL::UARTDriver *port); void run_cli(AP_HAL::UARTDriver *port);
uint64_t get_capabilities(void); void init_capabilities(void);
public: public:
void mavlink_delay_cb(); void mavlink_delay_cb();

View File

@ -1416,7 +1416,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: { case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: {
if (is_equal(packet.param1,1.0f)) { if (is_equal(packet.param1,1.0f)) {
copter.gcs[chan-MAVLINK_COMM_0].send_autopilot_version(copter.get_capabilities()); copter.gcs[chan-MAVLINK_COMM_0].send_autopilot_version();
result = MAV_RESULT_ACCEPTED; result = MAV_RESULT_ACCEPTED;
} }
break; break;
@ -1714,7 +1714,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
#endif // AC_RALLY == ENABLED #endif // AC_RALLY == ENABLED
case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST: case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST:
copter.gcs[chan-MAVLINK_COMM_0].send_autopilot_version(copter.get_capabilities()); copter.gcs[chan-MAVLINK_COMM_0].send_autopilot_version();
break; break;
case MAVLINK_MSG_ID_LED_CONTROL: case MAVLINK_MSG_ID_LED_CONTROL:

View File

@ -2,16 +2,10 @@
#include "Copter.h" #include "Copter.h"
uint64_t Copter::get_capabilities(void) void Copter::init_capabilities(void)
{ {
uint64_t capabilities = MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT);
| MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT);
| MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED);
| MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT; hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT);
#if AP_TERRAIN_AVAILABLE
capabilities |= MAV_PROTOCOL_CAPABILITY_TERRAIN;
#endif
return capabilities;
} }

View File

@ -266,6 +266,9 @@ void Copter::init_ardupilot()
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW)); ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
ins.set_dataflash(&DataFlash); ins.set_dataflash(&DataFlash);
// init vehicle capabilties
init_capabilities();
cliSerial->print_P(PSTR("\nReady to FLY ")); cliSerial->print_P(PSTR("\nReady to FLY "));
// flag that initialisation has completed // flag that initialisation has completed