41 #include <px4_platform_common/log.h> 63 PX4_ERR(
"Could not send command");
70 PX4_ERR(
"Could not get return value");
87 for (
size_t i = 0; i < argList.size(); i++) {
90 if (i < argList.size() - 1) {
95 if (cmd.size() >= qshell_req.MAX_STRLEN) {
96 PX4_ERR(
"Command too long: %d >= %d", (
int) cmd.size(), (int) qshell_req.MAX_STRLEN);
100 PX4_INFO(
"Send cmd: '%s'", cmd.c_str());
102 qshell_req.
strlen = cmd.size();
103 strcpy((
char *)qshell_req.
cmd, cmd.c_str());
118 PX4_ERR(
"could not subscribe to retval");
135 PX4_WARN(
"Ignoring return value with wrong sequence");
149 PX4_ERR(
"command timed out");
static uint32_t _current_sequence
int orb_copy(const struct orb_metadata *meta, int handle, void *buffer)
int _send_cmd(std::vector< std::string > &argList)
static px4::AppState appState
High-resolution timer with callouts and timekeeping.
int orb_subscribe(const struct orb_metadata *meta)
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
static hrt_abstime hrt_elapsed_time(const hrt_abstime *then)
Compute the delta between a timestamp taken in the past and now.
static orb_advert_t _pub_qshell_req
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
static int _sub_qshell_retval
uint32_t request_sequence
int orb_check(int handle, bool *updated)
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
static int orb_publish_auto(const struct orb_metadata *meta, orb_advert_t *handle, const void *data, int *instance, int priority)
Advertise as the publisher of a topic.