Skip to content

Commit

Permalink
added update magfield by distance
Browse files Browse the repository at this point in the history
  • Loading branch information
alireza787b committed Nov 30, 2023
1 parent e4d320e commit b9dece0
Show file tree
Hide file tree
Showing 7 changed files with 367 additions and 177 deletions.
38 changes: 17 additions & 21 deletions config/config.ini
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
; PX4-XPlane Configuration File
; File Version: 1.0
; File Version: 1.1
; Date Created: November 26, 2023
; This file configures the mapping of motor and servo channels from PX4 to X-Plane.

Expand All @@ -10,13 +10,16 @@
; - Ensure the mappings correspond to your specific setup.
; - Visit the GitHub repository (alireza787b/px4xplane) for more information and updates.

config_version= 1.1




; Configuration Name (Displayed in UI)
config_name = FixedWingTest

; Actuve Configuration Type to Load from below
active_config_type = FixedWing
config_version= 1.0


[Multirotor]
; This section defines the configuration for multirotor vehicles in the simulation.
Expand All @@ -39,26 +42,26 @@ motor4 = 4 ; PX4 Motor 4 mapped to X-Plane Motor 4
;... up to motor16



[FixedWing]
# Configuration for FixedWing channels. Each channel configuration includes:
# - Dataref: The data reference name in X-Plane.
# - Type: The data type (e.g., float, floatArray).
# - Array Indices: The indices for array data types (use 0 for non-array types).
# - Range: The range of values, specified as [min max] without a comma.
# Multiple datarefs for a single channel can be separated by a pipe (|).

# Aileron Left (Servo 1) (Usually seen from front of plane in X-Plane)
# Dataref: sim/flightmodel/controls/wing1l_ail1def is for visual only
# Dataref: sim/flightmodel/controls/lail1def
# Datarefs: sim/flightmodel/controls/wing2l_ail1def | sim/flightmodel/controls/wing1l_ail1def
# Type: float
# Range: [-20 15] (degrees of deflection)
channel0 = sim/flightmodel/controls/wing2l_ail1def , float, 0, [-20 15]
channel0 = sim/flightmodel/controls/wing2l_ail1def, float, 0, [-20 15] | sim/flightmodel/controls/wing1l_ail1def, float, 0, [-20 15]

# Aileron Right (Servo 2) (Usually seen from front of plane in X-Plane)
# Dataref: sim/flightmodel/controls/wing1r_ail1def is for visual only
# Dataref: sim/flightmodel/controls/rail1def
# Datarefs: sim/flightmodel/controls/wing2r_ail1def | sim/flightmodel/controls/wing1r_ail1def
# Type: float
# Range: [-20 15] (degrees of deflection)
channel1 = sim/flightmodel/controls/wing2r_ail1def , float, 0, [-20 15]
channel1 = sim/flightmodel/controls/wing2r_ail1def, float, 0, [-20 15] | sim/flightmodel/controls/wing1r_ail1def, float, 0, [-20 15]

# Elevator (Servo 3)
# Dataref: sim/flightmodel/controls/hstab1_elv1def
Expand All @@ -72,15 +75,8 @@ channel2 = sim/flightmodel/controls/hstab1_elv1def, float, 0, [-20 15]
# Range: [-1 1] (idle (0) to full throttle Foreward (+1) )
channel3 = sim/flightmodel/engine/ENGN_thro_use, floatArray, [0], [-1 1]

# Rudder (Servo 4)
# Dataref: sim/flightmodel/controls/vstab1_rud1def
# Type: float
# Range: [-20 20] (degrees of deflection)
channel4 = sim/flightmodel/controls/vstab1_rud1def, float, 0, [-20 20]


# Steering Gear (Servo 4 same with rudder)
# Dataref: sim/flightmodel2/gear/tire_steer_command_deg
# Type: floatArray
# Range: [-10 10] (degrees of steering)
channel5 = sim/flightmodel2/gear/tire_steer_command_deg, floatArray, [0], [-10 10]
# Rudder and Steering Gear (Servo 4)
# Datarefs: sim/flightmodel/controls/vstab1_rud1def | sim/flightmodel2/gear/tire_steer_command_deg
# Type: float | floatArray
# Range: [-20 20] (degrees of deflection) | [-10 10] (degrees of steering)
channel4 = sim/flightmodel/controls/vstab1_rud1def, float, 0, [-20 20] | sim/flightmodel2/gear/tire_steer_command_deg, floatArray, [0], [-10 10]
54 changes: 50 additions & 4 deletions include/ConfigManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,15 +8,61 @@
#include <vector>
#include "SimpleIni.h"

/**
* Enumeration of actuator data types.
* This enumeration defines the types of data that can be associated with an actuator.
* - UNKNOWN: Represents an undefined or unrecognized data type.
* - FLOAT_SINGLE: Represents a single floating-point value.
* - FLOAT_ARRAY: Represents an array of floating-point values.
* This is used to specify how the actuator data should be interpreted and processed.
*/
enum ActuatorDataType { UNKNOWN, FLOAT_SINGLE, FLOAT_ARRAY };

struct ActuatorConfig {
/**
* Structure representing the configuration of a single data reference (dataref).
* This structure encapsulates all the necessary information for configuring a dataref associated with an actuator.
* - datarefName: The name of the dataref.
* - dataType: The type of data (e.g., single float, array of floats).
* - arrayIndices: Indices in the case of an array data type.
* - range: The range of values that the actuator can accept.
*
* The constructor initializes the structure with the provided values.
*/
struct DatarefConfig {
std::string datarefName;
ActuatorDataType dataType;
std::vector<int> arrayIndices;
std::pair<float, float> range;

DatarefConfig(const std::string& name, ActuatorDataType type, const std::vector<int>& indices, const std::pair<float, float>& rng)
: datarefName(name), dataType(type), arrayIndices(indices), range(rng) {}
};

/**
* Structure representing the configuration of an actuator.
* This structure holds a collection of DatarefConfig objects, each representing a specific data reference configuration.
* Actuators in a simulation environment can be associated with multiple data references, each potentially having different
* data types, indices, and value ranges.
*
* - datarefs: A vector of DatarefConfig objects.
*
* The addDatarefConfig method allows adding a new DatarefConfig to the actuator configuration.
* The getDatarefConfigs method provides access to the stored DatarefConfig objects.
*/
struct ActuatorConfig {
std::vector<DatarefConfig> datarefs;

void addDatarefConfig(const DatarefConfig& config) {
datarefs.push_back(config);
}

const std::vector<DatarefConfig>& getDatarefConfigs() const {
return datarefs;
}
};



class ConfigManager {
public:
static void loadConfiguration();
Expand All @@ -41,10 +87,10 @@ class ConfigManager {
static void parseFixedWingConfig(CSimpleIniA& ini) ;
static void parseMultirotorConfig(CSimpleIniA& ini) ;
static ActuatorDataType stringToDataType(const std::string& typeStr);
static void ConfigManager::parseArrayIndices(const std::string& token, ActuatorConfig& config);
static void ConfigManager::parseRange(const std::string& token, ActuatorConfig& config);
static std::vector<int> ConfigManager::parseArrayIndices(const std::string& token);
static std::pair<float, float> ConfigManager::parseRange(const std::string& token);
static void ConfigManager::parseChannelValue(const std::string& value, ActuatorConfig& config);
static void ConfigManager::trimWhitespace(std::string& str);
static void ConfigManager::trimWhitespace(std::string& str);



Expand Down
20 changes: 17 additions & 3 deletions include/DataRefManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,14 @@ struct DataRefItem {
std::function<std::vector<float>(const char*)>> getter;
};

struct GeodeticPosition {
float latitude;
float longitude;
float altitude;
};



class DataRefManager {
public:
static constexpr float g_earth = 9.81f;
Expand All @@ -53,12 +61,18 @@ class DataRefManager {
static void enableOverride();
static void disableOverride();
static int drawActualThrottle(XPLMWindowID in_window_id, int l, int t, float col_white[], int lineOffset);
static Eigen::Vector3f updateEarthMagneticFieldNED(float lat, float lon, float alt);
static Eigen::Vector3f updateEarthMagneticFieldNED(const GeodeticPosition& position);
static float calculateDistance(const GeodeticPosition& pos1, const GeodeticPosition& pos2);
static Eigen::Vector3f convertNEDToBody(const Eigen::Vector3f& nedVector, float roll, float pitch, float yaw);
static void initializeMagneticField();
static std::string GetFormattedDroneConfig();
static float DataRefManager::scaleActuatorCommand(float input, float inputMin, float inputMax, float outputMin, float outputMax);

static std::string GetFormattedDroneConfig();
static float scaleActuatorCommand(float input, float inputMin, float inputMax, float outputMin, float outputMax);

static float lastLatitude;
static float lastLongitude;
static float lastAltitude;
static GeodeticPosition lastPosition;
static constexpr float UPDATE_THRESHOLD=1000; // Define a threshold for position change in meters
};

2 changes: 2 additions & 0 deletions include/MAVLinkManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,5 +44,7 @@ class MAVLinkManager {
static void populateHILStateQuaternion(mavlink_hil_state_quaternion_t& hil_state);
static void sendData(const mavlink_message_t& msg);
static uint16_t mapRCChannel(float value, float min, float max);
static void MAVLinkManager::updateMagneticFieldIfExceededTreshold(const mavlink_hil_gps_t& hil_gps);


};
Loading

0 comments on commit b9dece0

Please sign in to comment.