Skip to content

Commit

Permalink
builds but not tested yet after fixwing added
Browse files Browse the repository at this point in the history
  • Loading branch information
alireza787b committed Nov 24, 2023
1 parent 18cee06 commit 90b7634
Show file tree
Hide file tree
Showing 5 changed files with 14 additions and 23 deletions.
7 changes: 4 additions & 3 deletions include/ConfigManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,9 @@
#include <string>
#include <map>
#include <vector>
#include "SimpleIni.h"

enum ActuatorDataType { UNKNOWN, FLOAT, FLOAT_ARRAY };
enum ActuatorDataType { UNKNOWN, FLOAT_SINGLE, FLOAT_ARRAY };

struct ActuatorConfig {
std::string datarefName;
Expand All @@ -26,7 +27,8 @@ class ConfigManager {
static std::string getConfigVersion();
static std::string getConfigType();
static uint8_t getConfigTypeCode();

static std::map<int, ActuatorConfig> actuatorConfigs; // Map channel number to ActuatorConfig


private:
static std::map<int, int> motorMappingsPX4toXPlane;
Expand All @@ -36,7 +38,6 @@ class ConfigManager {
static std::string configType; // "Multirotor" or "FixedWing" or ...
static uint8_t ConfigManager::configTypeCode;
static std::string getConfigFilePath();
static std::map<int, ActuatorConfig> actuatorConfigs; // Map channel number to ActuatorConfig
static void parseFixedWingConfig(CSimpleIniA& ini) ;
static void parseMultirotorConfig(CSimpleIniA& ini) ;
static ActuatorDataType stringToDataType(const std::string& typeStr);
Expand Down
12 changes: 0 additions & 12 deletions include/DataRefManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,18 +57,6 @@ class DataRefManager {
static Eigen::Vector3f convertNEDToBody(const Eigen::Vector3f& nedVector, float roll, float pitch, float yaw);
static void initializeMagneticField();
static std::string GetFormattedDroneConfig();
static void overrideActuators_fixedwing() {



// Additional debug information can be printed here if necessary
}

void setControlSurface(const std::string& dataref, float value) ;
}

void setThrottle(const std::string& dataref, float value) ;



};
Expand Down
8 changes: 5 additions & 3 deletions src/ConfigManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
#include <fstream>
#include <sstream>
#include <iostream>
#include "SimpleIni.h"

std::map<int, int> ConfigManager::motorMappingsPX4toXPlane;
std::map<int, int> ConfigManager::motorMappingsXPlanetoPX4;
Expand All @@ -15,6 +14,9 @@ std::string ConfigManager::configVersion;
std::string ConfigManager::configType;
uint8_t ConfigManager::configTypeCode;

std::map<int, ActuatorConfig> ConfigManager::actuatorConfigs;


void ConfigManager::loadConfiguration() {
// Initialize the SimpleIni object and set it to handle Unicode
CSimpleIniA ini;
Expand Down Expand Up @@ -155,8 +157,8 @@ void ConfigManager::parseFixedWingConfig(CSimpleIniA& ini) {



ActuatorDataType stringToDataType(const std::string& typeStr) {
if (typeStr == "float") return FLOAT;
ActuatorDataType ConfigManager::stringToDataType(const std::string& typeStr) {
if (typeStr == "float") return FLOAT_SINGLE;
else if (typeStr == "floatArray") return FLOAT_ARRAY;
return UNKNOWN;
}
8 changes: 4 additions & 4 deletions src/DataRefManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -308,14 +308,14 @@ void DataRefManager::overrideActuators_fixedwing() {
MAVLinkManager::HILActuatorControlsData hilControls = MAVLinkManager::hilActuatorControlsData;

// Iterate over each configured actuator
for (const auto& [channel, config] : actuatorConfigs) {
// Retrieve the control value for the current channel and clamp it within the configured range
for (const auto& [channel, config] : ConfigManager::actuatorConfigs) {
// Retrieve the control value for the current channel and clamp it within the configured range
float value = hilControls.controls[channel];
value = std::max(config.range.first, std::min(config.range.second, value));
value = (std::max)(config.range.first, (std::min)(config.range.second, value));

// Set the dataref in X-Plane based on the actuator's data type
switch (config.dataType) {
case FLOAT:
case FLOAT_SINGLE:
// For float type, directly set the dataref with the clamped value
XPLMSetDataf(XPLMFindDataRef(config.datarefName.c_str()), value);
break;
Expand Down
2 changes: 1 addition & 1 deletion src/px4xplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
#include "ConfigReader.h"
#include "DataRefManager.h"
#include "ConnectionManager.h"

#include "ConfigManager.h"

#if IBM
#include <windows.h>
Expand Down

0 comments on commit 90b7634

Please sign in to comment.