Sub: move mavlink support for servo/relay up

This commit is contained in:
Peter Barker 2017-07-14 12:54:06 +10:00 committed by Francisco Ferreira
parent bcf7c6e6b6
commit 4723194a01
2 changed files with 6 additions and 24 deletions

View File

@ -1269,30 +1269,6 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
} }
break; break;
case MAV_CMD_DO_SET_SERVO:
if (sub.ServoRelayEvents.do_set_servo(packet.param1, packet.param2)) {
result = MAV_RESULT_ACCEPTED;
}
break;
case MAV_CMD_DO_REPEAT_SERVO:
if (sub.ServoRelayEvents.do_repeat_servo(packet.param1, packet.param2, packet.param3, packet.param4*1000)) {
result = MAV_RESULT_ACCEPTED;
}
break;
case MAV_CMD_DO_SET_RELAY:
if (sub.ServoRelayEvents.do_set_relay(packet.param1, packet.param2)) {
result = MAV_RESULT_ACCEPTED;
}
break;
case MAV_CMD_DO_REPEAT_RELAY:
if (sub.ServoRelayEvents.do_repeat_relay(packet.param1, packet.param2, packet.param3*1000)) {
result = MAV_RESULT_ACCEPTED;
}
break;
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN: case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) { if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) {
// Send an invalid signal to the motors to prevent spinning due to neutral (1500) pwm pulse being cut short // Send an invalid signal to the motors to prevent spinning due to neutral (1500) pwm pulse being cut short
@ -1753,6 +1729,11 @@ AP_Mission *GCS_MAVLINK_Sub::get_mission()
return &sub.mission; return &sub.mission;
} }
AP_ServoRelayEvents *GCS_MAVLINK_Sub::get_servorelayevents() const
{
return &sub.ServoRelayEvents;
}
AP_Rally *GCS_MAVLINK_Sub::get_rally() const AP_Rally *GCS_MAVLINK_Sub::get_rally() const
{ {
#if AC_RALLY == ENABLED #if AC_RALLY == ENABLED

View File

@ -16,6 +16,7 @@ protected:
AP_Mission *get_mission() override; AP_Mission *get_mission() override;
AP_Rally *get_rally() const override; AP_Rally *get_rally() const override;
AP_ServoRelayEvents *get_servorelayevents() const override;
uint8_t sysid_my_gcs() const override; uint8_t sysid_my_gcs() const override;