28 static bool mount_open = 0;
39 case MAV_MOUNT_MODE_RETRACT:
46 case MAV_MOUNT_MODE_NEUTRAL:
53 case MAV_MOUNT_MODE_MAVLINK_TARGETING:
61 case MAV_MOUNT_MODE_RC_TARGETING:
70 case MAV_MOUNT_MODE_GPS_POINT:
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;
134 gimbal_target = m * cam;
173 while (angle < -1800) angle += 3600;
174 while (angle >= 1800) angle -= 3600;
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;
184 if ((angle < angle_min) && (angle > angle_max)) {
186 int16_t err_min = angle_min - angle + (angle<angle_min ? 0 : 3600);
188 int16_t err_max = angle - angle_max + (angle>angle_max ? 0 : 3600);
189 angle = err_min<err_max ? angle_min : angle_max;
199 int16_t servo_out =
closest_limit(angle, angle_min, angle_max);
SRV_Channel::Aux_servo_function_t _pan_idx
void to_euler(float *roll, float *pitch, float *yaw) const
static AP_SerialManager serial_manager
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 update_targets_from_rc()
void from_euler(float roll, float pitch, float yaw)
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)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
int16_t closest_limit(int16_t angle, int16_t angle_min, int16_t angle_max)
bool is_zero(const T fVal1)
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)
struct Location _roi_target
SRV_Channel::Aux_servo_function_t _roll_idx
AP_Vector3f _retract_angles
Vector3f _angle_bf_output_deg
Receiving valid messages and 2D lock.
SRV_Channel::Aux_servo_function_t _open_idx
AP_Vector3f _neutral_angles
const AP_AHRS_TYPE & _ahrs
struct AP_Mount_Servo::@135 _flags
AP_HAL::AnalogSource * chan
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 ...
virtual void set_mode(enum MAV_MOUNT_MODE mode)
MAV_MOUNT_MODE get_mode(void) const
static bool function_assigned(SRV_Channel::Aux_servo_function_t function)
mount2 open (deploy) / close (retract)
SRV_Channel::Aux_servo_function_t _tilt_idx