mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 22:58:10 +08:00
Added simple, but complete code example
This commit is contained in:
@@ -0,0 +1,42 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Basic example application
|
||||
#
|
||||
|
||||
APPNAME = px4_simple_app
|
||||
PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||
STACKSIZE = 2048
|
||||
|
||||
include $(APPDIR)/mk/app.mk
|
||||
@@ -0,0 +1,115 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Example User <mail@example.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4_simple_app.c
|
||||
* Minimal application example for PX4 autopilot
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <poll.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
|
||||
__EXPORT int px4_simple_app_main(int argc, char *argv[]);
|
||||
|
||||
int px4_simple_app_main(int argc, char *argv[])
|
||||
{
|
||||
printf("Hello Sky!\n");
|
||||
|
||||
/* subscribe to sensor_combined topic */
|
||||
int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined));
|
||||
orb_set_interval(sensor_sub_fd, 1000);
|
||||
|
||||
/* advertise attitude topic */
|
||||
struct vehicle_attitude_s att;
|
||||
memset(&att, 0, sizeof(att));
|
||||
int att_pub_fd = orb_advertise(ORB_ID(vehicle_attitude), &att);
|
||||
|
||||
/* one could wait for multiple topics with this technique, just using one here */
|
||||
struct pollfd fds[] = {
|
||||
{ .fd = sensor_sub_fd, .events = POLLIN },
|
||||
/* there could be more file descriptors here, in the form like:
|
||||
* { .fd = other_sub_fd, .events = POLLIN },
|
||||
*/
|
||||
};
|
||||
|
||||
int error_counter = 0;
|
||||
|
||||
while (true) {
|
||||
/* wait for sensor update of 1 file descriptor for 1000 ms (1 second) */
|
||||
int poll_ret = poll(fds, 1, 1000);
|
||||
|
||||
/* handle the poll result */
|
||||
if (poll_ret == 0) {
|
||||
/* this means none of our providers is giving us data */
|
||||
printf("[px4_simple_app] Got no data within a second\n");
|
||||
} else if (poll_ret < 0) {
|
||||
/* this is seriously bad - should be an emergency */
|
||||
if (error_counter < 10 || error_counter % 50 == 0) {
|
||||
/* use a counter to prevent flooding (and slowing us down) */
|
||||
printf("[px4_simple_app] ERROR return value from poll(): %d\n"
|
||||
, poll_ret);
|
||||
}
|
||||
error_counter++;
|
||||
} else {
|
||||
|
||||
if (fds[0].revents & POLLIN) {
|
||||
/* obtained data for the first file descriptor */
|
||||
struct sensor_combined_s raw;
|
||||
/* copy sensors raw data into local buffer */
|
||||
orb_copy(ORB_ID(sensor_combined), sensor_sub_fd, &raw);
|
||||
printf("[px4_simple_app] Accelerometer:\t%8.4f\t%8.4f\t%8.4f\n",
|
||||
(double)raw.accelerometer_m_s2[0],
|
||||
(double)raw.accelerometer_m_s2[1],
|
||||
(double)raw.accelerometer_m_s2[2]);
|
||||
|
||||
/* set att and publish this information for other apps */
|
||||
att.roll = raw.accelerometer_m_s2[0];
|
||||
att.pitch = raw.accelerometer_m_s2[1];
|
||||
att.yaw = raw.accelerometer_m_s2[2];
|
||||
orb_publish(ORB_ID(vehicle_attitude), att_pub_fd, &att);
|
||||
}
|
||||
/* there could be more file descriptors here, in the form like:
|
||||
* if (fds[1..n].revents & POLLIN) {}
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
+34
-11
@@ -112,6 +112,7 @@ static int fd_barometer = -1;
|
||||
static int fd_adc = -1;
|
||||
|
||||
static bool thread_should_exit = false;
|
||||
static bool thread_running = false;
|
||||
static int sensors_task;
|
||||
|
||||
/* Private functions declared static */
|
||||
@@ -136,6 +137,11 @@ static int sensor_pub;
|
||||
*/
|
||||
__EXPORT int sensors_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Print the usage
|
||||
*/
|
||||
static void usage(const char *reason);
|
||||
|
||||
/**
|
||||
* Initialize all sensor drivers.
|
||||
*
|
||||
@@ -425,6 +431,8 @@ int sensors_thread_main(int argc, char *argv[])
|
||||
/* Enable high resolution timer callback to unblock main thread, run after 2 ms */
|
||||
hrt_call_every(&sensors_hrt_call, 2000, SENSOR_INTERVAL_MICROSEC, &sensors_timer_loop, NULL);
|
||||
|
||||
thread_running = true;
|
||||
|
||||
while (1) {
|
||||
pthread_mutex_lock(&sensors_read_ready_mutex);
|
||||
|
||||
@@ -909,6 +917,8 @@ int sensors_thread_main(int argc, char *argv[])
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
if (thread_should_exit) break;
|
||||
}
|
||||
|
||||
/* Never really getting here */
|
||||
@@ -922,39 +932,52 @@ int sensors_thread_main(int argc, char *argv[])
|
||||
|
||||
printf("[sensors] exiting.\n");
|
||||
|
||||
thread_running = false;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/**
|
||||
* Print the usage
|
||||
*/
|
||||
static void usage(const char *reason);
|
||||
|
||||
static void
|
||||
usage(const char *reason)
|
||||
{
|
||||
if (reason)
|
||||
fprintf(stderr, "%s\n", reason);
|
||||
fprintf(stderr, "usage: sensors {start|stop}\n");
|
||||
fprintf(stderr, "usage: sensors {start|stop|status}\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
int sensors_main(int argc, char *argv[])
|
||||
{
|
||||
int ch;
|
||||
|
||||
if (argc < 1)
|
||||
usage("missing command");
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
thread_should_exit = false;
|
||||
sensors_task = task_create("sensors", SCHED_PRIORITY_MAX - 5, 4096, sensors_thread_main, NULL);
|
||||
if (thread_running) {
|
||||
printf("sensors app already running\n");
|
||||
} else {
|
||||
thread_should_exit = false;
|
||||
sensors_task = task_create("sensors", SCHED_PRIORITY_MAX - 5, 4096, sensors_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
}
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "stop")) {
|
||||
thread_should_exit = true;
|
||||
if (!thread_running) {
|
||||
printf("sensors app not started\n");
|
||||
} else {
|
||||
printf("stopping sensors app");
|
||||
thread_should_exit = true;
|
||||
}
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
if (thread_running) {
|
||||
printf("\tsensors app is running\n");
|
||||
} else {
|
||||
printf("\tsensors app not started\n");
|
||||
}
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
||||
+4
-3
@@ -728,7 +728,8 @@ uorb_main(int argc, char *argv[])
|
||||
|
||||
if (g_dev != nullptr) {
|
||||
fprintf(stderr, "[uorb] already loaded\n");
|
||||
return -EBUSY;
|
||||
/* user wanted to start uorb, its already running, no error */
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* create the driver */
|
||||
@@ -759,10 +760,10 @@ uorb_main(int argc, char *argv[])
|
||||
/*
|
||||
* Print driver information.
|
||||
*/
|
||||
if (!strcmp(argv[1], "info"))
|
||||
if (!strcmp(argv[1], "status"))
|
||||
return info();
|
||||
|
||||
fprintf(stderr, "unrecognised command, try 'start', 'test' or 'info'\n");
|
||||
fprintf(stderr, "unrecognised command, try 'start', 'test' or 'status'\n");
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
|
||||
@@ -52,6 +52,10 @@ CONFIGURED_APPS += systemcmds/boardinfo
|
||||
CONFIGURED_APPS += systemcmds/mixer
|
||||
#CONFIGURED_APPS += systemcmds/calibration
|
||||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/hello_sky
|
||||
# CONFIGURED_APPS += examples/px4_simple_app
|
||||
|
||||
CONFIGURED_APPS += uORB
|
||||
|
||||
ifeq ($(CONFIG_MAVLINK),y)
|
||||
|
||||
Reference in New Issue
Block a user