AP_Mount: add handle_global_position_int() method to backend and use it + little spelling

This commit is contained in:
olliw42 2021-08-25 08:04:18 +02:00 committed by Peter Barker
parent 8550765c25
commit 312604f577
3 changed files with 25 additions and 16 deletions

View File

@ -618,19 +618,9 @@ void AP_Mount::handle_global_position_int(const mavlink_message_t &msg)
}
for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
if (_backends[instance] == nullptr) {
continue;
if (_backends[instance] != nullptr) {
_backends[instance]->handle_global_position_int(msg.sysid, packet);
}
struct mount_state &_state = state[instance];
if (_state._target_sysid != msg.sysid) {
continue;
}
_state._target_sysid_location.lat = packet.lat;
_state._target_sysid_location.lng = packet.lon;
// global_position_int.alt is *UP*, so is location.
_state._target_sysid_location.set_alt_cm(packet.alt*0.1,
Location::AltFrame::ABSOLUTE);
_state._target_sysid_location_set = true;
}
}
@ -665,7 +655,7 @@ void AP_Mount::handle_mount_control(const mavlink_message_t &msg)
/// Return mount status information
void AP_Mount::send_mount_status(mavlink_channel_t chan)
{
// call send_mount_status for each instance
// call send_mount_status for each instance
for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
if (_backends[instance] != nullptr) {
_backends[instance]->send_mount_status(chan);

View File

@ -36,7 +36,7 @@ void AP_Mount_Backend::set_target_sysid(uint8_t sysid)
_frontend.set_mode(_instance, MAV_MOUNT_MODE_SYSID_TARGET);
}
// 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)
{
set_mode((MAV_MOUNT_MODE)packet.mount_mode);
@ -98,6 +98,22 @@ void AP_Mount_Backend::control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_
}
}
// handle a GLOBAL_POSITION_INT message
bool AP_Mount_Backend::handle_global_position_int(uint8_t msg_sysid, const mavlink_global_position_int_t &packet)
{
if (_state._target_sysid != msg_sysid) {
return false;
}
_state._target_sysid_location.lat = packet.lat;
_state._target_sysid_location.lng = packet.lon;
// global_position_int.alt is *UP*, so is location.
_state._target_sysid_location.set_alt_cm(packet.alt*0.1, Location::AltFrame::ABSOLUTE);
_state._target_sysid_location_set = true;
return true;
}
void AP_Mount_Backend::rate_input_rad(float &out, const RC_Channel *chan, float min, float max) const
{
if ((chan == nullptr) || (chan->get_radio_in() == 0)) {

View File

@ -64,10 +64,10 @@ public:
// control - control the mount
virtual void control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, MAV_MOUNT_MODE mount_mode);
// process MOUNT_CONFIGURE messages received from GCS:
// process MOUNT_CONFIGURE messages received from GCS. deprecated.
void handle_mount_configure(const mavlink_mount_configure_t &msg);
// process MOUNT_CONTROL messages received from GCS:
// process MOUNT_CONTROL messages received from GCS. deprecated.
void handle_mount_control(const mavlink_mount_control_t &packet);
// send_mount_status - called to allow mounts to send their status to GCS via MAVLink
@ -82,6 +82,9 @@ public:
// send a GIMBAL_REPORT message to the GCS
virtual void send_gimbal_report(const mavlink_channel_t chan) {}
// handle a GLOBAL_POSITION_INT message
bool handle_global_position_int(uint8_t msg_sysid, const mavlink_global_position_int_t &packet);
protected:
// update_targets_from_rc - updates angle targets (i.e. _angle_ef_target_rad) using input from receiver