mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
GCS_MAVLink: factor out handle_manual_control_axes
This commit is contained in:
parent
644c7c316d
commit
3bd62c0e68
@ -590,6 +590,8 @@ protected:
|
||||
|
||||
MAV_RESULT handle_fixed_mag_cal_yaw(const mavlink_command_long_t &packet);
|
||||
|
||||
void handle_manual_control(const mavlink_message_t &msg);
|
||||
|
||||
// default empty handling of LANDING_TARGET
|
||||
virtual void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) { }
|
||||
// vehicle-overridable message send function
|
||||
@ -911,6 +913,8 @@ private:
|
||||
virtual void handle_change_alt_request(AP_Mission::Mission_Command &cmd) {};
|
||||
void handle_common_mission_message(const mavlink_message_t &msg);
|
||||
|
||||
virtual void handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow) {};
|
||||
|
||||
void handle_vicon_position_estimate(const mavlink_message_t &msg);
|
||||
void handle_vision_position_estimate(const mavlink_message_t &msg);
|
||||
void handle_global_vision_position_estimate(const mavlink_message_t &msg);
|
||||
@ -1139,10 +1143,10 @@ public:
|
||||
void enable_high_latency_connections(bool enabled);
|
||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
|
||||
protected:
|
||||
|
||||
virtual uint8_t sysid_this_mav() const = 0;
|
||||
|
||||
protected:
|
||||
|
||||
virtual GCS_MAVLINK *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
||||
AP_HAL::UARTDriver &uart) = 0;
|
||||
|
||||
|
@ -3803,6 +3803,10 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MAVLINK_MSG_ID_MANUAL_CONTROL:
|
||||
handle_manual_control(msg);
|
||||
break;
|
||||
|
||||
#if AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED
|
||||
case MAVLINK_MSG_ID_PLAY_TUNE:
|
||||
// send message to Notify
|
||||
@ -6299,6 +6303,29 @@ void GCS_MAVLINK::manual_override(RC_Channel *c, int16_t value_in, const uint16_
|
||||
c->set_override(override_value, tnow);
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::handle_manual_control(const mavlink_message_t &msg)
|
||||
{
|
||||
if (msg.sysid != sysid_my_gcs()) {
|
||||
return; // only accept control from our gcs
|
||||
}
|
||||
|
||||
mavlink_manual_control_t packet;
|
||||
mavlink_msg_manual_control_decode(&msg, &packet);
|
||||
|
||||
if (packet.target != gcs().sysid_this_mav()) {
|
||||
return; // only accept control aimed at us
|
||||
}
|
||||
|
||||
uint32_t tnow = AP_HAL::millis();
|
||||
|
||||
handle_manual_control_axes(packet, tnow);
|
||||
|
||||
// a manual control message is considered to be a 'heartbeat'
|
||||
// from the ground station for failsafe purposes
|
||||
gcs().sysid_myggcs_seen(tnow);
|
||||
}
|
||||
|
||||
|
||||
uint8_t GCS_MAVLINK::receiver_rssi() const
|
||||
{
|
||||
AP_RSSI *aprssi = AP::rssi();
|
||||
|
Loading…
Reference in New Issue
Block a user