Browse Source

AP_Mount: rename dataflash to logger

mission-4.1.18
Tom Pittenger 6 years ago committed by Peter Barker
parent
commit
9dc7e5342d
  1. 8
      libraries/AP_Mount/AP_Mount_SoloGimbal.cpp
  2. 8
      libraries/AP_Mount/SoloGimbal.cpp
  3. 6
      libraries/AP_Mount/SoloGimbal_Parameters.cpp

8
libraries/AP_Mount/AP_Mount_SoloGimbal.cpp

@ -118,13 +118,13 @@ void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, const mav @@ -118,13 +118,13 @@ void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, const mav
_gimbal.update_target(_angle_ef_target_rad);
_gimbal.receive_feedback(chan,msg);
AP_Logger *df = AP_Logger::get_singleton();
if (df == nullptr) {
AP_Logger *logger = AP_Logger::get_singleton();
if (logger == nullptr) {
return;
}
if(!_params_saved && df->logging_started()) {
_gimbal.fetch_params(); //last parameter save might not be stored in dataflash so retry
if(!_params_saved && logger->logging_started()) {
_gimbal.fetch_params(); //last parameter save might not be stored in logger so retry
_params_saved = true;
}

8
libraries/AP_Mount/SoloGimbal.cpp

@ -383,8 +383,8 @@ void SoloGimbal::update_target(const Vector3f &newTarget) @@ -383,8 +383,8 @@ void SoloGimbal::update_target(const Vector3f &newTarget)
void SoloGimbal::write_logs()
{
AP_Logger *dataflash = AP_Logger::get_singleton();
if (dataflash == nullptr) {
AP_Logger *logger = AP_Logger::get_singleton();
if (logger == nullptr) {
return;
}
@ -409,7 +409,7 @@ void SoloGimbal::write_logs() @@ -409,7 +409,7 @@ void SoloGimbal::write_logs()
joint_angles_y : _measurement.joint_angles.y,
joint_angles_z : _measurement.joint_angles.z
};
dataflash->WriteBlock(&pkt1, sizeof(pkt1));
logger->WriteBlock(&pkt1, sizeof(pkt1));
struct log_Gimbal2 pkt2 = {
LOG_PACKET_HEADER_INIT(LOG_GIMBAL2_MSG),
@ -425,7 +425,7 @@ void SoloGimbal::write_logs() @@ -425,7 +425,7 @@ void SoloGimbal::write_logs()
target_y: _att_target_euler_rad.y,
target_z: _att_target_euler_rad.z
};
dataflash->WriteBlock(&pkt2, sizeof(pkt2));
logger->WriteBlock(&pkt2, sizeof(pkt2));
_log_dt = 0;
_log_del_ang.zero();

6
libraries/AP_Mount/SoloGimbal_Parameters.cpp

@ -185,9 +185,9 @@ void SoloGimbal_Parameters::handle_param_value(const mavlink_message_t *msg) @@ -185,9 +185,9 @@ void SoloGimbal_Parameters::handle_param_value(const mavlink_message_t *msg)
mavlink_param_value_t packet;
mavlink_msg_param_value_decode(msg, &packet);
AP_Logger *dataflash = AP_Logger::get_singleton();
if (dataflash != nullptr) {
dataflash->Write_Parameter(packet.param_id, packet.param_value);
AP_Logger *logger = AP_Logger::get_singleton();
if (logger != nullptr) {
logger->Write_Parameter(packet.param_id, packet.param_value);
}
for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {

Loading…
Cancel
Save