mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-04 12:43:58 -04:00
Rover: move handling of RC_CHANNELS_OVERRIDE up
This commit is contained in:
parent
ae68b58678
commit
76fe58a3bd
@ -747,38 +747,19 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
|
||||||
|
void GCS_MAVLINK_Rover::handle_rc_channels_override(const mavlink_message_t *msg)
|
||||||
|
{
|
||||||
|
rover.failsafe.last_heartbeat_ms = AP_HAL::millis();
|
||||||
|
GCS_MAVLINK::handle_rc_channels_override(msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
||||||
{
|
{
|
||||||
switch (msg->msgid) {
|
switch (msg->msgid) {
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
|
|
||||||
{
|
|
||||||
// allow override of RC channel values for HIL
|
|
||||||
// or for complete GCS control of switch position
|
|
||||||
// and RC PWM values.
|
|
||||||
if (msg->sysid != rover.g.sysid_my_gcs) { // Only accept control from our gcs
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t tnow = AP_HAL::millis();
|
|
||||||
|
|
||||||
mavlink_rc_channels_override_t packet;
|
|
||||||
mavlink_msg_rc_channels_override_decode(msg, &packet);
|
|
||||||
|
|
||||||
RC_Channels::set_override(0, packet.chan1_raw, tnow);
|
|
||||||
RC_Channels::set_override(1, packet.chan2_raw, tnow);
|
|
||||||
RC_Channels::set_override(2, packet.chan3_raw, tnow);
|
|
||||||
RC_Channels::set_override(3, packet.chan4_raw, tnow);
|
|
||||||
RC_Channels::set_override(4, packet.chan5_raw, tnow);
|
|
||||||
RC_Channels::set_override(5, packet.chan6_raw, tnow);
|
|
||||||
RC_Channels::set_override(6, packet.chan7_raw, tnow);
|
|
||||||
RC_Channels::set_override(7, packet.chan8_raw, tnow);
|
|
||||||
|
|
||||||
// an RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
|
|
||||||
rover.failsafe.last_heartbeat_ms = tnow;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_MANUAL_CONTROL:
|
case MAVLINK_MSG_ID_MANUAL_CONTROL:
|
||||||
{
|
{
|
||||||
|
@ -38,6 +38,7 @@ private:
|
|||||||
void handleMessage(mavlink_message_t * msg) override;
|
void handleMessage(mavlink_message_t * msg) override;
|
||||||
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
|
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
|
||||||
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
|
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
|
||||||
|
void handle_rc_channels_override(const mavlink_message_t *msg) override;
|
||||||
bool try_send_message(enum ap_message id) override;
|
bool try_send_message(enum ap_message id) override;
|
||||||
|
|
||||||
void packetReceived(const mavlink_status_t &status, mavlink_message_t &msg) override;
|
void packetReceived(const mavlink_status_t &status, mavlink_message_t &msg) override;
|
||||||
|
Loading…
Reference in New Issue
Block a user