APM:Libraries
AP_Mount_Servo.cpp
Go to the documentation of this file.
1 #include "AP_Mount_Servo.h"
2 
3 extern const AP_HAL::HAL& hal;
4 
5 // init - performs any required initialisation for this instance
7 {
8  if (_instance == 0) {
13  } else {
14  // this must be the 2nd mount
19  }
20 
21  // check which servos have been assigned
23 }
24 
25 // update mount position - should be called periodically
27 {
28  static bool mount_open = 0; // 0 is closed
29 
30  // check servo map every three seconds to allow users to modify parameters
31  uint32_t now = AP_HAL::millis();
32  if (now - _last_check_servo_map_ms > 3000) {
35  }
36 
37  switch(get_mode()) {
38  // move mount to a "retracted position" or to a position where a fourth servo can retract the entire mount into the fuselage
39  case MAV_MOUNT_MODE_RETRACT:
40  {
42  break;
43  }
44 
45  // move mount to a neutral position, typically pointing forward
46  case MAV_MOUNT_MODE_NEUTRAL:
47  {
49  break;
50  }
51 
52  // point to the angles given by a mavlink message
53  case MAV_MOUNT_MODE_MAVLINK_TARGETING:
54  {
55  // earth-frame angle targets (i.e. _angle_ef_target_rad) should have already been set by a MOUNT_CONTROL message from GCS
56  stabilize();
57  break;
58  }
59 
60  // RC radio manual angle control, but with stabilization from the AHRS
61  case MAV_MOUNT_MODE_RC_TARGETING:
62  {
63  // update targets using pilot's rc inputs
65  stabilize();
66  break;
67  }
68 
69  // point mount to a GPS point given by the mission planner
70  case MAV_MOUNT_MODE_GPS_POINT:
71  {
72  if(AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
73  calc_angle_to_location(_state._roi_target, _angle_ef_target_rad, _flags.tilt_control, _flags.pan_control, false);
74  stabilize();
75  }
76  break;
77  }
78 
79  default:
80  //do nothing
81  break;
82  }
83 
84  // move mount to a "retracted position" into the fuselage with a fourth servo
85  bool mount_open_new = (get_mode() == MAV_MOUNT_MODE_RETRACT) ? 0 : 1;
86  if (mount_open != mount_open_new) {
87  mount_open = mount_open_new;
88  move_servo(_open_idx, mount_open_new, 0, 1);
89  }
90 
91  // write the results to the servos
95 }
96 
97 // set_mode - sets mount's mode
98 void AP_Mount_Servo::set_mode(enum MAV_MOUNT_MODE mode)
99 {
100  // record the mode change and return success
101  _state._mode = mode;
102 }
103 
104 // private methods
105 
106 // check_servo_map - detects which axis we control using the functions assigned to the servos in the RC_Channel_aux
107 // should be called periodically (i.e. 1hz or less)
109 {
113 }
114 
115 // status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
116 void AP_Mount_Servo::status_msg(mavlink_channel_t chan)
117 {
118  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);
119 }
120 
121 // stabilize - stabilizes the mount relative to the Earth's frame
122 // input: _angle_ef_target_rad (earth frame targets in radians)
123 // output: _angle_bf_output_deg (body frame angles in degrees)
125 {
126  // only do the full 3D frame transform if we are doing pan control
127  if (_state._stab_pan) {
128  Matrix3f m;
129  Matrix3f cam;
130  Matrix3f gimbal_target;
131  m = _frontend._ahrs.get_rotation_body_to_ned();
132  m.transpose();
134  gimbal_target = m * cam;
139  } else {
140  // otherwise base mount roll and tilt on the ahrs
141  // roll/tilt attitude, plus any requested angle
145  if (_state._stab_roll) {
147  }
148  if (_state._stab_tilt) {
150  }
151 
152  // lead filter
153  const Vector3f &gyro = _frontend._ahrs.get_gyro();
154 
155  if (_state._stab_roll && !is_zero(_state._roll_stb_lead) && fabsf(_frontend._ahrs.pitch) < M_PI/3.0f) {
156  // Compute rate of change of euler roll angle
157  float roll_rate = gyro.x + (_frontend._ahrs.sin_pitch() / _frontend._ahrs.cos_pitch()) * (gyro.y * _frontend._ahrs.sin_roll() + gyro.z * _frontend._ahrs.cos_roll());
159  }
160 
162  // Compute rate of change of euler pitch angle
163  float pitch_rate = _frontend._ahrs.cos_pitch() * gyro.y - _frontend._ahrs.sin_roll() * gyro.z;
165  }
166  }
167 }
168 
169 // closest_limit - returns closest angle to 'angle' taking into account limits. all angles are in degrees * 10
170 int16_t AP_Mount_Servo::closest_limit(int16_t angle, int16_t angle_min, int16_t angle_max)
171 {
172  // Make sure the angle lies in the interval [-180 .. 180[ degrees
173  while (angle < -1800) angle += 3600;
174  while (angle >= 1800) angle -= 3600;
175 
176  // Make sure the angle limits lie in the interval [-180 .. 180[ degrees
177  while (angle_min < -1800) angle_min += 3600;
178  while (angle_min >= 1800) angle_min -= 3600;
179  while (angle_max < -1800) angle_max += 3600;
180  while (angle_max >= 1800) angle_max -= 3600;
181 
182  // If the angle is outside servo limits, saturate the angle to the closest limit
183  // On a circle the closest angular position must be carefully calculated to account for wrap-around
184  if ((angle < angle_min) && (angle > angle_max)) {
185  // angle error if min limit is used
186  int16_t err_min = angle_min - angle + (angle<angle_min ? 0 : 3600); // add 360 degrees if on the "wrong side"
187  // angle error if max limit is used
188  int16_t err_max = angle - angle_max + (angle>angle_max ? 0 : 3600); // add 360 degrees if on the "wrong side"
189  angle = err_min<err_max ? angle_min : angle_max;
190  }
191 
192  return angle;
193 }
194 
195 // move_servo - moves servo with the given id to the specified angle. all angles are in degrees * 10
196 void AP_Mount_Servo::move_servo(uint8_t function_idx, int16_t angle, int16_t angle_min, int16_t angle_max)
197 {
198  // saturate to the closest angle limit if outside of [min max] angle interval
199  int16_t servo_out = closest_limit(angle, angle_min, angle_max);
200  SRV_Channels::move_servo((SRV_Channel::Aux_servo_function_t)function_idx, servo_out, angle_min, angle_max);
201 }
virtual void update()
SRV_Channel::Aux_servo_function_t _pan_idx
void to_euler(float *roll, float *pitch, float *yaw) const
Definition: matrix3.cpp:49
MAV_MOUNT_MODE _mode
Definition: AP_Mount.h:182
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
AP_Int16 _pan_angle_max
Definition: AP_Mount.h:174
static void move_servo(SRV_Channel::Aux_servo_function_t function, int16_t value, int16_t angle_min, int16_t angle_max)
Vector3f _angle_ef_target_rad
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
virtual void init(const AP_SerialManager &serial_manager)
AP_Mount::mount_state & _state
virtual void status_msg(mavlink_channel_t chan)
mount open (deploy) / close (retract)
Definition: SRV_Channel.h:53
AP_Mount & _frontend
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
mount yaw (pan)
Definition: SRV_Channel.h:50
int16_t closest_limit(int16_t angle, int16_t angle_min, int16_t angle_max)
AP_Float _pitch_stb_lead
Definition: AP_Mount.h:180
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
uint32_t _last_check_servo_map_ms
void calc_angle_to_location(const struct Location &target, Vector3f &angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan=true)
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
struct Location _roi_target
Definition: AP_Mount.h:183
SRV_Channel::Aux_servo_function_t _roll_idx
AP_Vector3f _retract_angles
Definition: AP_Mount.h:176
T z
Definition: vector3.h:67
Vector3f _angle_bf_output_deg
Receiving valid messages and 2D lock.
Definition: AP_GPS.h:99
SRV_Channel::Aux_servo_function_t _open_idx
AP_Vector3f _neutral_angles
Definition: AP_Mount.h:177
void transpose(void)
Definition: matrix3.h:185
const AP_AHRS_TYPE & _ahrs
Definition: AP_Mount.h:143
struct AP_Mount_Servo::@135 _flags
AP_Int16 _pan_angle_min
Definition: AP_Mount.h:173
AP_Int16 _roll_angle_max
Definition: AP_Mount.h:170
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
void move_servo(uint8_t rc, int16_t angle, int16_t angle_min, int16_t angle_max)
move_servo - moves servo with the given id to the specified angle. all angles are in degrees * 10 ...
AP_Int16 _roll_angle_min
Definition: AP_Mount.h:169
mount2 pitch (tilt)
Definition: SRV_Channel.h:57
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
AP_Float _roll_stb_lead
Definition: AP_Mount.h:179
virtual void set_mode(enum MAV_MOUNT_MODE mode)
#define degrees(x)
Definition: moduletest.c:23
#define M_PI
Definition: definitions.h:10
AP_Int16 _tilt_angle_max
Definition: AP_Mount.h:172
MAV_MOUNT_MODE get_mode(void) const
static bool function_assigned(SRV_Channel::Aux_servo_function_t function)
mount pitch (tilt)
Definition: SRV_Channel.h:51
T x
Definition: vector3.h:67
mount2 open (deploy) / close (retract)
Definition: SRV_Channel.h:59
mount2 yaw (pan)
Definition: SRV_Channel.h:56
SRV_Channel::Aux_servo_function_t _tilt_idx
AP_Int16 _tilt_angle_min
Definition: AP_Mount.h:171