mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mount: add build options for deprecated messages MOUNT_CONTROL/MOUNT_CONFIGURE
these are repalced by the command equivalents
This commit is contained in:
parent
9e330b2f09
commit
02d0a07083
@ -548,6 +548,7 @@ void AP_Mount::handle_global_position_int(const mavlink_message_t &msg)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED
|
||||||
/// Change the configuration of the mount
|
/// Change the configuration of the mount
|
||||||
void AP_Mount::handle_mount_configure(const mavlink_message_t &msg)
|
void AP_Mount::handle_mount_configure(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
@ -562,7 +563,9 @@ void AP_Mount::handle_mount_configure(const mavlink_message_t &msg)
|
|||||||
// send message to backend
|
// send message to backend
|
||||||
backend->handle_mount_configure(packet);
|
backend->handle_mount_configure(packet);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED
|
||||||
/// Control the mount (depends on the previously set mount configuration)
|
/// Control the mount (depends on the previously set mount configuration)
|
||||||
void AP_Mount::handle_mount_control(const mavlink_message_t &msg)
|
void AP_Mount::handle_mount_control(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
@ -577,6 +580,7 @@ void AP_Mount::handle_mount_control(const mavlink_message_t &msg)
|
|||||||
// send message to backend
|
// send message to backend
|
||||||
backend->handle_mount_control(packet);
|
backend->handle_mount_control(packet);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS
|
// send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS
|
||||||
void AP_Mount::send_gimbal_device_attitude_status(mavlink_channel_t chan)
|
void AP_Mount::send_gimbal_device_attitude_status(mavlink_channel_t chan)
|
||||||
@ -879,12 +883,16 @@ void AP_Mount::handle_message(mavlink_channel_t chan, const mavlink_message_t &m
|
|||||||
case MAVLINK_MSG_ID_GIMBAL_REPORT:
|
case MAVLINK_MSG_ID_GIMBAL_REPORT:
|
||||||
handle_gimbal_report(chan, msg);
|
handle_gimbal_report(chan, msg);
|
||||||
break;
|
break;
|
||||||
|
#if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED
|
||||||
case MAVLINK_MSG_ID_MOUNT_CONFIGURE:
|
case MAVLINK_MSG_ID_MOUNT_CONFIGURE:
|
||||||
handle_mount_configure(msg);
|
handle_mount_configure(msg);
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
|
#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED
|
||||||
case MAVLINK_MSG_ID_MOUNT_CONTROL:
|
case MAVLINK_MSG_ID_MOUNT_CONTROL:
|
||||||
handle_mount_control(msg);
|
handle_mount_control(msg);
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
|
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
|
||||||
handle_global_position_int(msg);
|
handle_global_position_int(msg);
|
||||||
break;
|
break;
|
||||||
|
@ -23,6 +23,7 @@
|
|||||||
|
|
||||||
#if HAL_MOUNT_ENABLED
|
#if HAL_MOUNT_ENABLED
|
||||||
|
|
||||||
|
#include <GCS_MAVLink/GCS_config.h>
|
||||||
#include <AP_HAL/AP_HAL_Boards.h>
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
@ -281,8 +282,12 @@ private:
|
|||||||
AP_Mount_Backend *get_instance(uint8_t instance) const;
|
AP_Mount_Backend *get_instance(uint8_t instance) const;
|
||||||
|
|
||||||
void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg);
|
void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg);
|
||||||
|
#if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED
|
||||||
void handle_mount_configure(const mavlink_message_t &msg);
|
void handle_mount_configure(const mavlink_message_t &msg);
|
||||||
|
#endif
|
||||||
|
#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED
|
||||||
void handle_mount_control(const mavlink_message_t &msg);
|
void handle_mount_control(const mavlink_message_t &msg);
|
||||||
|
#endif
|
||||||
|
|
||||||
MAV_RESULT handle_command_do_mount_configure(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_command_do_mount_configure(const mavlink_command_int_t &packet);
|
||||||
MAV_RESULT handle_command_do_mount_control(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_command_do_mount_control(const mavlink_command_int_t &packet);
|
||||||
|
@ -108,11 +108,13 @@ void AP_Mount_Backend::set_target_sysid(uint8_t sysid)
|
|||||||
set_mode(MAV_MOUNT_MODE_SYSID_TARGET);
|
set_mode(MAV_MOUNT_MODE_SYSID_TARGET);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED
|
||||||
// process MOUNT_CONFIGURE messages received from GCS. deprecated.
|
// process MOUNT_CONFIGURE messages received from GCS. deprecated.
|
||||||
void AP_Mount_Backend::handle_mount_configure(const mavlink_mount_configure_t &packet)
|
void AP_Mount_Backend::handle_mount_configure(const mavlink_mount_configure_t &packet)
|
||||||
{
|
{
|
||||||
set_mode((MAV_MOUNT_MODE)packet.mount_mode);
|
set_mode((MAV_MOUNT_MODE)packet.mount_mode);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS
|
// send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS
|
||||||
void AP_Mount_Backend::send_gimbal_device_attitude_status(mavlink_channel_t chan)
|
void AP_Mount_Backend::send_gimbal_device_attitude_status(mavlink_channel_t chan)
|
||||||
@ -212,6 +214,7 @@ void AP_Mount_Backend::send_gimbal_manager_status(mavlink_channel_t chan)
|
|||||||
0); // secondary control component id
|
0); // secondary control component id
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED
|
||||||
// process MOUNT_CONTROL messages received from GCS. deprecated.
|
// process MOUNT_CONTROL messages received from GCS. deprecated.
|
||||||
void AP_Mount_Backend::handle_mount_control(const mavlink_mount_control_t &packet)
|
void AP_Mount_Backend::handle_mount_control(const mavlink_mount_control_t &packet)
|
||||||
{
|
{
|
||||||
@ -247,6 +250,7 @@ void AP_Mount_Backend::handle_mount_control(const mavlink_mount_control_t &packe
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// handle do_mount_control command. Returns MAV_RESULT_ACCEPTED on success
|
// handle do_mount_control command. Returns MAV_RESULT_ACCEPTED on success
|
||||||
MAV_RESULT AP_Mount_Backend::handle_command_do_mount_control(const mavlink_command_int_t &packet)
|
MAV_RESULT AP_Mount_Backend::handle_command_do_mount_control(const mavlink_command_int_t &packet)
|
||||||
|
@ -99,12 +99,16 @@ public:
|
|||||||
// handle do_gimbal_manager_configure. Returns MAV_RESULT_ACCEPTED on success
|
// handle do_gimbal_manager_configure. Returns MAV_RESULT_ACCEPTED on success
|
||||||
// requires original message in order to extract caller's sysid and compid
|
// requires original message in order to extract caller's sysid and compid
|
||||||
MAV_RESULT handle_command_do_gimbal_manager_configure(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
|
MAV_RESULT handle_command_do_gimbal_manager_configure(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
|
||||||
|
|
||||||
|
#if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED
|
||||||
// process MOUNT_CONFIGURE messages received from GCS. deprecated.
|
// process MOUNT_CONFIGURE messages received from GCS. deprecated.
|
||||||
void handle_mount_configure(const mavlink_mount_configure_t &msg);
|
void handle_mount_configure(const mavlink_mount_configure_t &msg);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED
|
||||||
// process MOUNT_CONTROL messages received from GCS. deprecated.
|
// process MOUNT_CONTROL messages received from GCS. deprecated.
|
||||||
void handle_mount_control(const mavlink_mount_control_t &packet);
|
void handle_mount_control(const mavlink_mount_control_t &packet);
|
||||||
|
#endif
|
||||||
|
|
||||||
// send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS
|
// send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS
|
||||||
void send_gimbal_device_attitude_status(mavlink_channel_t chan);
|
void send_gimbal_device_attitude_status(mavlink_channel_t chan);
|
||||||
|
Loading…
Reference in New Issue
Block a user