Skip to content

Commit

Permalink
fixed home clone path
Browse files Browse the repository at this point in the history
  • Loading branch information
alireza787b committed Aug 25, 2024
1 parent 94eaa1c commit 4ad16a1
Show file tree
Hide file tree
Showing 6 changed files with 56 additions and 40 deletions.
19 changes: 5 additions & 14 deletions include/ConfigManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,22 +80,13 @@ class ConfigManager {
static std::string getActiveAirframeName();
static void setActiveAirframeName(const std::string& airframeName);
static std::string getAirframeByIndex(int index);
// Structure to hold the configuration settings
struct Config {
bool filter_accel_enabled = false; // Enable/disable accelerometer filtering
float accel_filter_alpha = 0.1f; // Alpha value for low-pass filter
// Add any other configuration fields as needed
};

// Static method to access the global configuration
static Config& getConfig() {
static Config config;
return config;
}

// Static method to load configuration (from a file, UI, etc.)
static void loadConfig(); // Implement this method if needed

static bool filter_velocity_enabled; // Flag for enabling/disabling velocity filtering
static float velocity_filter_alpha; // Alpha value for velocity filtering

static bool filter_accel_enabled; // Flag for enabling/disabling accelerometer filtering
static float accel_filter_alpha; // Alpha value for accelerometer filtering


private:
Expand Down
7 changes: 6 additions & 1 deletion include/DataRefManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ class DataRefManager {
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 float applyFilteringIfNeeded(float raw_value, float& prev_filtered_value);
static float applyFilteringIfNeeded(float raw_value, float& prev_filtered_value, bool filter_enabled, float filter_alpha);

static std::string GetFormattedDroneConfig();
static float scaleActuatorCommand(float input, float inputMin, float inputMax, float outputMin, float outputMax);
Expand All @@ -80,6 +80,11 @@ class DataRefManager {
static float prev_yacc;
static float prev_zacc;

// Static variables to hold previous filtered velocities
static float prev_vn;
static float prev_ve;
static float prev_vd;

static constexpr float UPDATE_THRESHOLD=1000; // Define a threshold for position change in meters
static std::bitset<8> motorBrakeStates; // Tracks the current brake states
static void checkAndApplyPropBrakes();
Expand Down
2 changes: 1 addition & 1 deletion setup/setup_px4_sitl.sh
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@
REPO_URL="https://github.com/alireza787b/PX4-Autopilot-Me.git"
BRANCH_NAME="px4xplane-sitl"
UPSTREAM_URL="https://github.com/PX4/PX4-Autopilot.git"
DEFAULT_CLONE_PATH="$HOME/testpx4"
DEFAULT_CLONE_PATH="$HOME"
DEFAULT_CONFIG_FILE="$HOME/.px4sitl_config"
DEFAULT_FALLBACK_IP="127.0.0.1"
SCRIPT_NAME="px4xplane_script.sh"
Expand Down
9 changes: 9 additions & 0 deletions src/ConfigManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,12 @@ std::map<int, int> ConfigManager::motorMappingsXPlanetoPX4;
// Name of the configuration, typically used for display purposes.
std::string ConfigManager::configName;

bool ConfigManager::filter_velocity_enabled = true;
float ConfigManager::velocity_filter_alpha = 0.25f;

bool ConfigManager::filter_accel_enabled = true;
float ConfigManager::accel_filter_alpha = 0.15f;


// Stores configurations for actuators, indexed by their channel number.
std::map<int, ActuatorConfig> ConfigManager::actuatorConfigs;
Expand Down Expand Up @@ -79,6 +85,9 @@ void ConfigManager::loadConfiguration() {
}





/**
* Resolves and returns the full file path of the 'config.ini' file.
* This function is used to determine the location of the configuration file
Expand Down
27 changes: 17 additions & 10 deletions src/DataRefManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,11 @@ float DataRefManager::prev_xacc = 0.0f;
float DataRefManager::prev_yacc = 0.0f;
float DataRefManager::prev_zacc = -9.81f;

// Initialize static variables for previous filtered velocities
float DataRefManager::prev_vn = 0.0f;
float DataRefManager::prev_ve = 0.0f;
float DataRefManager::prev_vd = 0.0f;


/**
* @brief Tracks the current brake state of each motor.
Expand Down Expand Up @@ -654,20 +659,21 @@ void DataRefManager::applyBrake(int motorIndex, bool enable) {


/**
* @brief Applies low-pass filtering to the accelerometer data if filtering is enabled.
* @brief Applies low-pass filtering to data if filtering is enabled.
*
* This function checks the configuration to see if filtering is enabled. If it is,
* it applies the low-pass filter to the accelerometer data and updates the previous
* filtered values. If filtering is disabled, it simply returns the raw data.
* This generalized function checks if filtering is enabled for a specific data type. If it is,
* it applies a low-pass filter to the data and updates the previous filtered value.
* If filtering is disabled, it simply returns the raw data.
*
* @param raw_value The raw accelerometer value.
* @param raw_value The raw sensor value (e.g., accelerometer, velocity).
* @param prev_filtered_value The previous filtered value.
* @return The filtered or raw accelerometer value.
* @param filter_enabled Flag indicating whether filtering is enabled.
* @param filter_alpha The alpha value for the low-pass filter.
* @return The filtered or raw value, depending on the filtering settings.
*/
float DataRefManager::applyFilteringIfNeeded(float raw_value, float& prev_filtered_value) {
if (ConfigManager::getConfig().filter_accel_enabled) {
float alpha = ConfigManager::getConfig().accel_filter_alpha;
float filtered_value = lowPassFilter(raw_value, prev_filtered_value, alpha);
float DataRefManager::applyFilteringIfNeeded(float raw_value, float& prev_filtered_value, bool filter_enabled, float filter_alpha) {
if (filter_enabled) {
float filtered_value = lowPassFilter(raw_value, prev_filtered_value, filter_alpha);
prev_filtered_value = filtered_value;
return filtered_value;
}
Expand All @@ -677,6 +683,7 @@ float DataRefManager::applyFilteringIfNeeded(float raw_value, float& prev_filter
}
}


/**
* @brief Checks the throttle for each motor and applies or releases the brake as necessary.
*
Expand Down
32 changes: 18 additions & 14 deletions src/MAVLinkManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -415,8 +415,9 @@ void MAVLinkManager::processHILActuatorControlsMessage(const mavlink_message_t&
* @brief Sets the acceleration data in the HIL_SENSOR message.
*
* This function retrieves the aircraft's current acceleration forces from the simulation,
* applies optional low-pass filtering, multiplies them by the gravitational constant,
* and sets them in the provided HIL_SENSOR message.
* applies optional low-pass filtering if enabled, multiplies them by the gravitational constant,
* and sets the processed data in the provided HIL_SENSOR message.
* The filtering parameters (enabled flag and alpha value) are configurable.
*
* @param hil_sensor Reference to the HIL_SENSOR message where the acceleration data will be set.
*/
Expand All @@ -427,11 +428,12 @@ void MAVLinkManager::setAccelerationData(mavlink_hil_sensor_t& hil_sensor) {
float raw_zacc = DataRefManager::getFloat("sim/flightmodel/forces/g_nrml") * DataRefManager::g_earth * -1;

// Apply filtering if enabled, otherwise use raw data
hil_sensor.xacc = DataRefManager::applyFilteringIfNeeded(raw_xacc, DataRefManager::prev_xacc);
hil_sensor.yacc = DataRefManager::applyFilteringIfNeeded(raw_yacc, DataRefManager::prev_yacc);
hil_sensor.zacc = DataRefManager::applyFilteringIfNeeded(raw_zacc, DataRefManager::prev_zacc);
hil_sensor.xacc = DataRefManager::applyFilteringIfNeeded(raw_xacc, DataRefManager::prev_xacc, ConfigManager::filter_accel_enabled, ConfigManager::accel_filter_alpha);
hil_sensor.yacc = DataRefManager::applyFilteringIfNeeded(raw_yacc, DataRefManager::prev_yacc, ConfigManager::filter_accel_enabled, ConfigManager::accel_filter_alpha);
hil_sensor.zacc = DataRefManager::applyFilteringIfNeeded(raw_zacc, DataRefManager::prev_zacc, ConfigManager::filter_accel_enabled, ConfigManager::accel_filter_alpha);
}


/**
* @brief Sets the gyroscope data in the HIL_SENSOR message.
*
Expand Down Expand Up @@ -614,18 +616,13 @@ void MAVLinkManager::setGPSVelocityDataByPath(mavlink_hil_gps_t& hil_gps) {
hil_gps.vel = static_cast<uint16_t>(sqrt(Vn * Vn + Ve * Ve + Vd * Vd) * 100.0f);
}


/**
* @brief Sets the velocity data for the HIL_GPS message using the NED coordinate system.
*
* This function temporarily uses the TCAS system velocities (sim/cockpit2/tcas/targets/position/vx, vy, vz)
* from X-Plane for calculating the aircraft's velocity in the NED coordinate system. The TCAS velocities
* are in the OGL coordinate system and are transformed to NED. This approach is a temporary workaround
* to address issues with other velocity datarefs and will be replaced by a more accurate solution in the future.
*
* Note: TCAS velocities are used here for their availability and ease of access, but they might not
* provide the most accurate representation of the aircraft's true velocity, especially in complex flight
* scenarios or with certain aircraft models.
* This function retrieves the TCAS system velocities (sim/cockpit2/tcas/targets/position/vx, vy, vz)
* from X-Plane, transforms them from the OGL coordinate system to the NED coordinate system, and applies
* optional low-pass filtering to the velocities if filtering is enabled in the configuration.
* The velocities are then populated into the HIL_GPS MAVLink message in cm/s.
*
* @param hil_gps Reference to the mavlink_hil_gps_t structure to populate.
*/
Expand All @@ -645,6 +642,11 @@ void MAVLinkManager::setGPSVelocityData(mavlink_hil_gps_t& hil_gps) {
float Ve = vx; // East remains the same
float Vd = -vy; // Down is negative Up

// Apply filtering if enabled, otherwise use raw data
Vn = DataRefManager::applyFilteringIfNeeded(Vn, DataRefManager::prev_vn, ConfigManager::filter_velocity_enabled, ConfigManager::velocity_filter_alpha);
Ve = DataRefManager::applyFilteringIfNeeded(Ve, DataRefManager::prev_ve, ConfigManager::filter_velocity_enabled, ConfigManager::velocity_filter_alpha);
Vd = DataRefManager::applyFilteringIfNeeded(Vd, DataRefManager::prev_vd, ConfigManager::filter_velocity_enabled, ConfigManager::velocity_filter_alpha);

// Populate the MAVLink message with NED velocities (converted to cm/s)
hil_gps.vn = static_cast<int16_t>(Vn * 100.0f);
hil_gps.ve = static_cast<int16_t>(Ve * 100.0f);
Expand All @@ -658,6 +660,8 @@ void MAVLinkManager::setGPSVelocityData(mavlink_hil_gps_t& hil_gps) {





/**
* @brief Sets the heading data for the HIL_GPS message.
*
Expand Down

0 comments on commit 4ad16a1

Please sign in to comment.