mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
SITL: stop taking DataFlash pointer as argument
This commit is contained in:
parent
071dca8fe8
commit
834b45ce18
@ -171,7 +171,7 @@ void SITL::simstate_send(mavlink_channel_t chan)
|
|||||||
}
|
}
|
||||||
|
|
||||||
/* report SITL state to DataFlash */
|
/* report SITL state to DataFlash */
|
||||||
void SITL::Log_Write_SIMSTATE(DataFlash_Class *DataFlash)
|
void SITL::Log_Write_SIMSTATE()
|
||||||
{
|
{
|
||||||
float yaw;
|
float yaw;
|
||||||
|
|
||||||
@ -195,7 +195,7 @@ void SITL::Log_Write_SIMSTATE(DataFlash_Class *DataFlash)
|
|||||||
q3 : state.quaternion.q3,
|
q3 : state.quaternion.q3,
|
||||||
q4 : state.quaternion.q4,
|
q4 : state.quaternion.q4,
|
||||||
};
|
};
|
||||||
DataFlash->WriteBlock(&pkt, sizeof(pkt));
|
DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -226,7 +226,7 @@ public:
|
|||||||
|
|
||||||
void simstate_send(mavlink_channel_t chan);
|
void simstate_send(mavlink_channel_t chan);
|
||||||
|
|
||||||
void Log_Write_SIMSTATE(DataFlash_Class *dataflash);
|
void Log_Write_SIMSTATE();
|
||||||
|
|
||||||
// convert a set of roll rates from earth frame to body frame
|
// convert a set of roll rates from earth frame to body frame
|
||||||
static void convert_body_frame(double rollDeg, double pitchDeg,
|
static void convert_body_frame(double rollDeg, double pitchDeg,
|
||||||
|
Loading…
Reference in New Issue
Block a user