mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-07 09:13:32 +08:00
send_event: convert to use ModuleBase
This commit is contained in:
@@ -463,7 +463,7 @@ then
|
||||
commander start
|
||||
fi
|
||||
|
||||
if send_event start_listening
|
||||
if send_event start
|
||||
then
|
||||
fi
|
||||
|
||||
|
||||
@@ -38,14 +38,13 @@
|
||||
#include <px4_log.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
static SendEvent *send_event_obj = nullptr;
|
||||
struct work_s SendEvent::_work = {};
|
||||
|
||||
// Run it at 30 Hz.
|
||||
const unsigned SEND_EVENT_INTERVAL_US = 33000;
|
||||
|
||||
|
||||
int SendEvent::initialize()
|
||||
int SendEvent::task_spawn(int argc, char *argv[])
|
||||
{
|
||||
int ret = work_queue(LPWORK, &_work, (worker_t)&SendEvent::initialize_trampoline, nullptr, 0);
|
||||
|
||||
@@ -59,13 +58,14 @@ int SendEvent::initialize()
|
||||
/* wait up to 1s */
|
||||
usleep(2500);
|
||||
|
||||
} while ((!send_event_obj || !send_event_obj->is_running()) && ++i < 400);
|
||||
} while (!_object && ++i < 400);
|
||||
|
||||
if (i == 400) {
|
||||
PX4_ERR("failed to start");
|
||||
return -1;
|
||||
}
|
||||
|
||||
_task_id = task_id_is_work_queue;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -75,13 +75,10 @@ SendEvent::SendEvent()
|
||||
|
||||
int SendEvent::start()
|
||||
{
|
||||
if (_task_is_running) {
|
||||
if (is_running()) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
_task_is_running = true;
|
||||
_task_should_exit = false;
|
||||
|
||||
_vehicle_command_sub = orb_subscribe(ORB_ID(vehicle_command));
|
||||
|
||||
// Kick off the cycling. We can call it directly because we're already in the work queue context
|
||||
@@ -90,37 +87,17 @@ int SendEvent::start()
|
||||
return 0;
|
||||
}
|
||||
|
||||
void SendEvent::stop()
|
||||
{
|
||||
if (!_task_is_running) {
|
||||
return;
|
||||
}
|
||||
|
||||
_task_should_exit = true;
|
||||
// Wait for task to exit
|
||||
int i = 0;
|
||||
|
||||
do {
|
||||
/* wait up to 3s */
|
||||
usleep(100000);
|
||||
|
||||
} while (_task_is_running && ++i < 30);
|
||||
|
||||
if (i == 30) {
|
||||
PX4_ERR("failed to stop");
|
||||
}
|
||||
}
|
||||
|
||||
void SendEvent::initialize_trampoline(void *arg)
|
||||
{
|
||||
send_event_obj = new SendEvent();
|
||||
SendEvent *send_event = new SendEvent();
|
||||
|
||||
if (!send_event_obj) {
|
||||
if (!send_event) {
|
||||
PX4_ERR("alloc failed");
|
||||
return;
|
||||
}
|
||||
|
||||
send_event_obj->start();
|
||||
send_event->start();
|
||||
_object = send_event;
|
||||
}
|
||||
|
||||
void
|
||||
@@ -133,13 +110,13 @@ SendEvent::cycle_trampoline(void *arg)
|
||||
|
||||
void SendEvent::cycle()
|
||||
{
|
||||
if (_task_should_exit) {
|
||||
if (should_exit()) {
|
||||
if (_vehicle_command_sub >= 0) {
|
||||
orb_unsubscribe(_vehicle_command_sub);
|
||||
_vehicle_command_sub = -1;
|
||||
}
|
||||
|
||||
_task_is_running = false;
|
||||
exit_and_cleanup();
|
||||
return;
|
||||
}
|
||||
|
||||
@@ -213,63 +190,44 @@ void SendEvent::answer_command(const vehicle_command_s &cmd, unsigned result)
|
||||
}
|
||||
|
||||
|
||||
void SendEvent::print_status()
|
||||
{
|
||||
PX4_INFO("running");
|
||||
}
|
||||
|
||||
|
||||
|
||||
static void print_usage(const char *reason = nullptr)
|
||||
int SendEvent::print_usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
PX4_WARN("%s\n", reason);
|
||||
printf("%s\n\n", reason);
|
||||
}
|
||||
|
||||
PX4_INFO("usage: send_event {start_listening|stop_listening|status|temperature_calibration}\n"
|
||||
"\tstart_listening: start background task to listen to events\n"
|
||||
"\ttemperature_calibration [-g] [-a] [-b]: start temperature calibration task\n"
|
||||
"\t all sensors if no option given, 1 or several of gyro, accel, baro otherwise\n"
|
||||
);
|
||||
}
|
||||
PRINT_MODULE_DESCRIPTION(
|
||||
R"DESCR_STR(
|
||||
Background process running periodically on the LP work queue to perform housekeeping tasks.
|
||||
It is currently only responsible for temperature calibration.
|
||||
|
||||
The tasks can be started via CLI or uORB topics (vehicle_command from MAVLink, etc.).
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("send_event", "system");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the background task");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("temperature_calibration", "Run temperature calibration process");
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('g', "calibrate the gyro", true);
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('a', "calibrate the accel", true);
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('b', "calibrate the baro (if none of these is given, all will be calibrated)", true);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
int send_event_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 2) {
|
||||
print_usage();
|
||||
return 1;
|
||||
}
|
||||
return SendEvent::main(argc, argv);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "start_listening")) {
|
||||
|
||||
if (send_event_obj) {
|
||||
PX4_INFO("already running");
|
||||
return -1;
|
||||
}
|
||||
int SendEvent::custom_command(int argc, char *argv[])
|
||||
{
|
||||
if (!strcmp(argv[0], "temperature_calibration")) {
|
||||
|
||||
return SendEvent::initialize();
|
||||
|
||||
} else if (!strcmp(argv[1], "stop_listening")) {
|
||||
if (send_event_obj) {
|
||||
send_event_obj->stop();
|
||||
delete send_event_obj;
|
||||
send_event_obj = nullptr;
|
||||
}
|
||||
|
||||
} else if (!strcmp(argv[1], "status")) {
|
||||
|
||||
if (send_event_obj) {
|
||||
send_event_obj->print_status();
|
||||
|
||||
} else {
|
||||
PX4_INFO("not running");
|
||||
}
|
||||
|
||||
} else if (!strcmp(argv[1], "temperature_calibration")) {
|
||||
|
||||
if (!send_event_obj) {
|
||||
if (!is_running()) {
|
||||
PX4_ERR("background task not running");
|
||||
return -1;
|
||||
}
|
||||
|
||||
@@ -34,12 +34,13 @@
|
||||
#pragma once
|
||||
|
||||
#include <px4_workqueue.h>
|
||||
#include <px4_module.h>
|
||||
#include <uORB/topics/vehicle_command.h>
|
||||
#include <uORB/topics/vehicle_command_ack.h>
|
||||
|
||||
extern "C" __EXPORT int send_event_main(int argc, char *argv[]);
|
||||
|
||||
class SendEvent
|
||||
class SendEvent : public ModuleBase<SendEvent>
|
||||
{
|
||||
public:
|
||||
SendEvent();
|
||||
@@ -47,14 +48,13 @@ public:
|
||||
/** Initialize class in the same context as the work queue. And start the background listener.
|
||||
*
|
||||
* @return 0 if successful, <0 on error */
|
||||
static int initialize();
|
||||
static int task_spawn(int argc, char *argv[]);
|
||||
|
||||
/** Stop background listener */
|
||||
void stop();
|
||||
/** @see ModuleBase */
|
||||
static int custom_command(int argc, char *argv[]);
|
||||
|
||||
bool is_running() { return _task_is_running; }
|
||||
|
||||
void print_status();
|
||||
/** @see ModuleBase */
|
||||
static int print_usage(const char *reason = nullptr);
|
||||
|
||||
private:
|
||||
|
||||
@@ -78,8 +78,6 @@ private:
|
||||
/** return an ACK to a vehicle_command */
|
||||
void answer_command(const vehicle_command_s &cmd, unsigned result);
|
||||
|
||||
volatile bool _task_should_exit = false;
|
||||
volatile bool _task_is_running = false;
|
||||
static struct work_s _work;
|
||||
int _vehicle_command_sub = -1;
|
||||
orb_advert_t _command_ack_pub = nullptr;
|
||||
|
||||
Reference in New Issue
Block a user