11 #if AP_AHRS_NAVEKF_AVAILABLE 24 GIMBAL_STATE_NOT_PRESENT = 0,
25 GIMBAL_STATE_PRESENT_INITIALIZING,
26 GIMBAL_STATE_PRESENT_ALIGNING,
27 GIMBAL_STATE_PRESENT_RUNNING
33 GIMBAL_MODE_POS_HOLD_FF,
44 _state(GIMBAL_STATE_NOT_PRESENT),
45 _vehicle_yaw_rate_ef_filt(0.0
f),
46 _vehicle_to_gimbal_quat(),
47 _vehicle_to_gimbal_quat_filt(),
48 _filtered_joint_angles(),
49 _last_report_msg_ms(0),
60 void update_target(
Vector3f newTarget);
61 void receive_feedback(mavlink_channel_t
chan, mavlink_message_t *msg);
68 void set_lockedToBody(
bool val) { _lockedToBody = val; }
72 float get_log_dt() {
return _log_dt; }
75 void fetch_params() { _gimbalParams.fetch_params(); }
77 void handle_param_value(mavlink_message_t *msg) {
78 _gimbalParams.handle_param_value(msg);
83 void update_estimators();
84 void send_controls(mavlink_channel_t
chan);
85 void extract_feedback(
const mavlink_gimbal_report_t& report_msg);
86 void update_joint_angle_est();
91 Vector3f get_ang_vel_dem_gyro_bias();
92 Vector3f get_ang_vel_dem_body_lock();
94 void gimbal_ang_vel_to_joint_rates(
const Vector3f& ang_vel,
Vector3f& joint_rates);
95 void joint_rates_to_gimbal_ang_vel(
const Vector3f& joint_rates,
Vector3f& ang_vel);
97 void readVehicleDeltaAngle(uint8_t ins_index,
Vector3f &dAng);
104 gimbal_mode_t get_mode();
106 bool joints_near_limits();
112 gimbal_state_t _state;
121 float _vehicle_yaw_rate_ef_filt;
123 static const uint8_t _compid = MAV_COMP_ID_GIMBAL;
132 uint32_t _last_report_msg_ms;
136 float _ang_vel_mag_filt;
152 #endif // AP_AHRS_NAVEKF_AVAILABLE
static void register_client(AP_AccelCal_Client *client)
virtual bool _acal_get_saving()
virtual AccelCalibrator * _acal_get_calibrator(uint8_t instance)=0
Common definitions and utility routines for the ArduPilot libraries.
virtual void _acal_save_calibrations()=0
AP_HAL::AnalogSource * chan
virtual bool _acal_get_ready_to_sample()