mirror of https://github.com/ArduPilot/ardupilot
Rover: factor out handle_manual_control_axes
This commit is contained in:
parent
447392c7f4
commit
38ea1b4039
|
@ -769,9 +769,6 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_do_reposition(const mavlink_com
|
|||
void GCS_MAVLINK_Rover::handleMessage(const mavlink_message_t &msg)
|
||||
{
|
||||
switch (msg.msgid) {
|
||||
case MAVLINK_MSG_ID_MANUAL_CONTROL:
|
||||
handle_manual_control(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
|
||||
handle_set_attitude_target(msg);
|
||||
|
@ -796,27 +793,10 @@ void GCS_MAVLINK_Rover::handleMessage(const mavlink_message_t &msg)
|
|||
}
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Rover::handle_manual_control(const mavlink_message_t &msg)
|
||||
void GCS_MAVLINK_Rover::handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow)
|
||||
{
|
||||
if (msg.sysid != rover.g.sysid_my_gcs) { // Only accept control from our gcs
|
||||
return;
|
||||
}
|
||||
|
||||
mavlink_manual_control_t packet;
|
||||
mavlink_msg_manual_control_decode(&msg, &packet);
|
||||
|
||||
if (packet.target != rover.g.sysid_this_mav) {
|
||||
return; // only accept control aimed at us
|
||||
}
|
||||
|
||||
uint32_t tnow = AP_HAL::millis();
|
||||
|
||||
manual_override(rover.channel_steer, packet.y, 1000, 2000, tnow);
|
||||
manual_override(rover.channel_throttle, packet.z, 1000, 2000, tnow);
|
||||
|
||||
// a manual control message is considered to be a 'heartbeat' from
|
||||
// the ground station for failsafe purposes
|
||||
gcs().sysid_myggcs_seen(tnow);
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Rover::handle_set_attitude_target(const mavlink_message_t &msg)
|
||||
|
|
|
@ -37,7 +37,7 @@ private:
|
|||
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
|
||||
bool try_send_message(enum ap_message id) override;
|
||||
|
||||
void handle_manual_control(const mavlink_message_t &msg);
|
||||
void handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow) override;
|
||||
void handle_set_attitude_target(const mavlink_message_t &msg);
|
||||
void handle_set_position_target_local_ned(const mavlink_message_t &msg);
|
||||
void handle_set_position_target_global_int(const mavlink_message_t &msg);
|
||||
|
|
Loading…
Reference in New Issue