Browse Source

GCS_MAVLink: support for sending generator message

zr-v5.1
Peter Barker 5 years ago committed by Randy Mackay
parent
commit
e2056f56e3
  1. 1
      libraries/GCS_MAVLink/GCS.h
  2. 17
      libraries/GCS_MAVLink/GCS_Common.cpp
  3. 1
      libraries/GCS_MAVLink/ap_message.h

1
libraries/GCS_MAVLink/GCS.h

@ -264,6 +264,7 @@ public: @@ -264,6 +264,7 @@ public:
void send_sys_status();
void send_set_position_target_global_int(uint8_t target_system, uint8_t target_component, const Location& loc);
void send_rpm() const;
void send_generator_status() const;
// lock a channel, preventing use by MAVLink
void lock(bool _lock) {

17
libraries/GCS_MAVLink/GCS_Common.cpp

@ -797,6 +797,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c @@ -797,6 +797,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
{ MAVLINK_MSG_ID_EXTENDED_SYS_STATE, MSG_EXTENDED_SYS_STATE},
{ MAVLINK_MSG_ID_AUTOPILOT_VERSION, MSG_AUTOPILOT_VERSION},
{ MAVLINK_MSG_ID_EFI_STATUS, MSG_EFI_STATUS},
{ MAVLINK_MSG_ID_GENERATOR_STATUS, MSG_GENERATOR_STATUS},
};
for (uint8_t i=0; i<ARRAY_SIZE(map); i++) {
@ -4368,6 +4369,17 @@ void GCS_MAVLINK::send_set_position_target_global_int(uint8_t target_system, uin @@ -4368,6 +4369,17 @@ void GCS_MAVLINK::send_set_position_target_global_int(uint8_t target_system, uin
0,0); // yaw, yaw_rate
}
void GCS_MAVLINK::send_generator_status() const
{
#if GENERATOR_ENABLED
AP_Generator_RichenPower *generator = AP::generator();
if (generator == nullptr) {
return;
}
generator->send_generator_status(*this);
#endif
}
bool GCS_MAVLINK::try_send_message(const enum ap_message id)
{
bool ret = true;
@ -4632,6 +4644,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) @@ -4632,6 +4644,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
send_vibration();
break;
case MSG_GENERATOR_STATUS:
CHECK_PAYLOAD_SIZE(GENERATOR_STATUS);
send_generator_status();
break;
case MSG_AUTOPILOT_VERSION:
CHECK_PAYLOAD_SIZE(AUTOPILOT_VERSION);
send_autopilot_version();

1
libraries/GCS_MAVLink/ap_message.h

@ -73,5 +73,6 @@ enum ap_message : uint8_t { @@ -73,5 +73,6 @@ enum ap_message : uint8_t {
MSG_EXTENDED_SYS_STATE,
MSG_AUTOPILOT_VERSION,
MSG_EFI_STATUS,
MSG_GENERATOR_STATUS,
MSG_LAST // MSG_LAST must be the last entry in this enum
};

Loading…
Cancel
Save