Doxy documenting in send_event.cpp/h and px4_module.h.

This commit is contained in:
mcsauder
2018-08-02 04:04:10 -06:00
committed by Beat Küng
parent 5a678295b3
commit bf87270ded
3 changed files with 90 additions and 42 deletions

View File

@@ -94,10 +94,10 @@ int SendEvent::start()
return 0;
}
// subscribe to the topics
// Subscribe to the topics.
_subscriber_handler.subscribe();
// Kick off the cycling. We can call it directly because we're already in the work queue context
// Kick off the cycling. We can call it directly because we're already in the work queue context.
cycle();
return 0;
@@ -116,8 +116,7 @@ void SendEvent::initialize_trampoline(void *arg)
_object = send_event;
}
void
SendEvent::cycle_trampoline(void *arg)
void SendEvent::cycle_trampoline(void *arg)
{
SendEvent *obj = reinterpret_cast<SendEvent *>(arg);
@@ -236,13 +235,6 @@ The tasks can be started via CLI or uORB topics (vehicle_command from MAVLink, e
return 0;
}
int send_event_main(int argc, char *argv[])
{
return SendEvent::main(argc, argv);
}
int SendEvent::custom_command(int argc, char *argv[])
{
if (!strcmp(argv[0], "temperature_calibration")) {
@@ -301,4 +293,9 @@ int SendEvent::custom_command(int argc, char *argv[])
return 0;
}
int send_event_main(int argc, char *argv[])
{
return SendEvent::main(argc, argv);
}
} /* namespace events */