mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
uncrustify libraries/AP_Mount/AP_Mount.h
This commit is contained in:
parent
ff555dfb7a
commit
7ffa44c324
@ -15,9 +15,9 @@
|
||||
* Usage: Use in main code to control mounts attached to *
|
||||
* vehicle. *
|
||||
* *
|
||||
*Comments: All angles in degrees * 100, distances in meters*
|
||||
**Comments: All angles in degrees * 100, distances in meters*
|
||||
* unless otherwise stated. *
|
||||
************************************************************/
|
||||
************************************************************/
|
||||
#ifndef AP_Mount_H
|
||||
#define AP_Mount_H
|
||||
|
||||
@ -36,7 +36,7 @@ public:
|
||||
AP_Mount(const struct Location *current_loc, GPS *&gps, AP_AHRS *ahrs, uint8_t id);
|
||||
|
||||
//enums
|
||||
enum MountType{
|
||||
enum MountType {
|
||||
k_unknown = 0, ///< unknown type
|
||||
k_pan_tilt = 1, ///< yaw-pitch
|
||||
k_tilt_roll = 2, ///< pitch-roll
|
||||
@ -56,7 +56,9 @@ public:
|
||||
void update_mount_type(); ///< Auto-detect the mount gimbal type depending on the functions assigned to the servos
|
||||
void debug_output(); ///< For testing and development. Called in the medium loop.
|
||||
// Accessors
|
||||
enum MountType get_mount_type() { return _mount_type; }
|
||||
enum MountType get_mount_type() {
|
||||
return _mount_type;
|
||||
}
|
||||
// hook for eeprom variables
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
@ -79,15 +81,15 @@ private:
|
||||
float angle_input_rad(RC_Channel* rc, int16_t angle_min, int16_t angle_max);
|
||||
|
||||
//members
|
||||
AP_AHRS *_ahrs; ///< Rotation matrix from earth to plane.
|
||||
GPS *&_gps;
|
||||
const struct Location *_current_loc;
|
||||
AP_AHRS * _ahrs; ///< Rotation matrix from earth to plane.
|
||||
GPS *& _gps;
|
||||
const struct Location * _current_loc;
|
||||
struct Location _target_GPS_location;
|
||||
MountType _mount_type;
|
||||
|
||||
uint8_t _roll_idx; ///< RC_Channel_aux mount roll function index
|
||||
uint8_t _tilt_idx; ///< RC_Channel_aux mount tilt function index
|
||||
uint8_t _pan_idx ; ///< RC_Channel_aux mount pan function index
|
||||
uint8_t _pan_idx; ///< RC_Channel_aux mount pan function index
|
||||
uint8_t _open_idx; ///< RC_Channel_aux mount open function index
|
||||
|
||||
float _roll_control_angle; ///< radians
|
||||
|
Loading…
Reference in New Issue
Block a user