2012-06-13 15:55:19 -03:00
/************************************************************
* AP_mount - - library to control a 2 or 3 axis mount . *
* *
* Author : Joe Holdsworth ; *
* Ritchie Wilson ; *
* Amilcar Lucas ; *
* Gregory Fletcher ; *
2015-01-08 16:10:48 -04:00
* heavily modified by Randy Mackay *
2012-06-13 15:55:19 -03:00
* *
* Purpose : Move a 2 or 3 axis mount attached to vehicle , *
* Used for mount to track targets or stabilise *
* camera plus other modes . *
* *
* Usage : Use in main code to control mounts attached to *
* vehicle . *
* *
2022-08-30 08:15:10 -03:00
* Comments : All angles in degrees , distances in meters *
2012-06-13 15:55:19 -03:00
* unless otherwise stated . *
2012-08-17 03:20:30 -03:00
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
2016-02-17 21:25:38 -04:00
# pragma once
2012-06-13 15:55:19 -03:00
2023-03-05 18:42:54 -04:00
# include "AP_Mount_config.h"
2020-07-24 14:01:21 -03:00
# if HAL_MOUNT_ENABLED
2023-08-23 21:10:29 -03:00
# include <GCS_MAVLink/GCS_config.h>
2023-06-20 02:44:43 -03:00
# include <AP_HAL/AP_HAL_Boards.h>
2015-08-11 03:28:44 -03:00
# include <AP_Math/AP_Math.h>
# include <AP_Common/AP_Common.h>
2019-04-04 07:50:00 -03:00
# include <AP_Common/Location.h>
2015-08-11 03:28:44 -03:00
# include <GCS_MAVLink/GCS_MAVLink.h>
2023-04-18 22:06:46 -03:00
# include <AP_Camera/AP_Camera_shareddefs.h>
2022-08-30 08:15:10 -03:00
# include "AP_Mount_Params.h"
2012-06-13 15:55:19 -03:00
2015-01-08 16:10:48 -04:00
// maximum number of mounts
2022-09-02 02:32:29 -03:00
# define AP_MOUNT_MAX_INSTANCES 2
2015-01-08 16:10:48 -04:00
// declare backend classes
class AP_Mount_Backend ;
class AP_Mount_Servo ;
2015-12-30 22:19:52 -04:00
class AP_Mount_SoloGimbal ;
2015-01-15 18:47:59 -04:00
class AP_Mount_Alexmos ;
2015-02-14 08:27:58 -04:00
class AP_Mount_SToRM32 ;
2015-05-26 04:21:12 -03:00
class AP_Mount_SToRM32_serial ;
2022-05-26 23:57:55 -03:00
class AP_Mount_Gremsy ;
2022-09-15 23:31:09 -03:00
class AP_Mount_Siyi ;
2022-12-27 21:21:46 -04:00
class AP_Mount_Scripting ;
2023-06-20 02:44:43 -03:00
class AP_Mount_Xacti ;
2023-07-05 02:35:39 -03:00
class AP_Mount_Viewpro ;
2015-01-08 16:10:48 -04:00
2015-01-30 02:39:31 -04:00
/*
This is a workaround to allow the MAVLink backend access to the
SmallEKF . It would be nice to find a neater solution to this
*/
2012-06-13 15:55:19 -03:00
class AP_Mount
{
2015-01-08 16:10:48 -04:00
// declare backends as friends
friend class AP_Mount_Backend ;
friend class AP_Mount_Servo ;
2015-12-30 22:19:52 -04:00
friend class AP_Mount_SoloGimbal ;
2015-01-15 18:47:59 -04:00
friend class AP_Mount_Alexmos ;
2015-02-14 08:27:58 -04:00
friend class AP_Mount_SToRM32 ;
2015-05-26 04:21:12 -03:00
friend class AP_Mount_SToRM32_serial ;
2022-05-26 23:57:55 -03:00
friend class AP_Mount_Gremsy ;
2022-09-15 23:31:09 -03:00
friend class AP_Mount_Siyi ;
2022-12-27 21:21:46 -04:00
friend class AP_Mount_Scripting ;
2023-06-20 02:44:43 -03:00
friend class AP_Mount_Xacti ;
2023-07-05 02:35:39 -03:00
friend class AP_Mount_Viewpro ;
2015-01-08 16:10:48 -04:00
2012-06-13 15:55:19 -03:00
public :
2019-03-26 08:36:36 -03:00
AP_Mount ( ) ;
2017-08-29 16:47:49 -03:00
/* Do not allow copies */
2022-09-30 06:50:43 -03:00
CLASS_NO_COPY ( AP_Mount ) ;
2017-08-29 16:47:49 -03:00
2018-07-24 20:30:23 -03:00
// get singleton instance
static AP_Mount * get_singleton ( ) {
return _singleton ;
}
2012-08-17 03:20:30 -03:00
2015-01-08 16:10:48 -04:00
// Enums
2023-05-24 04:07:42 -03:00
enum class Type {
None = 0 , /// no mount
2023-05-26 00:16:55 -03:00
# if HAL_MOUNT_SERVO_ENABLED
2023-05-24 04:07:42 -03:00
Servo = 1 , /// servo controlled mount
2023-05-26 00:16:55 -03:00
# endif
# if HAL_SOLO_GIMBAL_ENABLED
2023-05-24 04:07:42 -03:00
SoloGimbal = 2 , /// Solo's gimbal
2023-05-26 00:16:55 -03:00
# endif
# if HAL_MOUNT_ALEXMOS_ENABLED
2023-05-24 04:07:42 -03:00
Alexmos = 3 , /// Alexmos mount
2023-05-26 00:16:55 -03:00
# endif
# if HAL_MOUNT_STORM32MAVLINK_ENABLED
2023-05-24 04:07:42 -03:00
SToRM32 = 4 , /// SToRM32 mount using MAVLink protocol
2023-05-26 00:16:55 -03:00
# endif
# if HAL_MOUNT_STORM32SERIAL_ENABLED
2023-05-24 04:07:42 -03:00
SToRM32_serial = 5 , /// SToRM32 mount using custom serial protocol
2023-05-26 00:16:55 -03:00
# endif
# if HAL_MOUNT_GREMSY_ENABLED
2023-05-24 04:07:42 -03:00
Gremsy = 6 , /// Gremsy gimbal using MAVLink v2 Gimbal protocol
2023-05-26 00:16:55 -03:00
# endif
# if HAL_MOUNT_SERVO_ENABLED
2023-05-24 04:07:42 -03:00
BrushlessPWM = 7 , /// Brushless (stabilized) gimbal using PWM protocol
2023-05-26 00:16:55 -03:00
# endif
# if HAL_MOUNT_SIYI_ENABLED
2023-05-24 04:07:42 -03:00
Siyi = 8 , /// Siyi gimbal using custom serial protocol
2023-05-26 00:16:55 -03:00
# endif
# if HAL_MOUNT_SCRIPTING_ENABLED
2023-05-24 04:07:42 -03:00
Scripting = 9 , /// Scripting gimbal driver
2023-06-20 02:44:43 -03:00
# endif
# if HAL_MOUNT_XACTI_ENABLED
Xacti = 10 , /// Xacti DroneCAN gimbal driver
2023-07-05 02:35:39 -03:00
# endif
# if HAL_MOUNT_VIEWPRO_ENABLED
Viewpro = 11 , /// Viewpro gimbal using a custom serial protocol
2023-05-26 00:16:55 -03:00
# endif
2012-08-17 03:20:30 -03:00
} ;
2015-01-08 16:10:48 -04:00
// init - detect and initialise all mounts
2019-08-27 03:23:30 -03:00
void init ( ) ;
2015-01-08 16:10:48 -04:00
// update - give mount opportunity to update servos. should be called at 10hz or higher
void update ( ) ;
2015-12-30 22:19:52 -04:00
// used for gimbals that need to read INS data at full rate
void update_fast ( ) ;
2023-03-02 00:03:02 -04:00
// return primary instance ID
uint8_t get_primary_instance ( ) const { return _primary ; }
2022-09-05 22:18:38 -03:00
2015-01-08 16:10:48 -04:00
// get_mount_type - returns the type of mount
2023-05-24 04:07:42 -03:00
Type get_mount_type ( ) const { return get_mount_type ( _primary ) ; }
Type get_mount_type ( uint8_t instance ) const ;
2015-01-08 16:10:48 -04:00
// has_pan_control - returns true if the mount has yaw control (required for copters)
bool has_pan_control ( ) const { return has_pan_control ( _primary ) ; }
bool has_pan_control ( uint8_t instance ) const ;
2014-03-05 03:01:11 -04:00
2015-01-08 16:10:48 -04:00
// get_mode - returns current mode of mount (i.e. Retracted, Neutral, RC_Targeting, GPS Point)
enum MAV_MOUNT_MODE get_mode ( ) const { return get_mode ( _primary ) ; }
enum MAV_MOUNT_MODE get_mode ( uint8_t instance ) const ;
// set_mode - sets mount's mode
2015-01-12 07:41:12 -04:00
// returns true if mode is successfully set
void set_mode ( enum MAV_MOUNT_MODE mode ) { return set_mode ( _primary , mode ) ; }
2015-01-08 16:10:48 -04:00
void set_mode ( uint8_t instance , enum MAV_MOUNT_MODE mode ) ;
2022-08-30 08:15:10 -03:00
// set_mode_to_default - restores the mode to it's default mode held in the MNTx_DEFLT_MODE parameter
2015-11-03 09:46:29 -04:00
// this operation requires 60us on a Pixhawk/PX4
2015-01-08 16:10:48 -04:00
void set_mode_to_default ( ) { set_mode_to_default ( _primary ) ; }
void set_mode_to_default ( uint8_t instance ) ;
2024-03-19 07:36:38 -03:00
// set yaw_lock used in RC_TARGETING mode. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North)
2022-06-01 01:39:32 -03:00
// If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle
void set_yaw_lock ( bool yaw_lock ) { set_yaw_lock ( _primary , yaw_lock ) ; }
void set_yaw_lock ( uint8_t instance , bool yaw_lock ) ;
2022-06-20 08:50:44 -03:00
// set angle target in degrees
// yaw_is_earth_frame (aka yaw_lock) should be true if yaw angle is earth-frame, false if body-frame
void set_angle_target ( float roll_deg , float pitch_deg , float yaw_deg , bool yaw_is_earth_frame ) { set_angle_target ( _primary , roll_deg , pitch_deg , yaw_deg , yaw_is_earth_frame ) ; }
void set_angle_target ( uint8_t instance , float roll_deg , float pitch_deg , float yaw_deg , bool yaw_is_earth_frame ) ;
// sets rate target in deg/s
// yaw_lock should be true if the yaw rate is earth-frame, false if body-frame (e.g. rotates with body of vehicle)
void set_rate_target ( float roll_degs , float pitch_degs , float yaw_degs , bool yaw_lock ) { set_rate_target ( _primary , roll_degs , pitch_degs , yaw_degs , yaw_lock ) ; }
void set_rate_target ( uint8_t instance , float roll_degs , float pitch_degs , float yaw_degs , bool yaw_lock ) ;
2015-03-21 08:58:57 -03:00
2015-01-08 16:10:48 -04:00
// set_roi_target - sets target location that mount should attempt to point towards
2022-06-20 07:59:02 -03:00
void set_roi_target ( const Location & target_loc ) { set_roi_target ( _primary , target_loc ) ; }
void set_roi_target ( uint8_t instance , const Location & target_loc ) ;
2012-06-13 15:55:19 -03:00
2023-02-15 00:52:56 -04:00
// clear_roi_target - clears target location that mount should attempt to point towards
void clear_roi_target ( ) { clear_roi_target ( _primary ) ; }
void clear_roi_target ( uint8_t instance ) ;
2019-03-16 04:06:02 -03:00
// point at system ID sysid
2022-06-20 07:59:02 -03:00
void set_target_sysid ( uint8_t sysid ) { set_target_sysid ( _primary , sysid ) ; }
void set_target_sysid ( uint8_t instance , uint8_t sysid ) ;
2019-03-16 04:06:02 -03:00
2023-08-25 17:45:03 -03:00
// handling of set_roi_sysid message
MAV_RESULT handle_command_do_set_roi_sysid ( const mavlink_command_int_t & packet ) ;
2018-10-11 06:30:03 -03:00
// mavlink message handling:
2023-08-17 04:19:03 -03:00
MAV_RESULT handle_command ( const mavlink_command_int_t & packet , const mavlink_message_t & msg ) ;
2019-04-30 07:22:48 -03:00
void handle_param_value ( const mavlink_message_t & msg ) ;
void handle_message ( mavlink_channel_t chan , const mavlink_message_t & msg ) ;
2015-01-29 05:01:55 -04:00
2022-07-11 05:07:22 -03:00
// send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS
void send_gimbal_device_attitude_status ( mavlink_channel_t chan ) ;
2015-01-08 16:10:48 -04:00
2023-04-24 01:58:58 -03:00
// send a GIMBAL_MANAGER_INFORMATION message to GCS
void send_gimbal_manager_information ( mavlink_channel_t chan ) ;
2023-05-07 20:07:14 -03:00
// send a GIMBAL_MANAGER_STATUS message to GCS
void send_gimbal_manager_status ( mavlink_channel_t chan ) ;
2023-09-20 23:36:58 -03:00
# if AP_MOUNT_POI_TO_LATLONALT_ENABLED
// get poi information. Returns true on success and fills in gimbal attitude, location and poi location
bool get_poi ( uint8_t instance , Quaternion & quat , Location & loc , Location & poi_loc ) const ;
# endif
2022-09-20 02:39:35 -03:00
// get mount's current attitude in euler angles in degrees. yaw angle is in body-frame
// returns true on success
bool get_attitude_euler ( uint8_t instance , float & roll_deg , float & pitch_deg , float & yaw_bf_deg ) ;
2022-06-16 05:13:08 -03:00
// run pre-arm check. returns false on failure and fills in failure_msg
// any failure_msg returned will not include a prefix
bool pre_arm_checks ( char * failure_msg , uint8_t failure_msg_len ) ;
2023-07-21 03:35:42 -03:00
// get target rate in deg/sec. returns true on success
2022-12-27 21:21:46 -04:00
bool get_rate_target ( uint8_t instance , float & roll_degs , float & pitch_degs , float & yaw_degs , bool & yaw_is_earth_frame ) ;
2023-07-21 03:35:42 -03:00
// get target angle in deg. returns true on success
2022-12-27 21:21:46 -04:00
bool get_angle_target ( uint8_t instance , float & roll_deg , float & pitch_deg , float & yaw_deg , bool & yaw_is_earth_frame ) ;
2023-07-21 03:35:42 -03:00
// accessors for scripting backends and logging
2022-12-27 21:21:46 -04:00
bool get_location_target ( uint8_t instance , Location & target_loc ) ;
void set_attitude_euler ( uint8_t instance , float roll_deg , float pitch_deg , float yaw_bf_deg ) ;
2023-07-21 03:35:42 -03:00
// write mount log packet for all backends
void write_log ( ) ;
// write mount log packet for a single backend (called by camera library)
void write_log ( uint8_t instance , uint64_t timestamp_us ) ;
2022-09-27 22:28:56 -03:00
//
// camera controls for gimbals that include a camera
//
// take a picture
bool take_picture ( uint8_t instance ) ;
// start or stop video recording
// set start_recording = true to start record, false to stop recording
bool record_video ( uint8_t instance , bool start_recording ) ;
2023-04-12 09:35:43 -03:00
// set zoom specified as a rate or percentage
2023-04-18 22:06:46 -03:00
bool set_zoom ( uint8_t instance , ZoomType zoom_type , float zoom_value ) ;
2022-09-27 22:28:56 -03:00
2023-04-24 09:23:47 -03:00
// set focus specified as rate, percentage or auto
2022-09-27 22:28:56 -03:00
// focus in = -1, focus hold = 0, focus out = 1
2023-06-21 03:03:39 -03:00
SetFocusResult set_focus ( uint8_t instance , FocusType focus_type , float focus_value ) ;
2022-09-27 22:28:56 -03:00
2023-07-06 01:55:23 -03:00
// set tracking to none, point or rectangle (see TrackingType enum)
// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right
// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom
bool set_tracking ( uint8_t instance , TrackingType tracking_type , const Vector2f & p1 , const Vector2f & p2 ) ;
2023-07-14 08:21:22 -03:00
// set camera lens as a value from 0 to 5
bool set_lens ( uint8_t instance , uint8_t lens ) ;
2024-03-17 22:51:00 -03:00
# if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED
// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type
// primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t
bool set_camera_source ( uint8_t instance , uint8_t primary_source , uint8_t secondary_source ) ;
# endif
2023-06-12 00:10:19 -03:00
// send camera information message to GCS
2023-08-01 15:34:14 -03:00
void send_camera_information ( uint8_t instance , mavlink_channel_t chan ) const ;
2023-06-12 00:10:19 -03:00
// send camera settings message to GCS
2023-08-01 15:34:14 -03:00
void send_camera_settings ( uint8_t instance , mavlink_channel_t chan ) const ;
2023-09-11 23:23:17 -03:00
// send camera capture status message to GCS
void send_camera_capture_status ( uint8_t instance , mavlink_channel_t chan ) const ;
2023-06-12 00:10:19 -03:00
2023-08-21 09:29:28 -03:00
//
// rangefinder
//
// get rangefinder distance. Returns true on success
bool get_rangefinder_distance ( uint8_t instance , float & distance_m ) const ;
2024-03-14 21:58:24 -03:00
// enable/disable rangefinder. Returns true on success
bool set_rangefinder_enable ( uint8_t instance , bool enable ) ;
2015-01-08 16:10:48 -04:00
// parameter var table
static const struct AP_Param : : GroupInfo var_info [ ] ;
2014-07-10 01:01:46 -03:00
2015-01-18 21:39:55 -04:00
protected :
2018-07-24 20:30:23 -03:00
static AP_Mount * _singleton ;
2022-08-30 08:15:10 -03:00
// parameters for backends
AP_Mount_Params _params [ AP_MOUNT_MAX_INSTANCES ] ;
2015-01-08 16:10:48 -04:00
// front end members
uint8_t _num_instances ; // number of mounts instantiated
uint8_t _primary ; // primary mount
AP_Mount_Backend * _backends [ AP_MOUNT_MAX_INSTANCES ] ; // pointers to instantiated mounts
2018-10-11 06:30:03 -03:00
private :
2020-10-19 11:32:08 -03:00
// Check if instance backend is ok
2023-03-02 00:03:02 -04:00
AP_Mount_Backend * get_primary ( ) const ;
AP_Mount_Backend * get_instance ( uint8_t instance ) const ;
2018-10-11 06:30:03 -03:00
2019-04-30 07:22:48 -03:00
void handle_gimbal_report ( mavlink_channel_t chan , const mavlink_message_t & msg ) ;
2023-08-23 21:10:29 -03:00
# if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED
2019-04-30 07:22:48 -03:00
void handle_mount_configure ( const mavlink_message_t & msg ) ;
2023-08-23 21:10:29 -03:00
# endif
# if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED
2019-04-30 07:22:48 -03:00
void handle_mount_control ( const mavlink_message_t & msg ) ;
2023-08-23 21:10:29 -03:00
# endif
2018-10-11 06:30:03 -03:00
2023-08-17 04:19:03 -03:00
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_gimbal_manager_pitchyaw ( const mavlink_command_int_t & packet ) ;
MAV_RESULT handle_command_do_gimbal_manager_configure ( const mavlink_command_int_t & packet , const mavlink_message_t & msg ) ;
2023-03-24 00:50:40 -03:00
void handle_gimbal_manager_set_attitude ( const mavlink_message_t & msg ) ;
2023-11-04 06:03:14 -03:00
void handle_gimbal_manager_set_pitchyaw ( const mavlink_message_t & msg ) ;
2019-03-16 04:06:02 -03:00
void handle_global_position_int ( const mavlink_message_t & msg ) ;
2022-05-26 23:57:55 -03:00
void handle_gimbal_device_information ( const mavlink_message_t & msg ) ;
2022-06-03 05:27:08 -03:00
void handle_gimbal_device_attitude_status ( const mavlink_message_t & msg ) ;
2022-06-16 04:30:01 -03:00
// perform any required parameter conversion
void convert_params ( ) ;
2012-06-13 15:55:19 -03:00
} ;
2018-07-24 20:30:23 -03:00
namespace AP {
AP_Mount * mount ( ) ;
} ;
2020-07-24 14:01:21 -03:00
2021-07-20 09:16:21 -03:00
# endif // HAL_MOUNT_ENABLED