AP_Mount: remove MOUNT_CONFIGURE and MOUNT_CONTROL support

This commit is contained in:
Peter Barker 2025-01-02 19:17:16 +11:00 committed by Peter Barker
parent bdacfdc76d
commit 786df975f0
4 changed files with 0 additions and 106 deletions

View File

@ -584,40 +584,6 @@ 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
void AP_Mount::handle_mount_configure(const mavlink_message_t &msg)
{
auto *backend = get_primary();
if (backend == nullptr) {
return;
}
mavlink_mount_configure_t packet;
mavlink_msg_mount_configure_decode(&msg, &packet);
// send message to backend
backend->handle_mount_configure(packet);
}
#endif
#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED
/// Control the mount (depends on the previously set mount configuration)
void AP_Mount::handle_mount_control(const mavlink_message_t &msg)
{
auto *backend = get_primary();
if (backend == nullptr) {
return;
}
mavlink_mount_control_t packet;
mavlink_msg_mount_control_decode(&msg, &packet);
// send message to backend
backend->handle_mount_control(packet);
}
#endif
#if HAL_GCS_ENABLED
// send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS
void AP_Mount::send_gimbal_device_attitude_status(mavlink_channel_t chan)
@ -998,16 +964,6 @@ void AP_Mount::handle_message(mavlink_channel_t chan, const mavlink_message_t &m
case MAVLINK_MSG_ID_GIMBAL_REPORT:
handle_gimbal_report(chan, msg);
break;
#if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED
case MAVLINK_MSG_ID_MOUNT_CONFIGURE:
handle_mount_configure(msg);
break;
#endif
#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED
case MAVLINK_MSG_ID_MOUNT_CONTROL:
handle_mount_control(msg);
break;
#endif
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
handle_global_position_int(msg);
break;

View File

@ -321,12 +321,6 @@ private:
AP_Mount_Backend *get_instance(uint8_t instance) const;
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);
#endif
#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED
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_control(const mavlink_command_int_t &packet);

View File

@ -189,14 +189,6 @@ void AP_Mount_Backend::set_target_sysid(uint8_t sysid)
}
}
#if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED
// process MOUNT_CONFIGURE messages received from GCS. deprecated.
void AP_Mount_Backend::handle_mount_configure(const mavlink_mount_configure_t &packet)
{
set_mode((MAV_MOUNT_MODE)packet.mount_mode);
}
#endif
#if HAL_GCS_ENABLED
// send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS
void AP_Mount_Backend::send_gimbal_device_attitude_status(mavlink_channel_t chan)
@ -299,44 +291,6 @@ void AP_Mount_Backend::send_gimbal_manager_status(mavlink_channel_t chan)
0); // secondary control component id
}
#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED
// process MOUNT_CONTROL messages received from GCS. deprecated.
void AP_Mount_Backend::handle_mount_control(const mavlink_mount_control_t &packet)
{
switch (get_mode()) {
case MAV_MOUNT_MODE_MAVLINK_TARGETING:
// input_a : Pitch in centi-degrees (earth-frame)
// input_b : Roll in centi-degrees (earth-frame)
// input_c : Yaw in centi-degrees (interpreted as body-frame)
set_angle_target(packet.input_b * 0.01, packet.input_a * 0.01, packet.input_c * 0.01, false);
break;
case MAV_MOUNT_MODE_GPS_POINT: {
// input_a : lat in degE7
// input_b : lon in degE7
// input_c : alt in cm (interpreted as above home)
const Location target_location {
packet.input_a,
packet.input_b,
packet.input_c,
Location::AltFrame::ABOVE_HOME
};
set_roi_target(target_location);
break;
}
case MAV_MOUNT_MODE_RETRACT:
case MAV_MOUNT_MODE_NEUTRAL:
case MAV_MOUNT_MODE_RC_TARGETING:
case MAV_MOUNT_MODE_SYSID_TARGET:
case MAV_MOUNT_MODE_HOME_LOCATION:
default:
// no effect in these modes
break;
}
}
#endif
// 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)
{

View File

@ -107,16 +107,6 @@ public:
// 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);
#if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED
// process MOUNT_CONFIGURE messages received from GCS. deprecated.
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.
void handle_mount_control(const mavlink_mount_control_t &packet);
#endif
// send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS
void send_gimbal_device_attitude_status(mavlink_channel_t chan);