mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
AntennaTracker: Added supportfor manual control message to force antenna bearing and pitch in manual mode
This commit is contained in:
parent
61ebf365d9
commit
25c46cdc00
@ -813,11 +813,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
set_home(tell_command); // New home in EEPROM
|
||||
send_text_P(SEVERITY_LOW,PSTR("new HOME received"));
|
||||
waypoint_receiving = false;
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
mission_failed:
|
||||
// we are rejecting the mission/waypoint
|
||||
mavlink_msg_mission_ack_send(
|
||||
@ -828,6 +825,14 @@ mission_failed:
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_MANUAL_CONTROL:
|
||||
{
|
||||
if(msg->sysid != g.sysid_my_gcs) break; // Only accept control from our gcs
|
||||
mavlink_manual_control_t packet;
|
||||
mavlink_msg_manual_control_decode(msg, &packet);
|
||||
tracking_manual_control(packet);
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
|
||||
{
|
||||
|
@ -273,3 +273,14 @@ static void tracking_update_pressure(const mavlink_scaled_pressure_t &msg)
|
||||
nav_status.altitude_difference = alt_diff;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
handle a manual control message by using the data to command yaw and pitch
|
||||
*/
|
||||
static void tracking_manual_control(const mavlink_manual_control_t &msg)
|
||||
{
|
||||
nav_status.bearing = msg.x;
|
||||
nav_status.pitch = msg.y;
|
||||
nav_status.distance = 0.0;
|
||||
// z, r and buttons are not used
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user