mirror of https://github.com/ArduPilot/ardupilot
Copter: move mavlink support for servo/relay up
This commit is contained in:
parent
318861e824
commit
b14964eb1e
|
@ -1259,30 +1259,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||
}
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_SERVO:
|
||||
if (copter.ServoRelayEvents.do_set_servo(packet.param1, packet.param2)) {
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_REPEAT_SERVO:
|
||||
if (copter.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 (copter.ServoRelayEvents.do_set_relay(packet.param1, packet.param2)) {
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_REPEAT_RELAY:
|
||||
if (copter.ServoRelayEvents.do_repeat_relay(packet.param1, packet.param2, packet.param3*1000)) {
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
break;
|
||||
|
||||
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
||||
if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) {
|
||||
AP_Notify::flags.firmware_update = 1;
|
||||
|
@ -1976,6 +1952,11 @@ AP_Mission *GCS_MAVLINK_Copter::get_mission()
|
|||
return &copter.mission;
|
||||
}
|
||||
|
||||
AP_ServoRelayEvents *GCS_MAVLINK_Copter::get_servorelayevents() const
|
||||
{
|
||||
return &copter.ServoRelayEvents;
|
||||
}
|
||||
|
||||
AP_Rally *GCS_MAVLINK_Copter::get_rally() const
|
||||
{
|
||||
#if AC_RALLY == ENABLED
|
||||
|
|
|
@ -20,6 +20,7 @@ protected:
|
|||
|
||||
AP_Mission *get_mission() override;
|
||||
AP_Rally *get_rally() const override;
|
||||
AP_ServoRelayEvents *get_servorelayevents() const override;
|
||||
|
||||
uint8_t sysid_my_gcs() const override;
|
||||
|
||||
|
|
Loading…
Reference in New Issue