projects
/
flygplan.git
/ commitdiff
commit
grep
author
committer
pickaxe
?
search:
re
summary
|
shortlog
|
log
|
commit
| commitdiff |
tree
raw
|
patch
|
inline
| side by side (parent:
407a48f
)
reduced mutex duration
main
author
Nils Forssén
<forssennils@gmail.com>
Thu, 19 Jun 2025 09:19:23 +0000
(11:19 +0200)
committer
Nils Forssén
<forssennils@gmail.com>
Thu, 19 Jun 2025 09:19:23 +0000
(11:19 +0200)
README.md
patch
|
blob
|
history
processes/controller/controller.cpp
patch
|
blob
|
history
processes/controller/include/controller.h
patch
|
blob
|
history
processes/controller/main.cpp
patch
|
blob
|
history
diff --git
a/README.md
b/README.md
index 532b7201d015273af632980b2f4f6d1273533a71..df00a1a8704d4912f028eed2d0597c7894ecb0f5 100755
(executable)
--- a/
README.md
+++ b/
README.md
@@
-3,7
+3,7
@@
Enable fan pin 20 through raspi-config
```
Enable fan pin 20 through raspi-config
```
-sudo apt install -y cmake build-essential checkinstall zlib1g-dev libssl-dev python3 python3-pip ninja-build git ufw python3-picamera2 libspdlog-dev libeigen3-dev
--no-install-recommends
+sudo apt install -y cmake build-essential checkinstall zlib1g-dev libssl-dev python3 python3-pip ninja-build git ufw python3-picamera2 libspdlog-dev libeigen3-dev
libx264-dev libjpeg-dev --no-install-recommends
```
based a bit on [example](https://github.com/mavlink/mavlink/blob/master/examples/c/udp_example.c).
```
based a bit on [example](https://github.com/mavlink/mavlink/blob/master/examples/c/udp_example.c).
diff --git
a/processes/controller/controller.cpp
b/processes/controller/controller.cpp
index 79ff0f2ceb78cb7d23a494904918e5c147937907..827b0dec0cfccd4c49947565127eef9d039e9309 100644
(file)
--- a/
processes/controller/controller.cpp
+++ b/
processes/controller/controller.cpp
@@
-36,20
+36,6
@@
const vec2d Complementary_filter::get_state()
void Complementary_filter::update(const vec3d &gyro_meas, const vec3d &accel_meas,
double dt_sec, unsigned int gyro_range, unsigned int accel_range)
{
void Complementary_filter::update(const vec3d &gyro_meas, const vec3d &accel_meas,
double dt_sec, unsigned int gyro_range, unsigned int accel_range)
{
- /*
- // Crude check for new data
- if (last_accel_meas == accel_meas)
- {
- logger->warn("Last accel measurement indentical to new.");
- }
- if (last_gyro_meas == gyro_meas)
- {
- logger->warn("Last gyro measurement identical to new.");
- }
- last_accel_meas = accel_meas;
- last_gyro_meas = gyro_meas;
- */
-
auto accel_est = accel_to_pitch_roll(accel_meas);
auto gyro_est = pqr_to_euler(gyro_meas, current_state);
auto accel_est = accel_to_pitch_roll(accel_meas);
auto gyro_est = pqr_to_euler(gyro_meas, current_state);
diff --git
a/processes/controller/include/controller.h
b/processes/controller/include/controller.h
index 8cfc66ba94582f5e4f20d87dcf6865b5c10684f1..2ec06eabdbec39b204256ecf1ef3e2459cdefa94 100644
(file)
--- a/
processes/controller/include/controller.h
+++ b/
processes/controller/include/controller.h
@@
-29,9
+29,6
@@
private:
std::shared_ptr<spdlog::logger> logger;
const double alpha;
vec2d current_state;
std::shared_ptr<spdlog::logger> logger;
const double alpha;
vec2d current_state;
- vec3d last_gyro_meas;
- vec3d last_accel_meas;
-
};
class EKF
};
class EKF
diff --git
a/processes/controller/main.cpp
b/processes/controller/main.cpp
index c0f062eb1a9b508b0f8793070dfafb7e5744b288..877b5b25760fdf41b00371937776554033fe8455 100644
(file)
--- a/
processes/controller/main.cpp
+++ b/
processes/controller/main.cpp
@@
-94,6
+94,7
@@
int main(int argc, char* argv[])
{
THREAD_SLEEP(CLICK_READ_SPI_PERIOD);
{
THREAD_SLEEP(CLICK_READ_SPI_PERIOD);
+ /* __________________________________________________________ */
std::lock_guard<std::mutex> lk{data_lock};
logger->debug("Controlling!");
std::lock_guard<std::mutex> lk{data_lock};
logger->debug("Controlling!");
@@
-115,6
+116,8
@@
int main(int argc, char* argv[])
accel_vec = struct_to_vec_scaled(accel_data, (GRAVITY * 16.0) / 32768.0);
comp_filter.update(gyro_vec, accel_vec, time_d);
accel_vec = struct_to_vec_scaled(accel_data, (GRAVITY * 16.0) / 32768.0);
comp_filter.update(gyro_vec, accel_vec, time_d);
+
+ /* __________________________________________________________ */
}
close(sendpipe_fd);
}
close(sendpipe_fd);
@@
-176,10
+179,11
@@
static err_t spi_init()
while (true)
{
THREAD_SLEEP(CONTROLLER_MAVLINK_PERIOD);
while (true)
{
THREAD_SLEEP(CONTROLLER_MAVLINK_PERIOD);
- std::lock_guard<std::mutex> lk{data_lock};
-
logger->debug("Sending IMU Mavlink.");
logger->debug("Sending IMU Mavlink.");
-
+
+ /* __________________________________________________________ */
+ data_lock.lock();
+
// Pack data into MAVLINK packages
attitude.time_boot_ms = system_uptime_ms();
attitude.roll = comp_filter.get_state()[1];
// Pack data into MAVLINK packages
attitude.time_boot_ms = system_uptime_ms();
attitude.roll = comp_filter.get_state()[1];
@@
-201,6
+205,9
@@
static err_t spi_init()
scaled_imu.ymag = INT16_MAX;
scaled_imu.zmag = INT16_MAX;
scaled_imu.ymag = INT16_MAX;
scaled_imu.zmag = INT16_MAX;
+ data_lock.unlock();
+ /* __________________________________________________________ */
+
mavlink_msg_attitude_encode(
MAV_SYS_ID,
MAV_COMP_ID,
mavlink_msg_attitude_encode(
MAV_SYS_ID,
MAV_COMP_ID,