AP_Mount: use dataflash singleton

Closes #7550
This commit is contained in:
Peter Barker 2018-03-14 11:23:01 +11:00 committed by Randy Mackay
parent b348cfa985
commit 0652c89844
7 changed files with 19 additions and 14 deletions

View File

@ -415,8 +415,6 @@ void AP_Mount::init(const AP_SerialManager& serial_manager)
return;
}
_dataflash = DataFlash_Class::instance();
// default mount to servo mount if rc output channels to control roll, tilt or pan have been defined
if (!state[0]._type.configured()) {
if (SRV_Channels::function_assigned(SRV_Channel::Aux_servo_function_t::k_mount_pan) ||

View File

@ -182,6 +182,4 @@ protected:
MAV_MOUNT_MODE _mode; // current mode (see MAV_MOUNT_MODE enum)
struct Location _roi_target; // roi target location
} state[AP_MOUNT_MAX_INSTANCES];
DataFlash_Class *_dataflash;
};

View File

@ -119,19 +119,24 @@ void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, mavlink_m
_gimbal.update_target(_angle_ef_target_rad);
_gimbal.receive_feedback(chan,msg);
if(!_params_saved && _frontend._dataflash != nullptr && _frontend._dataflash->logging_started()) {
DataFlash_Class *df = DataFlash_Class::instance();
if (df == nullptr) {
return;
}
if(!_params_saved && df->logging_started()) {
_gimbal.fetch_params(); //last parameter save might not be stored in dataflash so retry
_params_saved = true;
}
if (_gimbal.get_log_dt() > 1.0f/25.0f) {
_gimbal.write_logs(_frontend._dataflash);
_gimbal.write_logs();
}
}
void AP_Mount_SoloGimbal::handle_param_value(mavlink_message_t *msg)
{
_gimbal.handle_param_value(_frontend._dataflash, msg);
_gimbal.handle_param_value(msg);
}
/*

View File

@ -371,9 +371,12 @@ void SoloGimbal::update_target(Vector3f newTarget)
_att_target_euler_rad.y = constrain_float(_att_target_euler_rad.y,radians(-90),radians(0));
}
void SoloGimbal::write_logs(DataFlash_Class* dataflash)
void SoloGimbal::write_logs()
{
if (dataflash == nullptr) return;
DataFlash_Class *dataflash = DataFlash_Class::instance();
if (dataflash == nullptr) {
return;
}
uint32_t tstamp = AP_HAL::millis();
Vector3f eulerEst;

View File

@ -67,15 +67,15 @@ public:
void set_lockedToBody(bool val) { _lockedToBody = val; }
void write_logs(DataFlash_Class* dataflash);
void write_logs();
float get_log_dt() { return _log_dt; }
void disable_torque_report() { _gimbalParams.set_param(GMB_PARAM_GMB_SND_TORQUE, 0); }
void fetch_params() { _gimbalParams.fetch_params(); }
void handle_param_value(DataFlash_Class *dataflash, mavlink_message_t *msg) {
_gimbalParams.handle_param_value(dataflash, msg);
void handle_param_value(mavlink_message_t *msg) {
_gimbalParams.handle_param_value(msg);
}
private:

View File

@ -166,11 +166,12 @@ void SoloGimbal_Parameters::update()
}
}
void SoloGimbal_Parameters::handle_param_value(DataFlash_Class *dataflash, mavlink_message_t *msg)
void SoloGimbal_Parameters::handle_param_value(mavlink_message_t *msg)
{
mavlink_param_value_t packet;
mavlink_msg_param_value_decode(msg, &packet);
DataFlash_Class *dataflash = DataFlash_Class::instance();
if (dataflash != nullptr) {
dataflash->Log_Write_Parameter(packet.param_id, packet.param_value);
}

View File

@ -54,7 +54,7 @@ public:
void set_param(gmb_param_t param, float value);
void update();
void handle_param_value(DataFlash_Class *dataflash, mavlink_message_t *msg);
void handle_param_value(mavlink_message_t *msg);
Vector3f get_accel_bias();
Vector3f get_accel_gain();