Browse Source

LPE: refactor to use ModuleBase

sbg
Beat Küng 7 years ago
parent
commit
83d55773af
  1. 153
      src/modules/local_position_estimator/local_position_estimator_main.cpp

153
src/modules/local_position_estimator/local_position_estimator_main.cpp

@ -40,130 +40,101 @@
* Local position estimator * Local position estimator
*/ */
#include <unistd.h> #include <px4_log.h>
#include <stdio.h> #include <px4_module.h>
#include <stdlib.h>
#include <string.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
#include <math.h>
#include <fcntl.h>
#include <px4_posix.h>
#include <px4_tasks.h> #include <px4_tasks.h>
#include "BlockLocalPositionEstimator.hpp" #include "BlockLocalPositionEstimator.hpp"
static volatile bool thread_should_exit = false; /**< Deamon exit flag */
static volatile bool thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
/**
* Deamon management function.
*/
extern "C" __EXPORT int local_position_estimator_main(int argc, char *argv[]); extern "C" __EXPORT int local_position_estimator_main(int argc, char *argv[]);
/** class LocalPositionEstimatorModule : public ModuleBase<LocalPositionEstimatorModule>
* Mainloop of deamon. {
*/ public:
int local_position_estimator_thread_main(int argc, char *argv[]); virtual ~LocalPositionEstimatorModule() = default;
/** /** @see ModuleBase */
* Print the correct usage. static int task_spawn(int argc, char *argv[]);
*/
static int usage(const char *reason);
static int /** @see ModuleBase */
usage(const char *reason) static LocalPositionEstimatorModule *instantiate(int argc, char *argv[]);
{
if (reason) {
fprintf(stderr, "%s\n", reason);
}
fprintf(stderr, "usage: local_position_estimator {start|stop|status} [-p <additional params>]\n\n"); /** @see ModuleBase */
return 1; static int custom_command(int argc, char *argv[]);
}
/** /** @see ModuleBase */
* The deamon app only briefly exists to start static int print_usage(const char *reason = nullptr);
* the background job. The stack size assigned in the
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
* to task_create().
*/
int local_position_estimator_main(int argc, char *argv[])
{
if (argc < 2) { /** @see ModuleBase::run() */
usage("missing command"); void run() override;
return 1;
}
if (!strcmp(argv[1], "start")) { private:
BlockLocalPositionEstimator _estimator;
};
if (thread_running) { int LocalPositionEstimatorModule::print_usage(const char *reason)
PX4_INFO("already running"); {
/* this is not an error */ if (reason) {
return 0; PX4_WARN("%s\n", reason);
} }
thread_should_exit = false; PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
Attitude and position estimator using an Extended Kalman Filter.
deamon_task = px4_task_spawn_cmd("lp_estimator", )DESCR_STR");
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
13500,
local_position_estimator_thread_main,
(argv && argc > 2) ? (char *const *) &argv[2] : (char *const *) nullptr);
return 0;
}
if (!strcmp(argv[1], "stop")) { PRINT_MODULE_USAGE_NAME("local_position_estimator", "estimator");
if (thread_running) { PRINT_MODULE_USAGE_COMMAND("start");
PX4_DEBUG("stop"); PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
thread_should_exit = true;
} else { return 0;
PX4_WARN("not started");
} }
return 0; int LocalPositionEstimatorModule::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");
} }
if (!strcmp(argv[1], "status")) {
if (thread_running) {
PX4_INFO("is running");
} else { int LocalPositionEstimatorModule::task_spawn(int argc, char *argv[])
PX4_INFO("not started"); {
_task_id = px4_task_spawn_cmd("lp_estimator",
SCHED_DEFAULT,
SCHED_PRIORITY_ESTIMATOR,
7900,
(px4_main_t)&run_trampoline,
(char *const *)argv);
if (_task_id < 0) {
_task_id = -1;
return -errno;
} }
return 0; return 0;
} }
usage("unrecognized command"); LocalPositionEstimatorModule *LocalPositionEstimatorModule::instantiate(int argc, char *argv[])
return 1;
}
int local_position_estimator_thread_main(int argc, char *argv[])
{ {
LocalPositionEstimatorModule *instance = new LocalPositionEstimatorModule();
PX4_DEBUG("starting"); if (instance == nullptr) {
PX4_ERR("alloc failed");
using namespace control; }
BlockLocalPositionEstimator est;
thread_running = true;
while (!thread_should_exit) { return instance;
est.update();
} }
PX4_DEBUG("exiting."); void LocalPositionEstimatorModule::run()
{
while (!should_exit()) {
_estimator.update();
}
}
thread_running = false;
return 0; int local_position_estimator_main(int argc, char *argv[])
{
return LocalPositionEstimatorModule::main(argc, argv);
} }

Loading…
Cancel
Save