Skip to content

Commit

Permalink
working fixedWing
Browse files Browse the repository at this point in the history
  • Loading branch information
alireza787b committed Nov 29, 2023
1 parent 86922a1 commit b610939
Show file tree
Hide file tree
Showing 5 changed files with 33 additions and 32 deletions.
16 changes: 9 additions & 7 deletions config/config.ini
Original file line number Diff line number Diff line change
Expand Up @@ -46,17 +46,19 @@ motor4 = 4 ; PX4 Motor 4 mapped to X-Plane Motor 4
# - 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.

# Aileron Left (Servo 1)
# Dataref: sim/flightmodel/controls/wing1l_ail1def
# 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
# Type: float
# Range: [-20 15] (degrees of deflection)
channel0 = sim/flightmodel/controls/wing1l_ail1def, float, 0, [-20 15]
channel0 = sim/flightmodel/controls/wing2l_ail1def , float, 0, [-20 15]

# Aileron Right (Servo 2)
# Dataref: sim/flightmodel/controls/wing1r_ail1def
# 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
# Type: float
# Range: [-20 15] (degrees of deflection)
channel1 = sim/flightmodel/controls/wing1r_ail1def, float, 0, [-20 15]
channel1 = sim/flightmodel/controls/wing2r_ail1def , float, 0, [-20 15]

# Elevator (Servo 3)
# Dataref: sim/flightmodel/controls/hstab1_elv1def
Expand All @@ -65,7 +67,7 @@ channel1 = sim/flightmodel/controls/wing1r_ail1def, float, 0, [-20 15]
channel2 = sim/flightmodel/controls/hstab1_elv1def, float, 0, [-20 15]

# Throttle (Motor 1)
# Dataref: sim/flightmodel/engine/ENGN_thro_use (array indices (+1) is the engine number)
# Dataref: sim/flightmodel/engine/ENGN_thro_use ([array indices + 1] is the engine number)
# Type: floatArray
# Range: [-1 1] (idle (0) to full throttle Foreward (+1) )
channel3 = sim/flightmodel/engine/ENGN_thro_use, floatArray, [0], [-1 1]
Expand Down
2 changes: 1 addition & 1 deletion src/ConfigManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,7 +185,7 @@ void ConfigManager::parseMultirotorConfig(CSimpleIniA& ini) {
void ConfigManager::parseFixedWingConfig(CSimpleIniA& ini) {
XPLMDebugString("px4xplane: Starting to parse FixedWing configuration.\n");

for (int channel = 0; channel < 16; ++channel) {
for (int channel = 0; channel < 16; channel++) {
std::string key = "channel" + std::to_string(channel);
std::string value = ini.GetValue("FixedWing", key.c_str(), "");

Expand Down
13 changes: 5 additions & 8 deletions src/DataRefManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,9 +134,9 @@ Eigen::Vector3f DataRefManager::updateEarthMagneticFieldNED(float lat, float lon
float lonRad = lon * M_PI / 180.0;

// Log the input values
char log[256];
/*char log[256];
sprintf(log, "updateEarthMagneticFieldNED called with lat: %f, lon: %f, alt: %f\n", lat, lon, alt);
XPLMDebugString(log);
XPLMDebugString(log);*/

geomag::Vector position = geomag::geodetic2ecef(lat, lon, alt);
geomag::Vector mag_field = geomag::GeoMag(2022.5, position, geomag::WMM2020);
Expand All @@ -145,8 +145,8 @@ Eigen::Vector3f DataRefManager::updateEarthMagneticFieldNED(float lat, float lon
earthMagneticFieldNED = Eigen::Vector3f(nedElements.north, nedElements.east, nedElements.down);

// Log the calculated magnetic field
sprintf(log, "Calculated magnetic field NED: north: %f, east: %f, down: %f\n", nedElements.north, nedElements.east, nedElements.down);
XPLMDebugString(log);
/*sprintf(log, "Calculated magnetic field NED: north: %f, east: %f, down: %f\n", nedElements.north, nedElements.east, nedElements.down);
XPLMDebugString(log)*/;

earthMagneticFieldNED *= 0.00001; // Convert from nT to Gauss

Expand Down Expand Up @@ -390,10 +390,7 @@ void DataRefManager::overrideActuators_multirotor() {
if (xplaneMotor != -1) { // Check if mapping exists
correctedControls.controls[xplaneMotor - 1] = hilControls.controls[i];

// Debug print
char debugMsg[100];
snprintf(debugMsg, sizeof(debugMsg), "PX4 Motor %d -> X-Plane Motor %d\n", i + 1, xplaneMotor);
XPLMDebugString(debugMsg);

}
}

Expand Down
28 changes: 15 additions & 13 deletions src/MAVLinkManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -478,7 +478,7 @@ void MAVLinkManager::setMagneticFieldData(mavlink_hil_sensor_t& hil_sensor) {
*/
void MAVLinkManager::setGPSTimeAndFix(mavlink_hil_gps_t& hil_gps) {
hil_gps.time_usec = static_cast<uint64_t>(DataRefManager::getFloat("sim/time/total_flight_time_sec") * 1e6);
hil_gps.fix_type = 3; // Assuming always a 3D fix in the simulation environment
hil_gps.fix_type = static_cast<uint8_t>(3); // Assuming always a 3D fix in the simulation environment
}

/**
Expand All @@ -498,9 +498,9 @@ void MAVLinkManager::setGPSPositionData(mavlink_hil_gps_t& hil_gps) {
* @param hil_gps Reference to the mavlink_hil_gps_t structure to populate.
*/
void MAVLinkManager::setGPSAccuracyData(mavlink_hil_gps_t& hil_gps) {
hil_gps.eph = 20; // Assuming high accuracy due to simulation environment
hil_gps.epv = 20;
hil_gps.satellites_visible = 12; // Assuming 12 satellites visible in good conditions
hil_gps.eph = static_cast<uint16_t>(20); // Assuming high accuracy due to simulation environment
hil_gps.epv = static_cast<uint16_t>(20);
hil_gps.satellites_visible = static_cast<uint16_t>(14);; // Assuming 12 satellites visible in good conditions
}

/**
Expand All @@ -512,9 +512,9 @@ void MAVLinkManager::setGPSAccuracyData(mavlink_hil_gps_t& hil_gps) {
* @param hil_gps Reference to the mavlink_hil_gps_t structure to populate.
*/
void MAVLinkManager::setGPSVelocityData(mavlink_hil_gps_t& hil_gps) {
float ogl_vx = DataRefManager::getFloat("sim/flightmodel/position/local_vx") * 100;
float ogl_vy = DataRefManager::getFloat("sim/flightmodel/position/local_vy") * 100;
float ogl_vz = DataRefManager::getFloat("sim/flightmodel/position/local_vz") * 100;
int16_t ogl_vx = DataRefManager::getFloat("sim/flightmodel/position/local_vx") * 100;
int16_t ogl_vy = DataRefManager::getFloat("sim/flightmodel/position/local_vy") * 100;
int16_t ogl_vz = DataRefManager::getFloat("sim/flightmodel/position/local_vz") * 100;

// Coordinate Transformation:
// The local OGL (OpenGL) coordinate system in the simulation environment is defined as:
Expand All @@ -532,10 +532,10 @@ void MAVLinkManager::setGPSVelocityData(mavlink_hil_gps_t& hil_gps) {
// NED East (Y) = OGL East (X)
// NED Down (Z) = -OGL Up (Y)

hil_gps.vn = -1 * ogl_vz;
hil_gps.ve = ogl_vx;
hil_gps.vd = -1 * ogl_vy;
hil_gps.vel = DataRefManager::getFloat("sim/flightmodel/position/groundspeed") * 100;
hil_gps.vn = static_cast<int16_t> ( - 1 * ogl_vz);
hil_gps.ve = static_cast<int16_t>(ogl_vx);
hil_gps.vd = static_cast<int16_t>(-1 * ogl_vy);
hil_gps.vel = static_cast<uint16_t>(DataRefManager::getFloat("sim/flightmodel/position/groundspeed") * 100);
}

/**
Expand All @@ -544,6 +544,8 @@ void MAVLinkManager::setGPSVelocityData(mavlink_hil_gps_t& hil_gps) {
* @param hil_gps Reference to the mavlink_hil_gps_t structure to populate.
*/
void MAVLinkManager::setGPSHeadingData(mavlink_hil_gps_t& hil_gps) {
hil_gps.cog = static_cast<uint16_t>(DataRefManager::getFloat("sim/cockpit2/gauges/indicators/ground_track_mag_copilot") * 100);
hil_gps.yaw = DataRefManager::getFloat("sim/flightmodel/position/mag_psi") * 100;
uint16_t cog = static_cast<uint16_t>(DataRefManager::getFloat("sim/cockpit2/gauges/indicators/ground_track_mag_copilot") * 100);
hil_gps.cog = (cog == 0) ? 360 : cog;
uint16_t yaw = static_cast<uint16_t>(DataRefManager::getFloat("sim/flightmodel/position/psi") * 100);
hil_gps.yaw = (yaw == 0) ? 360 : yaw;
}
6 changes: 3 additions & 3 deletions src/px4xplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -296,16 +296,16 @@ float MyFlightLoopCallback(float inElapsedSinceLastCall, float inElapsedTimeSinc
// Call MAVLinkManager::sendHILSensor() to send HIL_SENSOR data
MAVLinkManager::sendHILSensor(uint8_t(0));
MAVLinkManager::sendHILGPS();
MAVLinkManager::sendHILStateQuaternion();
MAVLinkManager::sendHILRCInputs();
//MAVLinkManager::sendHILStateQuaternion();
//MAVLinkManager::sendHILRCInputs();

ConnectionManager::receiveData();

// Check the configuration type and call the appropriate actuator override function
if (ConfigManager::getConfigTypeCode() == 1) {
// Multirotor configuration
DataRefManager::overrideActuators_multirotor();
} else if (ConfigManager::getConfigTypeCode() == 2) {
} else {
// Fixed-wing configuration
DataRefManager::overrideActuators_fixedwing();
}
Expand Down

0 comments on commit b610939

Please sign in to comment.