3 #if AP_AHRS_NAVEKF_AVAILABLE 12 bool SoloGimbal::present()
14 if (_state != GIMBAL_STATE_NOT_PRESENT &&
AP_HAL::millis()-_last_report_msg_ms > 3000) {
16 _state = GIMBAL_STATE_NOT_PRESENT;
20 return _state != GIMBAL_STATE_NOT_PRESENT;
23 bool SoloGimbal::aligned()
25 return present() && _state == GIMBAL_STATE_PRESENT_RUNNING;
28 gimbal_mode_t SoloGimbal::get_mode()
30 if ((_gimbalParams.initialized() &&
is_zero(_gimbalParams.get_K_rate())) || (_ahrs.get_rotation_body_to_ned().c.z < 0 && !(_lockedToBody || _calibrator.running()))) {
31 return GIMBAL_MODE_IDLE;
32 }
else if (!_ekf.getStatus()) {
33 return GIMBAL_MODE_POS_HOLD;
34 }
else if (_calibrator.running() || _lockedToBody) {
35 return GIMBAL_MODE_POS_HOLD_FF;
37 return GIMBAL_MODE_STABILIZE;
41 void SoloGimbal::receive_feedback(mavlink_channel_t
chan, mavlink_message_t *msg)
43 mavlink_gimbal_report_t report_msg;
44 mavlink_msg_gimbal_report_decode(msg, &report_msg);
46 _last_report_msg_ms = tnow_ms;
48 _gimbalParams.set_channel(chan);
50 if (report_msg.target_system != 1) {
51 _state = GIMBAL_STATE_NOT_PRESENT;
55 case GIMBAL_STATE_NOT_PRESENT:
57 _gimbalParams.reset();
59 _state = GIMBAL_STATE_PRESENT_INITIALIZING;
62 case GIMBAL_STATE_PRESENT_INITIALIZING:
63 _gimbalParams.update();
64 if (_gimbalParams.initialized()) {
66 extract_feedback(report_msg);
67 _ang_vel_mag_filt = 20;
68 _filtered_joint_angles = _measurement.joint_angles;
69 _vehicle_to_gimbal_quat_filt.from_vector312(_filtered_joint_angles.x,_filtered_joint_angles.y,_filtered_joint_angles.z);
71 _state = GIMBAL_STATE_PRESENT_ALIGNING;
75 case GIMBAL_STATE_PRESENT_ALIGNING:
76 _gimbalParams.update();
77 extract_feedback(report_msg);
79 if (_ekf.getStatus()) {
81 _state = GIMBAL_STATE_PRESENT_RUNNING;
85 case GIMBAL_STATE_PRESENT_RUNNING:
86 _gimbalParams.update();
87 extract_feedback(report_msg);
95 void SoloGimbal::send_controls(mavlink_channel_t chan)
97 if (_state == GIMBAL_STATE_PRESENT_RUNNING) {
100 _ekf.getQuat(quatEst);
103 _ang_vel_dem_rads.zero();
105 case GIMBAL_MODE_POS_HOLD_FF: {
106 _ang_vel_dem_rads += get_ang_vel_dem_body_lock();
107 _ang_vel_dem_rads += get_ang_vel_dem_gyro_bias();
108 float _ang_vel_dem_radsLen = _ang_vel_dem_rads.length();
109 if (_ang_vel_dem_radsLen >
radians(400)) {
110 _ang_vel_dem_rads *=
radians(400)/_ang_vel_dem_radsLen;
112 mavlink_msg_gimbal_control_send(chan,
mavlink_system.sysid, _compid,
113 _ang_vel_dem_rads.x, _ang_vel_dem_rads.y, _ang_vel_dem_rads.z);
116 case GIMBAL_MODE_STABILIZE: {
117 _ang_vel_dem_rads += get_ang_vel_dem_yaw(quatEst);
118 _ang_vel_dem_rads += get_ang_vel_dem_tilt(quatEst);
119 _ang_vel_dem_rads += get_ang_vel_dem_feedforward(quatEst);
120 _ang_vel_dem_rads += get_ang_vel_dem_gyro_bias();
121 float ang_vel_dem_norm = _ang_vel_dem_rads.length();
122 if (ang_vel_dem_norm >
radians(400)) {
123 _ang_vel_dem_rads *=
radians(400)/ang_vel_dem_norm;
125 mavlink_msg_gimbal_control_send(chan,
mavlink_system.sysid, _compid,
126 _ang_vel_dem_rads.x, _ang_vel_dem_rads.y, _ang_vel_dem_rads.z);
130 case GIMBAL_MODE_IDLE:
131 case GIMBAL_MODE_POS_HOLD:
137 if (get_mode() == GIMBAL_MODE_POS_HOLD) {
147 _max_torque = max_torque;
157 void SoloGimbal::extract_feedback(
const mavlink_gimbal_report_t& report_msg)
159 _measurement.delta_time = report_msg.delta_time;
160 _measurement.delta_angles.x = report_msg.delta_angle_x;
161 _measurement.delta_angles.y = report_msg.delta_angle_y;
162 _measurement.delta_angles.z = report_msg.delta_angle_z;
163 _measurement.delta_velocity.x = report_msg.delta_velocity_x,
164 _measurement.delta_velocity.y = report_msg.delta_velocity_y;
165 _measurement.delta_velocity.z = report_msg.delta_velocity_z;
166 _measurement.joint_angles.x = report_msg.joint_roll;
167 _measurement.joint_angles.y = report_msg.joint_el;
168 _measurement.joint_angles.z = report_msg.joint_az;
171 _calibrator.new_sample(_measurement.delta_velocity,_measurement.delta_time);
174 _measurement.delta_angles -= _gimbalParams.get_gyro_bias() * _measurement.delta_time;
175 _measurement.joint_angles -= _gimbalParams.get_joint_bias();
176 _measurement.delta_velocity -= _gimbalParams.get_accel_bias() * _measurement.delta_time;
177 Vector3f accel_gain = _gimbalParams.get_accel_gain();
178 _measurement.delta_velocity.
x *= (
is_zero(accel_gain.
x) ? 1.0f : accel_gain.
x);
179 _measurement.delta_velocity.y *= (
is_zero(accel_gain.
y) ? 1.0f : accel_gain.
y);
180 _measurement.delta_velocity.z *= (
is_zero(accel_gain.
z) ? 1.0f : accel_gain.
z);
183 Vector3f ang_vel = _measurement.delta_angles / _measurement.delta_time;
185 _ekf.getGyroBias(ekf_gyro_bias);
186 ang_vel -= ekf_gyro_bias;
187 float alpha =
constrain_float(_measurement.delta_time/(_measurement.delta_time+0.5f),0.0f,1.0f);
188 _ang_vel_mag_filt += (ang_vel.
length()-_ang_vel_mag_filt)*alpha;
189 _ang_vel_mag_filt =
MIN(_ang_vel_mag_filt,20.0
f);
192 _vehicle_to_gimbal_quat.from_vector312(_measurement.joint_angles.x,_measurement.joint_angles.y,_measurement.joint_angles.z);
195 _log_dt += _measurement.delta_time;
196 _log_del_ang += _measurement.delta_angles;
197 _log_del_vel += _measurement.delta_velocity;
200 void SoloGimbal::update_estimators()
202 if (_state == GIMBAL_STATE_NOT_PRESENT || _state == GIMBAL_STATE_PRESENT_INITIALIZING) {
207 _ekf.RunEKF(_measurement.delta_time, _measurement.delta_angles, _measurement.delta_velocity, _measurement.joint_angles);
208 update_joint_angle_est();
211 void SoloGimbal::readVehicleDeltaAngle(uint8_t ins_index,
Vector3f &dAng) {
221 void SoloGimbal::update_fast() {
227 readVehicleDeltaAngle(0, dAng);
228 _vehicle_delta_angles += dAng*0.5f;
229 readVehicleDeltaAngle(1, dAng);
230 _vehicle_delta_angles += dAng*0.5f;
236 _vehicle_delta_angles += dAng;
240 void SoloGimbal::update_joint_angle_est()
242 static const float tc = 1.0f;
243 float dt = _measurement.delta_time;
247 _vehicle_to_gimbal_quat.
inverse().rotation_matrix(Tvg);
250 _ekf.getGyroBias(delta_angle_bias);
251 delta_angle_bias *= dt;
254 gimbal_ang_vel_to_joint_rates((_measurement.delta_angles-delta_angle_bias) - Tvg*_vehicle_delta_angles, joint_del_ang);
256 _filtered_joint_angles += joint_del_ang;
257 _filtered_joint_angles += (_measurement.joint_angles-_filtered_joint_angles)*alpha;
259 _vehicle_to_gimbal_quat_filt.from_vector312(_filtered_joint_angles.x,_filtered_joint_angles.y,_filtered_joint_angles.z);
261 _vehicle_delta_angles.
zero();
266 static const float tc = 0.1f;
267 static const float yawErrorLimit =
radians(5.7
f);
268 float dt = _measurement.delta_time;
269 float alpha = dt/(dt+tc);
271 Matrix3f Tve = _ahrs.get_rotation_body_to_ned();
279 _vehicle_yaw_rate_ef_filt += (_ahrs.get_yaw_rate_earth() - _vehicle_yaw_rate_ef_filt) * alpha;
281 float yaw_rate_ff = 0;
284 if (_vehicle_yaw_rate_ef_filt > _gimbalParams.get_K_rate()*yawErrorLimit) {
285 yaw_rate_ff = _vehicle_yaw_rate_ef_filt-_gimbalParams.get_K_rate()*yawErrorLimit;
286 }
else if (_vehicle_yaw_rate_ef_filt < -_gimbalParams.get_K_rate()*yawErrorLimit) {
287 yaw_rate_ff = _vehicle_yaw_rate_ef_filt+_gimbalParams.get_K_rate()*yawErrorLimit;
294 gimbalRateDemVecYaw.
z = yaw_rate_ff - _gimbalParams.get_K_rate() * _filtered_joint_angles.z /
constrain_float(Tve.
c.
z,0.5f,1.0f);
298 gimbalRateDemVecYaw = Teg * gimbalRateDemVecYaw;
300 return gimbalRateDemVecYaw;
311 _att_target_euler_rad.y,
323 Vector3f gimbalRateDemVecTilt = deltaAngErr * _gimbalParams.get_K_rate();
324 return gimbalRateDemVecTilt;
330 static float lastDem;
333 float delta = _att_target_euler_rad.y - lastDem;
334 lastDem = _att_target_euler_rad.y;
337 gimbalRateDemVecForward.
y = delta / _measurement.delta_time;
338 return gimbalRateDemVecForward;
341 Vector3f SoloGimbal::get_ang_vel_dem_gyro_bias()
344 _ekf.getGyroBias(gyroBias);
345 return gyroBias + _gimbalParams.get_gyro_bias();
348 Vector3f SoloGimbal::get_ang_vel_dem_body_lock()
352 _vehicle_to_gimbal_quat_filt.
inverse().rotation_matrix(Tvg);
356 gimbalRateDemVecBodyLock = _filtered_joint_angles * -_gimbalParams.get_K_rate();
358 joint_rates_to_gimbal_ang_vel(gimbalRateDemVecBodyLock, gimbalRateDemVecBodyLock);
361 gimbalRateDemVecBodyLock += Tvg * _ahrs.get_gyro();
363 return gimbalRateDemVecBodyLock;
366 void SoloGimbal::update_target(
Vector3f newTarget)
369 _att_target_euler_rad.
y = _att_target_euler_rad.y + 0.02f*(newTarget.
y - _att_target_euler_rad.y);
374 void SoloGimbal::write_logs()
377 if (dataflash ==
nullptr) {
385 _ekf.getQuat(quatEst);
386 quatEst.
to_euler(eulerEst.
x, eulerEst.
y, eulerEst.
z);
407 est_sta : (uint8_t) _ekf.getStatus(),
411 rate_x : _ang_vel_dem_rads.x,
412 rate_y : _ang_vel_dem_rads.y,
413 rate_z : _ang_vel_dem_rads.z,
425 bool SoloGimbal::joints_near_limits()
427 return fabsf(_measurement.joint_angles.x) >
radians(40) || _measurement.joint_angles.y >
radians(45) || _measurement.joint_angles.y < -
radians(135);
432 if(instance==0 && (present() || _calibrator.get_status() ==
ACCEL_CAL_SUCCESS)) {
439 bool SoloGimbal::_acal_get_ready_to_sample()
441 return _ang_vel_mag_filt <
radians(10);
444 bool SoloGimbal::_acal_get_saving()
446 return _gimbalParams.flashing();
449 void SoloGimbal::_acal_save_calibrations()
456 _calibrator.get_calibration(bias,gain);
457 _gimbalParams.set_accel_bias(bias);
458 _gimbalParams.set_accel_gain(gain);
459 _gimbalParams.flash();
462 void SoloGimbal::gimbal_ang_vel_to_joint_rates(
const Vector3f& ang_vel,
Vector3f& joint_rates)
464 float sin_theta = sinf(_measurement.joint_angles.y);
465 float cos_theta = cosf(_measurement.joint_angles.y);
467 float sin_phi = sinf(_measurement.joint_angles.x);
468 float cos_phi = cosf(_measurement.joint_angles.x);
469 float sec_phi = 1.0f/cos_phi;
470 float tan_phi = sin_phi/cos_phi;
472 joint_rates.
x = ang_vel.
x*cos_theta+ang_vel.
z*sin_theta;
473 joint_rates.
y = ang_vel.
x*sin_theta*tan_phi-ang_vel.
z*cos_theta*tan_phi+ang_vel.
y;
474 joint_rates.
z = sec_phi*(ang_vel.
z*cos_theta-ang_vel.
x*sin_theta);
477 void SoloGimbal::joint_rates_to_gimbal_ang_vel(
const Vector3f& joint_rates,
Vector3f& ang_vel)
479 float sin_theta = sinf(_measurement.joint_angles.y);
480 float cos_theta = cosf(_measurement.joint_angles.y);
482 float sin_phi = sinf(_measurement.joint_angles.x);
483 float cos_phi = cosf(_measurement.joint_angles.x);
485 ang_vel.
x = cos_theta*joint_rates.
x-sin_theta*cos_phi*joint_rates.
z;
486 ang_vel.
y = joint_rates.
y + sin_phi*joint_rates.
z;
487 ang_vel.
z = sin_theta*joint_rates.
x+cos_theta*cos_phi*joint_rates.
z;
490 #endif // AP_AHRS_NAVEKF_AVAILABLE
void to_euler(float &roll, float &pitch, float &yaw) const
bool get_soft_armed() const
void to_axis_angle(Vector3f &v)
void from_vector312(float roll, float pitch, float yaw)
const Vector3f & get_gyro(uint8_t i) const
Interface definition for the various Ground Control System.
uint8_t get_primary_gyro(void) const
void WriteBlock(const void *pBuffer, uint16_t size)
static AP_InertialSensor ins
bool get_delta_angle(uint8_t i, Vector3f &delta_angle) const
bool is_zero(const T fVal1)
mavlink_system_t mavlink_system
MAVLink system definition.
static DataFlash_Class * instance(void)
void rotation_matrix(Matrix3f &m) const
uint16_t get_sample_rate(void) const
float constrain_float(const float amt, const float low, const float high)
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Vector3f to_vector312(void) const
static constexpr float radians(float deg)
AP_HAL::AnalogSource * chan
Quaternion inverse(void) const
uint8_t get_gyro_count(void) const
AP_InertialSensor & ins()
bool inverse(Matrix3< T > &inv) const
bool get_gyro_health(uint8_t instance) const
#define LOG_PACKET_HEADER_INIT(id)