// send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message 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); } // block heartbeat from transmitting to the GCS GCS_MAVLINK::disable_channel_routing(chan); }
// send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message void AP_Mount_Alexmos::send_mount_status(mavlink_channel_t chan) { if (!_initialised) { return; } get_angles(); mavlink_msg_mount_status_send(chan, 0, 0, _current_angle.y*100, _current_angle.x*100, _current_angle.z*100); }
// status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message void BP_Mount_Component::status_msg(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); float pitch_deg, roll_deg, yaw_deg; get_target_angles_deg(&pitch_deg, &roll_deg, &yaw_deg); // MAVLink MOUNT_STATUS: int32_t pitch(deg*100), int32_t roll(deg*100), int32_t yaw(deg*100) mavlink_msg_mount_status_send(chan, 0, 0, pitch_deg*100.0f, roll_deg*100.0f, yaw_deg*100.0f); }
// status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message void AP_Mount_SToRM32::status_msg(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); }
// status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message void AP_Mount_MAVLink::status_msg(mavlink_channel_t chan) { Vector3f est = _gimbal.getGimbalEstimateEF(); mavlink_msg_mount_status_send(chan, 0, 0, degrees(est.y)*100, degrees(est.x)*100, degrees(est.z)*100); }
// status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message void AP_Mount_SToRM32_serial::status_msg(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); }
// status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message void AP_Mount_Servo::status_msg(mavlink_channel_t chan) { mavlink_msg_mount_status_send(chan, 0, 0, _angle_bf_output_deg.x*100, _angle_bf_output_deg.y*100, _angle_bf_output_deg.z*100); }