|
|
|
@ -32,7 +32,7 @@
@@ -32,7 +32,7 @@
|
|
|
|
|
****************************************************************************/ |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @file px4_mavlink_debug.c |
|
|
|
|
* @file px4_mavlink_debug.cpp |
|
|
|
|
* Debug application example for PX4 autopilot |
|
|
|
|
* |
|
|
|
|
* @author Example User <mail@example.com> |
|
|
|
@ -41,6 +41,7 @@
@@ -41,6 +41,7 @@
|
|
|
|
|
#include <px4_config.h> |
|
|
|
|
#include <unistd.h> |
|
|
|
|
#include <stdio.h> |
|
|
|
|
#include <string.h> |
|
|
|
|
#include <poll.h> |
|
|
|
|
|
|
|
|
|
#include <systemlib/err.h> |
|
|
|
@ -50,39 +51,53 @@
@@ -50,39 +51,53 @@
|
|
|
|
|
#include <uORB/topics/debug_key_value.h> |
|
|
|
|
#include <uORB/topics/debug_value.h> |
|
|
|
|
#include <uORB/topics/debug_vect.h> |
|
|
|
|
#include <uORB/topics/debug_array.h> |
|
|
|
|
|
|
|
|
|
__EXPORT int px4_mavlink_debug_main(int argc, char *argv[]); |
|
|
|
|
extern "C" __EXPORT int px4_mavlink_debug_main(int argc, char *argv[]); |
|
|
|
|
|
|
|
|
|
int px4_mavlink_debug_main(int argc, char *argv[]) |
|
|
|
|
{ |
|
|
|
|
printf("Hello Debug!\n"); |
|
|
|
|
|
|
|
|
|
/* advertise named debug value */ |
|
|
|
|
struct debug_key_value_s dbg_key = { .key = "velx", .value = 0.0f }; |
|
|
|
|
struct debug_key_value_s dbg_key; |
|
|
|
|
strncpy(dbg_key.key, "velx", 10); |
|
|
|
|
dbg_key.value = 0.0f; |
|
|
|
|
orb_advert_t pub_dbg_key = orb_advertise(ORB_ID(debug_key_value), &dbg_key); |
|
|
|
|
|
|
|
|
|
/* advertise indexed debug value */ |
|
|
|
|
struct debug_value_s dbg_ind = { .ind = 42, .value = 0.5f }; |
|
|
|
|
struct debug_value_s dbg_ind; |
|
|
|
|
dbg_ind.ind = 42; |
|
|
|
|
dbg_ind.value = 0.5f; |
|
|
|
|
orb_advert_t pub_dbg_ind = orb_advertise(ORB_ID(debug_value), &dbg_ind); |
|
|
|
|
|
|
|
|
|
/* advertise debug vect */ |
|
|
|
|
struct debug_vect_s dbg_vect = { .name = "vel3D", .x = 1.0f, .y = 2.0f, .z = 3.0f }; |
|
|
|
|
struct debug_vect_s dbg_vect; |
|
|
|
|
strncpy(dbg_vect.name, "vel3D", 10); |
|
|
|
|
dbg_vect.x = 1.0f; |
|
|
|
|
dbg_vect.y = 2.0f; |
|
|
|
|
dbg_vect.z = 3.0f; |
|
|
|
|
orb_advert_t pub_dbg_vect = orb_advertise(ORB_ID(debug_vect), &dbg_vect); |
|
|
|
|
|
|
|
|
|
/* advertise debug array */ |
|
|
|
|
struct debug_array_s dbg_array; |
|
|
|
|
dbg_array.id = 1; |
|
|
|
|
strncpy(dbg_array.name, "dbg_array", 10); |
|
|
|
|
orb_advert_t pub_dbg_array = orb_advertise(ORB_ID(debug_array), &dbg_array); |
|
|
|
|
|
|
|
|
|
int value_counter = 0; |
|
|
|
|
|
|
|
|
|
while (value_counter < 100) { |
|
|
|
|
uint64_t timestamp_us = hrt_absolute_time(); |
|
|
|
|
uint32_t timestamp_ms = timestamp_us / 1000; |
|
|
|
|
|
|
|
|
|
/* send one named value */ |
|
|
|
|
dbg_key.value = value_counter; |
|
|
|
|
dbg_key.timestamp = timestamp_ms * 1e3f; |
|
|
|
|
dbg_key.timestamp = timestamp_us; |
|
|
|
|
orb_publish(ORB_ID(debug_key_value), pub_dbg_key, &dbg_key); |
|
|
|
|
|
|
|
|
|
/* send one indexed value */ |
|
|
|
|
dbg_ind.value = 0.5f * value_counter; |
|
|
|
|
dbg_ind.timestamp = timestamp_ms * 1e3f; |
|
|
|
|
dbg_ind.timestamp = timestamp_us; |
|
|
|
|
orb_publish(ORB_ID(debug_value), pub_dbg_ind, &dbg_ind); |
|
|
|
|
|
|
|
|
|
/* send one vector */ |
|
|
|
@ -92,6 +107,14 @@ int px4_mavlink_debug_main(int argc, char *argv[])
@@ -92,6 +107,14 @@ int px4_mavlink_debug_main(int argc, char *argv[])
|
|
|
|
|
dbg_vect.timestamp = timestamp_us; |
|
|
|
|
orb_publish(ORB_ID(debug_vect), pub_dbg_vect, &dbg_vect); |
|
|
|
|
|
|
|
|
|
/* send one array */ |
|
|
|
|
for (size_t i = 0; i < debug_array_s::ARRAY_SIZE; i++) { |
|
|
|
|
dbg_array.data[i] = value_counter + i * 0.01f; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
dbg_array.timestamp = timestamp_us; |
|
|
|
|
orb_publish(ORB_ID(debug_array), pub_dbg_array, &dbg_array); |
|
|
|
|
|
|
|
|
|
warnx("sent one more value.."); |
|
|
|
|
|
|
|
|
|
value_counter++; |