Skip to content

Commit

Permalink
unstable flight (possible motor combination) and magnetometer problem…
Browse files Browse the repository at this point in the history
… only
  • Loading branch information
alireza787b committed Oct 16, 2023
1 parent 37deefe commit fa793e4
Show file tree
Hide file tree
Showing 5 changed files with 24 additions and 5 deletions.
9 changes: 7 additions & 2 deletions ConnectionManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@

#include <fstream>
#include <sstream>
#include "DataRefManager.h"


static bool connected = false;
Expand Down Expand Up @@ -101,6 +102,7 @@ void ConnectionManager::acceptConnection() {
connected = true;
status = "Connected";
setLastMessage("Connected to SITL successfully.");
DataRefManager::enableOverride();
//motorMappings = loadMotorMappings("config.ini");
// Hard-coded motor mappings
motorMappings[1] = 4;
Expand Down Expand Up @@ -177,6 +179,7 @@ void ConnectionManager::disconnect() {
sockfd = -1;
closeSocket(newsockfd); // Close the newsockfd
newsockfd = -1;
DataRefManager::disableOverride();
connected = false;
status = "Disconnected";
setLastMessage("Disconnected from SITL.");
Expand Down Expand Up @@ -258,12 +261,14 @@ void ConnectionManager::receiveData() {
int bytesReceived = recv(newsockfd, reinterpret_cast<char*>(buffer), sizeof(buffer) - 1, 0);
if (bytesReceived < 0) {
XPLMDebugString("px4xplane: Error receiving data\n");
setLastMessage("Error receiving from PX4!"); // Store the received message

}
else if (bytesReceived > 0) {
buffer[bytesReceived] = '\0'; // Null-terminate the received data
setLastMessage(reinterpret_cast<char*>(buffer)); // Store the received message
setLastMessage("Receiving from PX4!"); // Store the received message
//XPLMDebugString("px4xplane: Data received: ");
XPLMDebugString(reinterpret_cast<char*>(buffer)); // Write the received message to the X-Plane log
//XPLMDebugString(reinterpret_cast<char*>(buffer)); // Write the received message to the X-Plane log

// Call MAVLinkManager::receiveHILActuatorControls() function here
MAVLinkManager::receiveHILActuatorControls(buffer, bytesReceived);
Expand Down
13 changes: 12 additions & 1 deletion DataRefManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,7 @@ std::tuple<float, float, float> DataRefManager::convertOGLtoNED(float ogl_vx, fl
R[0][1] = cos(yaw_rad) * sin(pitch_rad) * sin(roll_rad) - sin(yaw_rad) * cos(roll_rad);
R[0][2] = cos(yaw_rad) * sin(pitch_rad) * cos(roll_rad) + sin(yaw_rad) * sin(roll_rad);

R[1][0] = sin(yaw_rad) * cos(pitch_rad);
R[1][0] = sin(yaw_rad) * cos(pitch_rad);
R[1][1] = sin(yaw_rad) * sin(pitch_rad) * sin(roll_rad) + cos(yaw_rad) * cos(roll_rad);
R[1][2] = sin(yaw_rad) * sin(pitch_rad) * cos(roll_rad) - cos(yaw_rad) * sin(roll_rad);

Expand All @@ -202,6 +202,14 @@ std::tuple<float, float, float> DataRefManager::convertOGLtoNED(float ogl_vx, fl
return std::make_tuple(ned_vn, ned_ve, ned_vd);
}

void DataRefManager::enableOverride() {
XPLMSetDatai(XPLMFindDataRef("sim/operation/override/override_throttles"), 1);
}

void DataRefManager::disableOverride() {
XPLMSetDatai(XPLMFindDataRef("sim/operation/override/override_throttles"), 0);
}


void DataRefManager::overrideActuators() {
// Get the HILActuatorControlsData from MAVLinkManager
Expand All @@ -219,6 +227,9 @@ void DataRefManager::overrideActuators() {
correctedControls.controls[xplaneMotor - 1] = hilControls.controls[i];
}

// Enable the override (already enabled)
//DataRefManager::enableOverride();

// Override the throttle dataref in X-Plane for all engines at once
std::string dataRef = "sim/flightmodel/engine/ENGN_thro_use";
XPLMSetDatavf(XPLMFindDataRef(dataRef.c_str()), correctedControls.controls, 0, 16);
Expand Down
3 changes: 3 additions & 0 deletions DataRefManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,5 +46,8 @@ class DataRefManager {
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 void drawActuatorControls(XPLMWindowID in_window_id, int l, int t, float col_white[], int lineOffset);
static void overrideActuators();
static void enableOverride();
static void disableOverride();

};

2 changes: 1 addition & 1 deletion MAVLinkManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,7 +214,7 @@ void MAVLinkManager::sendHILRCInputs() {
hil_rc_inputs.chan2_raw = static_cast<uint16_t>(DataRefManager::mapChannelValue(DataRefManager::getFloat("sim/joystick/yoke_pitch_ratio"), -1, +1, 1000, 2000));
hil_rc_inputs.chan3_raw = static_cast<uint16_t>(DataRefManager::mapChannelValue(DataRefManager::getFloat("sim/cockpit2/engine/actuators/throttle_ratio_all"),0, +1, 1000, 2000));
hil_rc_inputs.chan4_raw = static_cast<uint16_t>(DataRefManager::mapChannelValue(DataRefManager::getFloat("sim/joystick/yoke_heading_ratio"), -1, +1, 1000, 2000));
hil_rc_inputs.chan4_raw = static_cast<uint16_t>(DataRefManager::mapChannelValue(0, -1, +1, 1000, 2000));
hil_rc_inputs.chan5_raw = static_cast<uint16_t>(DataRefManager::mapChannelValue(0, -1, +1, 1000, 2000));
// Map the remaining channels as needed

hil_rc_inputs.rssi = 255; // Set the RSSI field to a constant value if not available
Expand Down
2 changes: 1 addition & 1 deletion px4xplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ void draw_px4xplane(XPLMWindowID in_window_id, void* in_refcon) {
DataRefManager::drawDataRefs(in_window_id, l + 10, t - lineOffset, col_white, lineOffset);


int rightColumnPosition = l + 300;
int rightColumnPosition = l + 350;

DataRefManager::drawActuatorControls(in_window_id, rightColumnPosition, t, col_white, lineOffset);

Expand Down

0 comments on commit fa793e4

Please sign in to comment.