mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
mavlink_receiver: limit access through instances with gimbal mode
This adds explicit handling for the few things we want to allow through a MAVLink instance dedicated to a gimbal/(camera) payload as per the MAVLink gimbal mode configuration.
This commit is contained in:
parent
3f17f15505
commit
fdfe43471e
@ -406,6 +406,34 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
|
||||
_mavlink.handle_message(msg);
|
||||
}
|
||||
|
||||
void MavlinkReceiver::handle_messages_in_gimbal_mode(mavlink_message_t &msg)
|
||||
{
|
||||
switch (msg.msgid) {
|
||||
case MAVLINK_MSG_ID_HEARTBEAT:
|
||||
handle_message_heartbeat(&msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE:
|
||||
handle_message_gimbal_manager_set_attitude(&msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL:
|
||||
handle_message_gimbal_manager_set_manual_control(&msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION:
|
||||
handle_message_gimbal_device_information(&msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS:
|
||||
handle_message_gimbal_device_attitude_status(&msg);
|
||||
break;
|
||||
}
|
||||
|
||||
// Message forwarding
|
||||
_mavlink.handle_message(&msg);
|
||||
}
|
||||
|
||||
bool
|
||||
MavlinkReceiver::evaluate_target_ok(int command, int target_system, int target_component)
|
||||
{
|
||||
@ -3176,7 +3204,16 @@ MavlinkReceiver::run()
|
||||
_mavlink.set_proto_version(2);
|
||||
}
|
||||
|
||||
handle_message(&msg);
|
||||
switch (_mavlink.get_mode()) {
|
||||
case Mavlink::MAVLINK_MODE::MAVLINK_MODE_GIMBAL:
|
||||
handle_messages_in_gimbal_mode(msg);
|
||||
break;
|
||||
|
||||
default:
|
||||
handle_message(&msg);
|
||||
break;
|
||||
}
|
||||
|
||||
_mavlink.set_has_received_messages(true); // Received first message, unlock wait to transmit '-w' command-line flag
|
||||
update_rx_stats(msg);
|
||||
|
||||
|
||||
@ -155,6 +155,7 @@ private:
|
||||
float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
|
||||
|
||||
void handle_message(mavlink_message_t *msg);
|
||||
void handle_messages_in_gimbal_mode(mavlink_message_t &msg);
|
||||
|
||||
void handle_message_adsb_vehicle(mavlink_message_t *msg);
|
||||
void handle_message_att_pos_mocap(mavlink_message_t *msg);
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user