diff --git a/drone_control/common/include/drone_alt_controller.hpp b/drone_control/common/include/drone_alt_controller.hpp index 5e396dfc..464ac009 100644 --- a/drone_control/common/include/drone_alt_controller.hpp +++ b/drone_control/common/include/drone_alt_controller.hpp @@ -103,8 +103,8 @@ class DroneAltController { /* * thrust */ - //out.thrust = (mass * gravity) + (throttle_gain * throttle_power); - out.thrust = (throttle_gain * throttle_power); + out.thrust = (mass * gravity) + (throttle_gain * throttle_power); + //out.thrust = (throttle_gain * throttle_power); spd_prev_out = out; } spd_simulation_time += delta_time; diff --git a/hakoniwa/config/rc/drone_config_0.json b/hakoniwa/config/rc/drone_config_0.json index 8db73053..29db1329 100644 --- a/hakoniwa/config/rc/drone_config_0.json +++ b/hakoniwa/config/rc/drone_config_0.json @@ -67,13 +67,13 @@ }, "battery": { "vendor": "None", - "model": "constant", + "model": "linear", "BatteryModelCsvFilePath": "./tmp_battery_model.csv", "VoltageLevelGreen": 12.1, "VoltageLevelYellow": 11.1, - "CapacityLevelYellow": 900, + "CapacityLevelYellow": 3, "NominalVoltage": 14.8, - "NominalCapacity": 1000.0, + "NominalCapacity": 4.0, "EODVoltage": 3.0 }, "rotor": {