mirror of https://github.com/ArduPilot/ardupilot
Copter: add capability bitmask
This commit is contained in:
parent
c946ce72e8
commit
edf5ff1bbe
|
@ -946,6 +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);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
void mavlink_delay_cb();
|
void mavlink_delay_cb();
|
||||||
|
|
|
@ -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.gcs[chan-MAVLINK_COMM_0].send_autopilot_version(copter.get_capabilities());
|
||||||
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.gcs[chan-MAVLINK_COMM_0].send_autopilot_version(copter.get_capabilities());
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_LED_CONTROL:
|
case MAVLINK_MSG_ID_LED_CONTROL:
|
||||||
|
|
|
@ -0,0 +1,17 @@
|
||||||
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
|
#include "Copter.h"
|
||||||
|
|
||||||
|
uint64_t Copter::get_capabilities(void)
|
||||||
|
{
|
||||||
|
uint64_t capabilities = MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT
|
||||||
|
| MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT
|
||||||
|
| MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED
|
||||||
|
| MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT;
|
||||||
|
|
||||||
|
#if AP_TERRAIN_AVAILABLE
|
||||||
|
capabilities |= MAV_PROTOCOL_CAPABILITY_TERRAIN;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return capabilities;
|
||||||
|
}
|
Loading…
Reference in New Issue