mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
SITL: expose update rate to HAL_SITL
and fixed dataflash reference loop
This commit is contained in:
parent
95ca0b39a8
commit
e1cb9beeef
@ -72,6 +72,9 @@ public:
|
||||
/* fill a sitl_fdm structure from the simulator state */
|
||||
void fill_fdm(struct sitl_fdm &fdm) const;
|
||||
|
||||
// get frame rate of model in Hz
|
||||
float get_rate_hz(void) const { return rate_hz; }
|
||||
|
||||
protected:
|
||||
Location home;
|
||||
Location location;
|
||||
|
@ -23,6 +23,7 @@
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <DataFlash/DataFlash.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
@ -104,7 +105,7 @@ void SITL::simstate_send(mavlink_channel_t chan)
|
||||
}
|
||||
|
||||
/* report SITL state to DataFlash */
|
||||
void SITL::Log_Write_SIMSTATE(DataFlash_Class &DataFlash)
|
||||
void SITL::Log_Write_SIMSTATE(DataFlash_Class *DataFlash)
|
||||
{
|
||||
float yaw;
|
||||
|
||||
@ -124,7 +125,7 @@ void SITL::Log_Write_SIMSTATE(DataFlash_Class &DataFlash)
|
||||
lat : (int32_t)(state.latitude*1.0e7),
|
||||
lng : (int32_t)(state.longitude*1.0e7)
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
DataFlash->WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -2,9 +2,10 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <DataFlash/DataFlash.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
|
||||
class DataFlash_Class;
|
||||
|
||||
namespace SITL {
|
||||
|
||||
struct PACKED sitl_fdm {
|
||||
@ -26,7 +27,6 @@ struct PACKED sitl_fdm {
|
||||
// number of rc output channels
|
||||
#define SITL_NUM_CHANNELS 14
|
||||
|
||||
|
||||
class SITL {
|
||||
public:
|
||||
|
||||
@ -49,6 +49,12 @@ public:
|
||||
|
||||
struct sitl_fdm state;
|
||||
|
||||
// loop update rate in Hz
|
||||
uint16_t update_rate_hz;
|
||||
|
||||
// true when motors are active
|
||||
bool motors_on;
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
// noise levels for simulated sensors
|
||||
@ -105,7 +111,7 @@ public:
|
||||
|
||||
void simstate_send(mavlink_channel_t chan);
|
||||
|
||||
void Log_Write_SIMSTATE(DataFlash_Class &dataflash);
|
||||
void Log_Write_SIMSTATE(DataFlash_Class *dataflash);
|
||||
|
||||
// convert a set of roll rates from earth frame to body frame
|
||||
static void convert_body_frame(double rollDeg, double pitchDeg,
|
||||
|
Loading…
Reference in New Issue
Block a user