Skip to content

Commit

Permalink
paramfile version2
Browse files Browse the repository at this point in the history
  • Loading branch information
alireza787b committed Nov 12, 2023
1 parent b963ea3 commit e0801d6
Show file tree
Hide file tree
Showing 11 changed files with 344 additions and 152 deletions.
54 changes: 46 additions & 8 deletions config/config.ini
Original file line number Diff line number Diff line change
@@ -1,8 +1,46 @@
[Motors]
# This section defines the mapping between PX4 and X-Plane motors.
# Each line should be in the format "PX4_X = Y", where X is the PX4 motor number and Y is the corresponding X-Plane motor number.
# CW/CCW of the px4 motors and xplane motors should match (FWD_RIGHT and BACK_LEFT: CCW) (FWD_LEFT and BACK_RIGHT: CW)
PX4_1 = 4
PX4_2 = 1
PX4_3 = 3
PX4_4 = 2
; PX4-XPlane Configuration File
; File Version: 1.0
; Date Created: November 10, 2023
; This file configures the mapping of motor and servo channels from PX4 to X-Plane.

; General Instructions:
; - Specify the configuration name for UI display.
; - Set 'num_motors' for multirotors and provide motor mappings.
; - For fixed-wing configurations, this section is a placeholder and currently not supported.
; - Ensure the mappings correspond to your specific setup.
; - Visit the GitHub repository (alireza787b/px4xplane) for more information and updates.

; Configuration Name (Displayed in UI)
config_name = Quadricopter Air Taxi

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


[Multirotor]
; Default configuration for a standard quadcopter.
; Number of motors in your multirotor setup.
num_motors = 4 ; Change this number based on your setup.

; Motor Mappings: PX4 motor number = X-Plane motor number
; The following is the default setup for a Quadricopter. You can modify these mappings as needed.
; The Rotaion direction (CW & CCW) of motors should be compatible with PX4.
motor1 = 1
motor2 = 2
motor3 = 3
motor4 = 4
;motor5 =
;motor6 =
;... up to motor16

[FixedWing]
; Placeholder for future fixed-wing configurations.
; This section is not yet supported but will be available in future updates.
; Stay tuned for updates on the GitHub repository.

; Additional notes:
; - The version number at the top of this file helps track changes and compatibility.
; - The configuration name helps users verify that the correct configuration is loaded in the UI.
; - Detailed documentation and examples for various configurations are available in the GitHub repository.
; - For any issues or feature requests, please open an issue on GitHub.
59 changes: 30 additions & 29 deletions config/quadricopter_px4.params
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
#
# Stack: PX4 Pro
# Vehicle: Multi-Rotor
# Version: 1.15.0 dev
# Git Revision: 22ee90b7d7000000
# Version: 1.15.0 alpha
# Git Revision: 1592aedc11000000
#
# Vehicle-Id Component-Id Name Value Type
1 1 ASPD_SCALE_1 1.000000000000000000 9
Expand All @@ -25,11 +25,11 @@
1 1 CAL_ACC0_ID 1310988 6
1 1 CAL_ACC0_PRIO 50 6
1 1 CAL_ACC0_ROT -1 6
1 1 CAL_ACC0_XOFF -0.098337166011333466 9
1 1 CAL_ACC0_XOFF 0.092552497982978821 9
1 1 CAL_ACC0_XSCALE 1.000000000000000000 9
1 1 CAL_ACC0_YOFF 0.003198791295289993 9
1 1 CAL_ACC0_YOFF 0.002633769065141678 9
1 1 CAL_ACC0_YSCALE 1.000000000000000000 9
1 1 CAL_ACC0_ZOFF 0.004741855431348085 9
1 1 CAL_ACC0_ZOFF 0.000934728712309152 9
1 1 CAL_ACC0_ZSCALE 1.000000000000000000 9
1 1 CAL_ACC1_ID 1310996 6
1 1 CAL_ACC1_PRIO -1 6
Expand Down Expand Up @@ -83,16 +83,16 @@
1 1 CAL_MAG0_ROT -1 6
1 1 CAL_MAG0_XCOMP 0.000000000000000000 9
1 1 CAL_MAG0_XODIAG 0.000000000000000000 9
1 1 CAL_MAG0_XOFF 0.014998760074377060 9
1 1 CAL_MAG0_XOFF -0.004175098147243261 9
1 1 CAL_MAG0_XSCALE 1.000000000000000000 9
1 1 CAL_MAG0_YAW 0.000000000000000000 9
1 1 CAL_MAG0_YCOMP 0.000000000000000000 9
1 1 CAL_MAG0_YODIAG 0.000000000000000000 9
1 1 CAL_MAG0_YOFF -0.005241870414465666 9
1 1 CAL_MAG0_YOFF 0.007193128578364849 9
1 1 CAL_MAG0_YSCALE 1.000000000000000000 9
1 1 CAL_MAG0_ZCOMP 0.000000000000000000 9
1 1 CAL_MAG0_ZODIAG 0.000000000000000000 9
1 1 CAL_MAG0_ZOFF 0.034636233001947403 9
1 1 CAL_MAG0_ZOFF 0.354712426662445068 9
1 1 CAL_MAG0_ZSCALE 1.000000000000000000 9
1 1 CAL_MAG1_ID 197644 6
1 1 CAL_MAG1_PITCH 0.000000000000000000 9
Expand Down Expand Up @@ -137,9 +137,9 @@
1 1 CA_ROTOR0_AY 0.000000000000000000 9
1 1 CA_ROTOR0_AZ -1.000000000000000000 9
1 1 CA_ROTOR0_CT 6.500000000000000000 9
1 1 CA_ROTOR0_KM 0.050000000745058060 9
1 1 CA_ROTOR0_PX 0.151500001549720764 9
1 1 CA_ROTOR0_PY 0.245000004768371582 9
1 1 CA_ROTOR0_KM -0.050000000745058060 9
1 1 CA_ROTOR0_PX 1.399999976158142090 9
1 1 CA_ROTOR0_PY -1.399999976158142090 9
1 1 CA_ROTOR0_PZ 0.000000000000000000 9
1 1 CA_ROTOR10_AX 0.000000000000000000 9
1 1 CA_ROTOR10_AY 0.000000000000000000 9
Expand All @@ -162,24 +162,24 @@
1 1 CA_ROTOR1_AZ -1.000000000000000000 9
1 1 CA_ROTOR1_CT 6.500000000000000000 9
1 1 CA_ROTOR1_KM 0.050000000745058060 9
1 1 CA_ROTOR1_PX -0.151500001549720764 9
1 1 CA_ROTOR1_PY -0.187500000000000000 9
1 1 CA_ROTOR1_PX 1.399999976158142090 9
1 1 CA_ROTOR1_PY 1.399999976158142090 9
1 1 CA_ROTOR1_PZ 0.000000000000000000 9
1 1 CA_ROTOR2_AX 0.000000000000000000 9
1 1 CA_ROTOR2_AY 0.000000000000000000 9
1 1 CA_ROTOR2_AZ -1.000000000000000000 9
1 1 CA_ROTOR2_CT 6.500000000000000000 9
1 1 CA_ROTOR2_KM -0.050000000745058060 9
1 1 CA_ROTOR2_PX 0.151500001549720764 9
1 1 CA_ROTOR2_PY -0.245000004768371582 9
1 1 CA_ROTOR2_KM 0.050000000745058060 9
1 1 CA_ROTOR2_PX -1.399999976158142090 9
1 1 CA_ROTOR2_PY -1.399999976158142090 9
1 1 CA_ROTOR2_PZ 0.000000000000000000 9
1 1 CA_ROTOR3_AX 0.000000000000000000 9
1 1 CA_ROTOR3_AY 0.000000000000000000 9
1 1 CA_ROTOR3_AZ -1.000000000000000000 9
1 1 CA_ROTOR3_CT 6.500000000000000000 9
1 1 CA_ROTOR3_KM -0.050000000745058060 9
1 1 CA_ROTOR3_PX -0.151500001549720764 9
1 1 CA_ROTOR3_PY 0.187500000000000000 9
1 1 CA_ROTOR3_PX -1.399999976158142090 9
1 1 CA_ROTOR3_PY 1.399999976158142090 9
1 1 CA_ROTOR3_PZ 0.000000000000000000 9
1 1 CA_ROTOR4_AX 0.000000000000000000 9
1 1 CA_ROTOR4_AY 0.000000000000000000 9
Expand Down Expand Up @@ -273,7 +273,7 @@
1 1 COM_DISARM_PRFLT 10.000000000000000000 9
1 1 COM_DL_LOSS_T 10 6
1 1 COM_FAIL_ACT_T 5.000000000000000000 9
1 1 COM_FLIGHT_UUID 8 6
1 1 COM_FLIGHT_UUID 3 6
1 1 COM_FLTMODE1 -1 6
1 1 COM_FLTMODE2 -1 6
1 1 COM_FLTMODE3 -1 6
Expand Down Expand Up @@ -314,6 +314,7 @@
1 1 COM_TAKEOFF_ACT 0 6
1 1 COM_VEL_FS_EVH 1.000000000000000000 9
1 1 COM_WIND_MAX -1.000000000000000000 9
1 1 COM_WIND_MAX_ACT 0 6
1 1 COM_WIND_WARN -1.000000000000000000 9
1 1 CP_DELAY 0.400000005960464478 9
1 1 CP_DIST -1.000000000000000000 9
Expand Down Expand Up @@ -387,7 +388,7 @@
1 1 EKF2_MAG_CHECK 1 6
1 1 EKF2_MAG_CHK_INC 20.000000000000000000 9
1 1 EKF2_MAG_CHK_STR 0.200000002980232239 9
1 1 EKF2_MAG_DECL 2.794761419296264648 9
1 1 EKF2_MAG_DECL 2.795423984527587891 9
1 1 EKF2_MAG_DELAY 0.000000000000000000 9
1 1 EKF2_MAG_E_NOISE 0.001000000047497451 9
1 1 EKF2_MAG_GATE 3.000000000000000000 9
Expand Down Expand Up @@ -515,7 +516,7 @@
1 1 LNDMC_XY_VEL_MAX 1.500000000000000000 9
1 1 LNDMC_Z_VEL_MAX 0.250000000000000000 9
1 1 LND_FLIGHT_T_HI 0 6
1 1 LND_FLIGHT_T_LO 1736953736 6
1 1 LND_FLIGHT_T_LO 1502311844 6
1 1 MAN_ARM_GESTURE 1 6
1 1 MAV_COMP_ID 1 6
1 1 MAV_FWDEXTSP 1 6
Expand Down Expand Up @@ -554,20 +555,20 @@
1 1 MC_ROLLRATE_D 0.009999999776482582 9
1 1 MC_ROLLRATE_FF 0.000000000000000000 9
1 1 MC_ROLLRATE_I 0.100000001490116119 9
1 1 MC_ROLLRATE_K 3.000000000000000000 9
1 1 MC_ROLLRATE_K 2.250000000000000000 9
1 1 MC_ROLLRATE_MAX 220.000000000000000000 9
1 1 MC_ROLLRATE_P 0.150000005960464478 9
1 1 MC_ROLL_P 1.000000000000000000 9
1 1 MC_RR_INT_LIM 0.300000011920928955 9
1 1 MC_YAWRATE_D 2.000000000000000000 9
1 1 MC_YAWRATE_FF 0.000000000000000000 9
1 1 MC_YAWRATE_I 0.000000000000000000 9
1 1 MC_YAWRATE_K 0.899999976158142090 9
1 1 MC_YAWRATE_K 0.600000023841857910 9
1 1 MC_YAWRATE_MAX 200.000000000000000000 9
1 1 MC_YAWRATE_P 0.200000002980232239 9
1 1 MC_YAWRATE_P 1.000000000000000000 9
1 1 MC_YAW_P 1.000000000000000000 9
1 1 MC_YAW_WEIGHT 0.400000005960464478 9
1 1 MC_YR_INT_LIM 0.300000011920928955 9
1 1 MC_YR_INT_LIM 0.100000001490116119 9
1 1 MIS_DIST_1WP 900.000000000000000000 9
1 1 MIS_LND_ABRT_ALT 30 6
1 1 MIS_MNT_YAW_CTL 0 6
Expand Down Expand Up @@ -614,16 +615,16 @@
1 1 MPC_VEL_MANUAL 10.000000000000000000 9
1 1 MPC_VEL_MAN_BACK -1.000000000000000000 9
1 1 MPC_VEL_MAN_SIDE -1.000000000000000000 9
1 1 MPC_XY_CRUISE 5.000000000000000000 9
1 1 MPC_XY_CRUISE 12.000000000000000000 9
1 1 MPC_XY_ERR_MAX 2.000000000000000000 9
1 1 MPC_XY_MAN_EXPO 0.600000023841857910 9
1 1 MPC_XY_P 0.200000002980232239 9
1 1 MPC_XY_P 0.050000000745058060 9
1 1 MPC_XY_TRAJ_P 0.500000000000000000 9
1 1 MPC_XY_VEL_ALL -10.000000000000000000 9
1 1 MPC_XY_VEL_D_ACC 0.699999988079071045 9
1 1 MPC_XY_VEL_D_ACC 1.500000000000000000 9
1 1 MPC_XY_VEL_I_ACC 0.200000002980232239 9
1 1 MPC_XY_VEL_MAX 12.000000000000000000 9
1 1 MPC_XY_VEL_P_ACC 1.950000047683715820 9
1 1 MPC_XY_VEL_P_ACC 1.200000047683715820 9
1 1 MPC_YAWRAUTO_MAX 45.000000000000000000 9
1 1 MPC_YAW_EXPO 0.600000023841857910 9
1 1 MPC_YAW_MODE 0 6
Expand Down
29 changes: 29 additions & 0 deletions include/ConfigManager.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
// ConfigManager.h

#ifndef CONFIGMANAGER_H
#define CONFIGMANAGER_H

#include <string>
#include <map>

class ConfigManager {
public:
static void loadConfiguration();
static int getPX4MotorFromXPlane(int xPlaneMotorNumber);
static int getXPlaneMotorFromPX4(int px4MotorNumber);

static std::string getConfigName();
static std::string getConfigVersion();
static std::string getConfigType();

private:
static std::map<int, int> motorMappingsPX4toXPlane;
static std::map<int, int> motorMappingsXPlanetoPX4;
static std::string configName;
static std::string configVersion;
static std::string configType; // "Multirotor" or "FixedWing"

static std::string getConfigFilePath();
};

#endif // CONFIGMANAGER_H
4 changes: 2 additions & 2 deletions include/DataRefManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,14 +40,13 @@ class DataRefManager {
static Eigen::Vector3f earthMagneticFieldNED;


static void drawDataRefs(XPLMWindowID in_window_id, int l, int t, float col_white[], int lineOffset);
static int drawDataRefs(XPLMWindowID in_window_id, int l, int t, float col_white[], int lineOffset);
static std::vector<float> getFloatArray(const char* dataRefName);
static float getFloat(const char* dataRef);
static int getInt(const char* dataRef);
static double getDouble(const char* dataRef);
static std::string arrayToString(const std::vector<float>& array); // add this line
static float mapChannelValue(float value, float minInput, float maxInput, float minOutput, float maxOutput);
static std::tuple<float, float, float> convertOGLtoNED(float ogl_vx, float ogl_vy, float ogl_vz, float roll_rad, float pitch_rad, float yaw_rad);
static int drawActuatorControls(XPLMWindowID in_window_id, int l, int t, float col_white[], int lineOffset);
static void overrideActuators();
static void enableOverride();
Expand All @@ -56,6 +55,7 @@ class DataRefManager {
static Eigen::Vector3f updateEarthMagneticFieldNED(float lat, float lon, float alt);
static Eigen::Vector3f convertNEDToBody(const Eigen::Vector3f& nedVector, float roll, float pitch, float yaw);
static void initializeMagneticField();
static std::string GetFormattedDroneConfig();


};
Expand Down
1 change: 0 additions & 1 deletion include/MAVLinkManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@ class MAVLinkManager {
static void setPressureData(mavlink_hil_sensor_t& hil_sensor);
static void setMagneticFieldData(mavlink_hil_sensor_t& hil_sensor);
static void receiveHILActuatorControls(uint8_t* buffer, int size);
static Eigen::Vector3f calculateMagneticVector(float latitude, float longitude, float altitude, float roll_rad, float pitch_rad, float yaw_rad);

struct HILActuatorControlsData {
uint64_t timestamp;
Expand Down
7 changes: 5 additions & 2 deletions px4-xplane.vcxproj
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@
<TargetName>win</TargetName>
<IncludePath>C:\Users\Alireza\source\repos\px4xplane\include;C:\Users\Alireza\vcpkg\installed\x64-windows\include;C:\Users\Alireza\source\repos\px4xplane\lib\SDK\CHeaders\XPLM;$(IncludePath)</IncludePath>
<LibraryPath>C:\Users\Alireza\source\repos\px4xplane\lib;C:\Users\Alireza\vcpkg\installed\x64-windows\lib;C:\Users\Alireza\GeographicLib\lib;C:\Users\Alireza\source\repos\px4xplane\lib\SDK\Libraries\Win;$(LibraryPath)</LibraryPath>
<ExternalIncludePath>C:\Users\Alireza\GeographicLib\include\GeographicLib;$(ExternalIncludePath)</ExternalIncludePath>
<ExternalIncludePath>C:\Users\Alireza\source\repos\px4xplane\lib\simpleini;$(ExternalIncludePath)</ExternalIncludePath>
<SourcePath>C:\Users\Alireza\source\repos\px4xplane\src;$(SourcePath)</SourcePath>
</PropertyGroup>
<PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|x64'">
Expand Down Expand Up @@ -108,7 +108,8 @@
<AdditionalDependencies>Opengl32.lib;odbc32.lib;odbccp32.lib;XPLM_64.lib;XPWidgets_64.lib;%(AdditionalDependencies)</AdditionalDependencies>
</Link>
<PostBuildEvent>
<Command>copy "$(ProjectDir)config\config.ini" "$(OutDir)"</Command>
<Command>copy "$(ProjectDir)config\config.ini" "$(OutDir)"
copy "$(ProjectDir)config\quadricopter_px4.params" "$(OutDir)"</Command>
</PostBuildEvent>
</ItemDefinitionGroup>
<ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Debug|x64'">
Expand Down Expand Up @@ -156,6 +157,7 @@
</Link>
</ItemDefinitionGroup>
<ItemGroup>
<ClCompile Include="src\ConfigManager.cpp" />
<ClCompile Include="src\configReader.cpp" />
<ClCompile Include="src\ConnectionManager.cpp" />
<ClCompile Include="src\DataRefManager.cpp" />
Expand All @@ -164,6 +166,7 @@
</ItemGroup>
<ItemGroup>
<ClInclude Include="config\ini.h" />
<ClInclude Include="include\ConfigManager.h" />
<ClInclude Include="include\configReader.h" />
<ClInclude Include="include\ConnectionManager.h" />
<ClInclude Include="include\DataRefManager.h" />
Expand Down
Loading

0 comments on commit e0801d6

Please sign in to comment.