42 #include <px4_platform_common/log.h> 49 #include "px4_middleware.h" 50 #include "px4_defines.h" 74 PX4_WARN(
"Successful after memset... ");
77 if (pub_fd ==
nullptr) {
78 PX4_WARN(
"Error: advertizing pwm_input topic");
84 if (pub_sc ==
nullptr) {
85 PX4_WARN(
"Error: advertizing sensor_combined topic");
93 while (!
appState.exitRequested() && i < 10) {
95 PX4_INFO(
" Doing work...");
111 if (pub_id_esc_status == 0) {
112 PX4_ERR(
"error publishing esc_status");
117 PX4_ERR(
"[%d]Error publishing the esc_status message", i);
123 if (sub_vc == PX4_ERROR) {
124 PX4_ERR(
"Error subscribing to vehicle_command topic");
130 PX4_DEBUG(
"[%d] Doing work...", i);
131 bool updated =
false;
135 PX4_WARN(
"[%d]vechile command status is updated... reading new value", i);
138 PX4_ERR(
"[%d]Error calling orb copy for vechicle... ", i);
143 PX4_ERR(
"[%d]Error publishing the esc_status message", i);
148 PX4_WARN(
"[%d] vechicle command topic is not updated", i);
152 PX4_ERR(
"[%d]Error checking the updated status for vehicle command ", i);
171 for (
int i = 0; i < 10; ++i) {
172 PX4_INFO(
"In While Loop: B4 Sleep for[%d] seconds [%" PRIu64
"]", i + 1,
hrt_absolute_time());
173 usleep((i + 1) * 1000000);
174 PX4_INFO(
"In While Loop: After Sleep for[%d] seconds [%" PRIu64
"]", i + 1,
hrt_absolute_time());
177 PX4_INFO(
"exiting sleep test...");
184 static const char TEST_FILE_PATH[] =
"./test.txt";
190 fp = fopen(TEST_FILE_PATH,
"r");
193 PX4_WARN(
"unable to open file[%s] for reading", TEST_FILE_PATH);
206 PX4_INFO(
"Successfully opened file [%s]", TEST_FILE_PATH);
struct vehicle_command_s m_vc
int orb_copy(const struct orb_metadata *meta, int handle, void *buffer)
API for the uORB lightweight object broker.
orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data)
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.
struct esc_status_s m_esc_status
static px4::AppState appState
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
int orb_check(int handle, bool *updated)
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).