AP_Mount: add mount mode to MOUNT_STATUS

This commit is contained in:
Joshua Henderson 2022-01-05 16:50:53 -05:00 committed by Andrew Tridgell
parent 1948073438
commit dd8daa05fc
5 changed files with 5 additions and 5 deletions

View File

@ -104,7 +104,7 @@ void AP_Mount_Alexmos::send_mount_status(mavlink_channel_t chan)
}
get_angles();
mavlink_msg_mount_status_send(chan, 0, 0, _current_angle.y*100, _current_angle.x*100, _current_angle.z*100);
mavlink_msg_mount_status_send(chan, 0, 0, _current_angle.y*100, _current_angle.x*100, _current_angle.z*100, _state._mode);
}
/*

View File

@ -116,7 +116,7 @@ void AP_Mount_SToRM32::set_mode(enum MAV_MOUNT_MODE mode)
void AP_Mount_SToRM32::send_mount_status(mavlink_channel_t chan)
{
// return target angles as gimbal's actual attitude. To-Do: retrieve actual gimbal attitude and send these instead
mavlink_msg_mount_status_send(chan, 0, 0, ToDeg(_angle_ef_target_rad.y)*100, ToDeg(_angle_ef_target_rad.x)*100, ToDeg(_angle_ef_target_rad.z)*100);
mavlink_msg_mount_status_send(chan, 0, 0, ToDeg(_angle_ef_target_rad.y)*100, ToDeg(_angle_ef_target_rad.x)*100, ToDeg(_angle_ef_target_rad.z)*100, _state._mode);
}
// search for gimbal in GCS_MAVLink routing table

View File

@ -150,7 +150,7 @@ void AP_Mount_SToRM32_serial::set_mode(enum MAV_MOUNT_MODE mode)
void AP_Mount_SToRM32_serial::send_mount_status(mavlink_channel_t chan)
{
// return target angles as gimbal's actual attitude.
mavlink_msg_mount_status_send(chan, 0, 0, _current_angle.y, _current_angle.x, _current_angle.z);
mavlink_msg_mount_status_send(chan, 0, 0, _current_angle.y, _current_angle.x, _current_angle.z, _state._mode);
}
bool AP_Mount_SToRM32_serial::can_send(bool with_control) {

View File

@ -136,7 +136,7 @@ void AP_Mount_Servo::check_servo_map()
// send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
void AP_Mount_Servo::send_mount_status(mavlink_channel_t chan)
{
mavlink_msg_mount_status_send(chan, 0, 0, _angle_bf_output_deg.y*100, _angle_bf_output_deg.x*100, _angle_bf_output_deg.z*100);
mavlink_msg_mount_status_send(chan, 0, 0, _angle_bf_output_deg.y*100, _angle_bf_output_deg.x*100, _angle_bf_output_deg.z*100, _state._mode);
}
// stabilize - stabilizes the mount relative to the Earth's frame

View File

@ -116,7 +116,7 @@ void AP_Mount_SoloGimbal::set_mode(enum MAV_MOUNT_MODE mode)
void AP_Mount_SoloGimbal::send_mount_status(mavlink_channel_t chan)
{
if (_gimbal.aligned()) {
mavlink_msg_mount_status_send(chan, 0, 0, degrees(_angle_ef_target_rad.y)*100, degrees(_angle_ef_target_rad.x)*100, degrees(_angle_ef_target_rad.z)*100);
mavlink_msg_mount_status_send(chan, 0, 0, degrees(_angle_ef_target_rad.y)*100, degrees(_angle_ef_target_rad.x)*100, degrees(_angle_ef_target_rad.z)*100, _state._mode);
}
// block heartbeat from transmitting to the GCS