aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp25
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp28
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp26
3 files changed, 70 insertions, 9 deletions
diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
index d572f5339..40cb6043f 100644
--- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
@@ -125,6 +125,13 @@ public:
int start();
/**
+ * Task status
+ *
+ * @return true if the mainloop is running
+ */
+ bool task_running() { return _task_running; }
+
+ /**
* Print the current status.
*/
void print_status();
@@ -151,7 +158,8 @@ public:
private:
bool _task_should_exit; /**< if true, sensor task should exit */
- int _estimator_task; /**< task handle for sensor task */
+ bool _task_running; /**< if true, task is running in its mainloop */
+ int _estimator_task; /**< task handle for sensor task */
#ifndef SENSOR_COMBINED_SUB
int _gyro_sub; /**< gyro sensor subscription */
int _accel_sub; /**< accel sensor subscription */
@@ -313,12 +321,13 @@ namespace estimator
#endif
static const int ERROR = -1;
-FixedwingEstimator *g_estimator;
+FixedwingEstimator *g_estimator = nullptr;
}
FixedwingEstimator::FixedwingEstimator() :
_task_should_exit(false),
+ _task_running(false),
_estimator_task(-1),
/* subscriptions */
@@ -741,6 +750,8 @@ FixedwingEstimator::task_main()
_gps.vel_e_m_s = 0.0f;
_gps.vel_d_m_s = 0.0f;
+ _task_running = true;
+
while (!_task_should_exit) {
/* wait for up to 500ms for data */
@@ -1491,6 +1502,8 @@ FixedwingEstimator::task_main()
perf_end(_loop_perf);
}
+ _task_running = false;
+
warnx("exiting.\n");
_estimator_task = -1;
@@ -1643,6 +1656,14 @@ int ekf_att_pos_estimator_main(int argc, char *argv[])
err(1, "start failed");
}
+ /* avoid memory fragmentation by not exiting start handler until the task has fully started */
+ while (estimator::g_estimator == nullptr || !estimator::g_estimator->task_running()) {
+ usleep(50000);
+ printf(".");
+ fflush(stdout);
+ }
+ printf("\n");
+
exit(0);
}
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp
index 3cd4ce928..4cdba735a 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -99,13 +98,21 @@ public:
/**
* Start the sensors task.
*
- * @return OK on success.
+ * @return OK on success.
*/
int start();
+ /**
+ * Task status
+ *
+ * @return true if the mainloop is running
+ */
+ bool task_running() { return _task_running; }
+
private:
bool _task_should_exit; /**< if true, sensor task should exit */
+ bool _task_running; /**< if true, task is running in its mainloop */
int _control_task; /**< task handle for sensor task */
int _att_sub; /**< vehicle attitude subscription */
@@ -276,6 +283,7 @@ private:
* Main sensor collection task.
*/
void task_main();
+
};
namespace att_control
@@ -287,12 +295,13 @@ namespace att_control
#endif
static const int ERROR = -1;
-FixedwingAttitudeControl *g_control;
+FixedwingAttitudeControl *g_control = nullptr;
}
FixedwingAttitudeControl::FixedwingAttitudeControl() :
_task_should_exit(false),
+ _task_running(false),
_control_task(-1),
/* subscriptions */
@@ -598,6 +607,8 @@ FixedwingAttitudeControl::task_main()
fds[1].fd = _att_sub;
fds[1].events = POLLIN;
+ _task_running = true;
+
while (!_task_should_exit) {
static int loop_counter = 0;
@@ -921,6 +932,7 @@ FixedwingAttitudeControl::task_main()
warnx("exiting.\n");
_control_task = -1;
+ _task_running = false;
_exit(0);
}
@@ -966,6 +978,14 @@ int fw_att_control_main(int argc, char *argv[])
err(1, "start failed");
}
+ /* avoid memory fragmentation by not exiting start handler until the task has fully started */
+ while (att_control::g_control == nullptr || !att_control::g_control->task_running()) {
+ usleep(50000);
+ printf(".");
+ fflush(stdout);
+ }
+ printf("\n");
+
exit(0);
}
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index 98ccd09a5..08c996ebc 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -120,10 +119,18 @@ public:
*/
int start();
+ /**
+ * Task status
+ *
+ * @return true if the mainloop is running
+ */
+ bool task_running() { return _task_running; }
+
private:
int _mavlink_fd;
bool _task_should_exit; /**< if true, sensor task should exit */
+ bool _task_running; /**< if true, task is running in its mainloop */
int _control_task; /**< task handle for sensor task */
int _global_pos_sub;
@@ -391,13 +398,14 @@ namespace l1_control
#endif
static const int ERROR = -1;
-FixedwingPositionControl *g_control;
+FixedwingPositionControl *g_control = nullptr;
}
FixedwingPositionControl::FixedwingPositionControl() :
_mavlink_fd(-1),
_task_should_exit(false),
+ _task_running(false),
_control_task(-1),
/* subscriptions */
@@ -1290,6 +1298,8 @@ FixedwingPositionControl::task_main()
fds[1].fd = _global_pos_sub;
fds[1].events = POLLIN;
+ _task_running = true;
+
while (!_task_should_exit) {
/* wait for up to 500ms for data */
@@ -1390,6 +1400,8 @@ FixedwingPositionControl::task_main()
perf_end(_loop_perf);
}
+ _task_running = false;
+
warnx("exiting.\n");
_control_task = -1;
@@ -1478,6 +1490,14 @@ int fw_pos_control_l1_main(int argc, char *argv[])
err(1, "start failed");
}
+ /* avoid memory fragmentation by not exiting start handler until the task has fully started */
+ while (l1_control::g_control == nullptr || !l1_control::g_control->task_running()) {
+ usleep(50000);
+ printf(".");
+ fflush(stdout);
+ }
+ printf("\n");
+
exit(0);
}