mirror of https://github.com/ArduPilot/ardupilot
SITL: add parameter MAG_DEVID in SITL
This commit is contained in:
parent
8d227d401a
commit
8a7dcafa0f
|
@ -217,10 +217,19 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
|
||||||
const AP_Param::GroupInfo SITL::var_info3[] = {
|
const AP_Param::GroupInfo SITL::var_info3[] = {
|
||||||
AP_GROUPINFO("ODOM_ENABLE", 1, SITL, odom_enable, 0),
|
AP_GROUPINFO("ODOM_ENABLE", 1, SITL, odom_enable, 0),
|
||||||
AP_GROUPINFO("GPS2_POS", 2, SITL, gps_pos_offset[1], 0),
|
AP_GROUPINFO("GPS2_POS", 2, SITL, gps_pos_offset[1], 0),
|
||||||
|
AP_GROUPINFO("MAG1_DEVID", 3, SITL, mag_devid[0], 97539),
|
||||||
|
AP_GROUPINFO("MAG2_DEVID", 4, SITL, mag_devid[1], 131874),
|
||||||
|
AP_GROUPINFO("MAG3_DEVID", 5, SITL, mag_devid[2], 263178),
|
||||||
|
AP_GROUPINFO("MAG4_DEVID", 6, SITL, mag_devid[3], 97283),
|
||||||
|
AP_GROUPINFO("MAG5_DEVID", 7, SITL, mag_devid[4], 97795),
|
||||||
|
AP_GROUPINFO("MAG6_DEVID", 8, SITL, mag_devid[5], 98051),
|
||||||
|
AP_GROUPINFO("MAG7_DEVID", 9, SITL, mag_devid[6], 0),
|
||||||
|
AP_GROUPINFO("MAG8_DEVID", 10, SITL, mag_devid[7], 0),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
/* report SITL state via MAVLink */
|
/* report SITL state via MAVLink */
|
||||||
void SITL::simstate_send(mavlink_channel_t chan)
|
void SITL::simstate_send(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
|
|
|
@ -7,7 +7,7 @@
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||||
#include <AP_Common/Location.h>
|
#include <AP_Common/Location.h>
|
||||||
|
#include <AP_Compass/AP_Compass.h>
|
||||||
#include "SIM_Buzzer.h"
|
#include "SIM_Buzzer.h"
|
||||||
#include "SIM_Gripper_EPM.h"
|
#include "SIM_Gripper_EPM.h"
|
||||||
#include "SIM_Gripper_Servo.h"
|
#include "SIM_Gripper_Servo.h"
|
||||||
|
@ -185,6 +185,7 @@ public:
|
||||||
AP_Int8 gps_hdg_enabled; // enable the output of a NMEA heading HDT sentence
|
AP_Int8 gps_hdg_enabled; // enable the output of a NMEA heading HDT sentence
|
||||||
AP_Int32 loop_delay; // extra delay to add to every loop
|
AP_Int32 loop_delay; // extra delay to add to every loop
|
||||||
AP_Float mag_scaling; // scaling factor on first compasses
|
AP_Float mag_scaling; // scaling factor on first compasses
|
||||||
|
AP_Int32 mag_devid[MAX_CONNECTED_MAGS]; // Mag devid
|
||||||
|
|
||||||
// EFI type
|
// EFI type
|
||||||
enum EFIType {
|
enum EFIType {
|
||||||
|
|
Loading…
Reference in New Issue