mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
SITL: added temperature control parameters
This commit is contained in:
parent
7e24be95c9
commit
c1b6684b9f
@ -93,6 +93,15 @@ const AP_Param::GroupInfo SITL::var_info[] = {
|
||||
AP_GROUPINFO("ENGINE_FAIL", 60, SITL, engine_fail, 0),
|
||||
AP_GROUPINFO("GPS2_TYPE", 61, SITL, gps2_type, SITL::GPS_TYPE_UBLOX),
|
||||
AP_GROUPINFO("ODOM_ENABLE", 62, SITL, odom_enable, 0),
|
||||
AP_SUBGROUPEXTENSION("", 63, SITL, var_info2),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
// second table of user settable parameters for SITL.
|
||||
const AP_Param::GroupInfo SITL::var_info2[] = {
|
||||
AP_GROUPINFO("TEMP_START", 1, SITL, temp_start, 25),
|
||||
AP_GROUPINFO("TEMP_FLIGHT", 2, SITL, temp_flight, 35),
|
||||
AP_GROUPINFO("TEMP_TCONST", 3, SITL, temp_tconst, 30),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -38,6 +38,7 @@ public:
|
||||
// set a default compass offset
|
||||
mag_ofs.set(Vector3f(5, 13, -18));
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
AP_Param::setup_object_defaults(this, var_info2);
|
||||
}
|
||||
|
||||
enum GPSType {
|
||||
@ -65,6 +66,7 @@ public:
|
||||
float height_agl;
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
static const struct AP_Param::GroupInfo var_info2[];
|
||||
|
||||
// noise levels for simulated sensors
|
||||
AP_Float baro_noise; // in metres
|
||||
@ -145,6 +147,11 @@ public:
|
||||
AP_Vector3f rngfnd_pos_offset; // XYZ position of the range finder zero range datum relative to the body frame origin (m)
|
||||
AP_Vector3f optflow_pos_offset; // XYZ position of the optical flow sensor focal point relative to the body frame origin (m)
|
||||
|
||||
// temperature control
|
||||
AP_Float temp_start;
|
||||
AP_Float temp_flight;
|
||||
AP_Float temp_tconst;
|
||||
|
||||
uint16_t irlock_port;
|
||||
|
||||
void simstate_send(mavlink_channel_t chan);
|
||||
|
Loading…
Reference in New Issue
Block a user