Merge branch 'master' into ms5611_newmath

This commit is contained in:
px4dev 2012-09-03 12:35:36 -07:00
commit f92139f53b
179 changed files with 3051 additions and 987 deletions

View File

@ -1,7 +1,7 @@
Multirotor mixer for PX4FMU
===========================
This file defines a single mixer for a quadrotor in the + configuration, with 10% contribution from
roll and pitch and 20% contribution from yaw and no deadband.
This file defines a single mixer for a quadrotor in the + configuration. All controls
are mixed 100%.
R: 4+ 1000 1000 2000 0
R: 4+ 10000 10000 10000 0

View File

@ -1,7 +1,7 @@
Multirotor mixer for PX4FMU
===========================
This file defines a single mixer for a quadrotor in the X configuration, with 10% contribution from
roll and pitch and 20% contribution from yaw and no deadband.
This file defines a single mixer for a quadrotor in the X configuration. All controls
are mixed 100%.
R: 4x 1000 1000 2000 0
R: 4x 10000 10000 10000 0

View File

@ -0,0 +1,40 @@
#
# Startup for X-quad on FMU1.5/1.6
#
echo "[init] uORB"
uorb start
echo "[init] eeprom"
eeprom start
if [ -f /eeprom/parameters]
then
eeprom load_param /eeprom/parameters
fi
echo "[init] sensors"
#bma180 start
#l3gd20 start
mpu6000 start
hmc5883 start
ms5611 start
sensors start
echo "[init] mavlink"
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
echo "[init] commander"
commander start
echo "[init] attitude control"
attitude_estimator_bm &
multirotor_att_control start
echo "[init] starting PWM output"
fmu mode_pwm
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
echo "[init] startup done, exiting"
exit

View File

@ -289,5 +289,19 @@
threds to no more than 3 of each priority. Bad things happen
when the existing logic tried to created several hundred test
treads!
* apps/nshlib/nsh.h: Both CONFIG_LIBC_STRERROR and CONFIG_NSH_STRERROR
must be defined to use strerror() with NSH.
* apps/examples/*/*_main.c, system/i2c/i2c_main.c, and others: Added
configuration variable CONFIG_USER_ENTRYPOINT that may be used to change
the default entry from user_start to some other symbol. Contributed by
Kate.
* apps/netutils/webserver/httpd/c: Fix a typo that as introduced in
version r4402: 'lese' instead of 'else' (Noted by Max Holtzberg).
* tools/mkfsdata.pl: The uIP web server CGI image making perl script was
moved from apps/netutils/webserver/makefsdata to nuttx/tools/mkfsdata.pl
(Part of a larger change submitted by Max Holtzberg).
* apps/netutils/webserver, apps/examples/uip, and apps/include/netutils/httpd.h:
The "canned" version of the uIP web servers content that was at
netutils/webserver/httpd_fsdata.c has been replaced with a dynamically
built configuration located at apps/examples/uip (Contributed by
Max Holtzberg).

View File

@ -118,7 +118,7 @@ the NuttX configuration file:
CONFIG_BUILTIN_APP_START=<application name>
that application shall be invoked immediately after system starts
*instead* of the normal, default "user_start" entry point.
*instead* of the default "user_start" entry point.
Note that <application name> must be provided as: "hello",
will call:

View File

@ -63,12 +63,18 @@ __EXPORT int ardrone_interface_main(int argc, char *argv[]);
static bool thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
static int ardrone_interface_task; /**< Handle of deamon task / thread */
static int ardrone_write; /**< UART to write AR.Drone commands to */
/**
* Mainloop of ardrone_interface.
*/
int ardrone_interface_thread_main(int argc, char *argv[]);
/**
* Open the UART connected to the motor controllers
*/
static int ardrone_open_uart(struct termios *uart_config_original);
/**
* Print the correct usage.
*/
@ -128,63 +134,74 @@ int ardrone_interface_main(int argc, char *argv[])
exit(1);
}
static int ardrone_open_uart(struct termios *uart_config_original)
{
/* baud rate */
int speed = B115200;
int uart;
const char* uart_name = "/dev/ttyS1";
/* open uart */
printf("[ardrone_interface] UART is /dev/ttyS1, baud rate is 115200");
uart = open(uart_name, O_RDWR | O_NOCTTY);
/* Try to set baud rate */
struct termios uart_config;
int termios_state;
/* Back up the original uart configuration to restore it after exit */
if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
fprintf(stderr, "[ardrone_interface] ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state);
close(uart);
return -1;
}
/* Fill the struct for the new configuration */
tcgetattr(uart, &uart_config);
/* Clear ONLCR flag (which appends a CR for every LF) */
uart_config.c_oflag &= ~ONLCR;
/* Set baud rate */
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
fprintf(stderr, "[ardrone_interface] ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
close(uart);
return -1;
}
if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
fprintf(stderr, "[ardrone_interface] ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name);
close(uart);
return -1;
}
return uart;
}
int ardrone_interface_thread_main(int argc, char *argv[])
{
/* welcome user */
printf("[ardrone_interface] Control started, taking over motors\n");
/* default values for arguments */
char *ardrone_uart_name = "/dev/ttyS1";
/* File descriptors */
int ardrone_write;
int gpios;
enum {
CONTROL_MODE_RATES = 0,
CONTROL_MODE_ATTITUDE = 1,
} control_mode = CONTROL_MODE_ATTITUDE;
char *commandline_usage = "\tusage: ardrone_interface -d ardrone-devicename -m mode\n\tmodes are:\n\t\trates\n\t\tattitude\n";
char *commandline_usage = "\tusage: ardrone_interface start|status|stop [-t for motor test (10%% thrust)]\n";
bool motor_test_mode = false;
/* read commandline arguments */
for (int i = 1; i < argc; i++) {
if (strcmp(argv[i], "-d") == 0 || strcmp(argv[i], "--device") == 0) { //ardrone set
if (argc > i + 1) {
ardrone_uart_name = argv[i + 1];
} else {
printf(commandline_usage);
return ERROR;
}
} else if (strcmp(argv[i], "-m") == 0 || strcmp(argv[i], "--mode") == 0) {
if (argc > i + 1) {
if (strcmp(argv[i + 1], "rates") == 0) {
control_mode = CONTROL_MODE_RATES;
} else if (strcmp(argv[i + 1], "attitude") == 0) {
control_mode = CONTROL_MODE_ATTITUDE;
} else {
printf(commandline_usage);
return ERROR;
}
} else {
printf(commandline_usage);
return ERROR;
}
} else if (strcmp(argv[i], "-t") == 0 || strcmp(argv[i], "--test") == 0) {
if (strcmp(argv[i], "-t") == 0 || strcmp(argv[i], "--test") == 0) {
motor_test_mode = true;
}
}
/* open uarts */
printf("[ardrone_interface] AR.Drone UART is %s\n", ardrone_uart_name);
ardrone_write = open(ardrone_uart_name, O_RDWR | O_NOCTTY | O_NDELAY);
struct termios uart_config_original;
ardrone_write = ardrone_open_uart(&uart_config_original);
if (ardrone_write < 0) {
fprintf(stderr, "[ardrone_interface] Failed opening AR.Drone UART, exiting.\n");
exit(ERROR);
@ -279,11 +296,19 @@ int ardrone_interface_thread_main(int argc, char *argv[])
counter++;
}
/* restore old UART config */
int termios_state;
if ((termios_state = tcsetattr(ardrone_write, TCSANOW, &uart_config_original)) < 0) {
fprintf(stderr, "[ardrone_interface] ERROR setting baudrate / termios config for (tcsetattr)\n");
}
printf("[ardrone_interface] Restored original UART config, exiting..\n");
/* close uarts */
close(ardrone_write);
ar_multiplexing_deinit(gpios);
printf("[ardrone_interface] ending now...\n\n");
fflush(stdout);
thread_running = false;

View File

@ -43,6 +43,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_controls.h>
#include <systemlib/systemlib.h>
#include <arch/board/up_hrt.h>
#include <mavlink/mavlink_log.h>
@ -121,7 +122,7 @@ int do_state_update(int status_pub, struct vehicle_status_s *current_status, con
if (current_status->state_machine == SYSTEM_STATE_STANDBY
|| current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
/* set system flags according to state */
current_status->flag_system_armed = true;
current_status->flag_system_armed = false;
mavlink_log_critical(mavlink_fd, "[commander] Switched to PREFLIGHT state");
} else {
invalid_state = true;
@ -198,6 +199,10 @@ int do_state_update(int status_pub, struct vehicle_status_s *current_status, con
if (invalid_state == false || old_state != new_state) {
current_status->state_machine = new_state;
state_machine_publish(status_pub, current_status, mavlink_fd);
struct actuator_armed_s armed;
armed.armed = current_status->flag_system_armed;
orb_advert_t armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed);
orb_publish(ORB_ID(actuator_armed), armed_pub, &armed);
ret = OK;
}
if (invalid_state) {

View File

@ -1345,10 +1345,14 @@ examples/uip
file in the configuration driver with instruction to build applications
like:
CONFIGURED_APPS += uiplib
CONFIGURED_APPS += dhcpc
CONFIGURED_APPS += resolv
CONFIGURED_APPS += webserver
CONFIGURED_APPS += uiplib
CONFIGURED_APPS += dhcpc
CONFIGURED_APPS += resolv
CONFIGURED_APPS += webserver
NOTE: This example does depend on the perl script at
nuttx/tools/mkfsdata.pl. You must have perl installed on your
development system at /usr/bin/perl.
examples/usbserial
^^^^^^^^^^^^^^^^^^

View File

@ -57,14 +57,6 @@
* Pre-processor Definitions
****************************************************************************/
#ifdef CONFIG_NSH_BUILTIN_APPS
# define MAIN_NAME adc_main
# define MAIN_STRING "adc_main: "
#else
# define MAIN_NAME user_start
# define MAIN_STRING "user_start: "
#endif
/****************************************************************************
* Private Types
****************************************************************************/
@ -223,10 +215,10 @@ static void parse_args(FAR struct adc_state_s *adc, int argc, FAR char **argv)
****************************************************************************/
/****************************************************************************
* Name: user_start/adc_main
* Name: adc_main
****************************************************************************/
int MAIN_NAME(int argc, char *argv[])
int adc_main(int argc, char *argv[])
{
struct adc_msg_s sample[CONFIG_EXAMPLES_ADC_GROUPSIZE];
size_t readsize;
@ -244,11 +236,11 @@ int MAIN_NAME(int argc, char *argv[])
* this test.
*/
message(MAIN_STRING "Initializing external ADC device\n");
message("adc_main: Initializing external ADC device\n");
ret = adc_devinit();
if (ret != OK)
{
message(MAIN_STRING "adc_devinit failed: %d\n", ret);
message("adc_main: adc_devinit failed: %d\n", ret);
errval = 1;
goto errout;
}
@ -276,18 +268,18 @@ int MAIN_NAME(int argc, char *argv[])
*/
#if defined(CONFIG_NSH_BUILTIN_APPS) || defined(CONFIG_EXAMPLES_ADC_NSAMPLES)
message(MAIN_STRING "g_adcstate.count: %d\n", g_adcstate.count);
message("adc_main: g_adcstate.count: %d\n", g_adcstate.count);
#endif
/* Open the ADC device for reading */
message(MAIN_STRING "Hardware initialized. Opening the ADC device: %s\n",
message("adc_main: Hardware initialized. Opening the ADC device: %s\n",
g_adcstate.devpath);
fd = open(g_adcstate.devpath, O_RDONLY);
if (fd < 0)
{
message(MAIN_STRING "open %s failed: %d\n", g_adcstate.devpath, errno);
message("adc_main: open %s failed: %d\n", g_adcstate.devpath, errno);
errval = 2;
goto errout_with_dev;
}
@ -322,17 +314,17 @@ int MAIN_NAME(int argc, char *argv[])
errval = errno;
if (errval != EINTR)
{
message(MAIN_STRING "read %s failed: %d\n",
message("adc_main: read %s failed: %d\n",
g_adcstate.devpath, errval);
errval = 3;
goto errout_with_dev;
}
message(MAIN_STRING "Interrupted read...\n");
message("adc_main: Interrupted read...\n");
}
else if (nbytes == 0)
{
message(MAIN_STRING "No data read, Ignoring\n");
message("adc_main: No data read, Ignoring\n");
}
/* Print the sample data on successful return */
@ -342,7 +334,7 @@ int MAIN_NAME(int argc, char *argv[])
int nsamples = nbytes / sizeof(struct adc_msg_s);
if (nsamples * sizeof(struct adc_msg_s) != nbytes)
{
message(MAIN_STRING "read size=%d is not a multiple of sample size=%d, Ignoring\n",
message("adc_main: read size=%d is not a multiple of sample size=%d, Ignoring\n",
nbytes, sizeof(struct adc_msg_s));
}
else

View File

@ -130,16 +130,6 @@
#define NUM_BUTTONS (MAX_BUTTON - MIN_BUTTON + 1)
#define BUTTON_INDEX(b) ((b)-MIN_BUTTON)
/* Is this being built as an NSH built-in application? */
#ifdef CONFIG_NSH_BUILTIN_APPS
# define MAIN_NAME buttons_main
# define MAIN_STRING "buttons_main: "
#else
# define MAIN_NAME user_start
# define MAIN_STRING "user_start: "
#endif
/****************************************************************************
* Private Types
****************************************************************************/
@ -399,10 +389,10 @@ static int button7_handler(int irq, FAR void *context)
****************************************************************************/
/****************************************************************************
* user_start/buttons_main
* buttons_main
****************************************************************************/
int MAIN_NAME(int argc, char *argv[])
int buttons_main(int argc, char *argv[])
{
uint8_t newset;
irqstate_t flags;

View File

@ -76,14 +76,6 @@
# define MAX_ID (1 << 11)
#endif
#ifdef CONFIG_NSH_BUILTIN_APPS
# define MAIN_NAME can_main
# define MAIN_STRING "can_main: "
#else
# define MAIN_NAME user_start
# define MAIN_STRING "user_start: "
#endif
/****************************************************************************
* Private Types
****************************************************************************/
@ -109,10 +101,10 @@
****************************************************************************/
/****************************************************************************
* Name: user_start/can_main
* Name: can_main
****************************************************************************/
int MAIN_NAME(int argc, char *argv[])
int can_main(int argc, char *argv[])
{
#ifndef CONFIG_EXAMPLES_CAN_READONLY
struct can_msg_s txmsg;
@ -150,31 +142,31 @@ int MAIN_NAME(int argc, char *argv[])
{
nmsgs = strtol(argv[1], NULL, 10);
}
message(MAIN_STRING "nmsgs: %d\n", nmsgs);
message("can_main: nmsgs: %d\n", nmsgs);
#elif defined(CONFIG_EXAMPLES_CAN_NMSGS)
message(MAIN_STRING "nmsgs: %d\n", CONFIG_EXAMPLES_CAN_NMSGS);
message("can_main: nmsgs: %d\n", CONFIG_EXAMPLES_CAN_NMSGS);
#endif
/* Initialization of the CAN hardware is performed by logic external to
* this test.
*/
message(MAIN_STRING "Initializing external CAN device\n");
message("can_main: Initializing external CAN device\n");
ret = can_devinit();
if (ret != OK)
{
message(MAIN_STRING "can_devinit failed: %d\n", ret);
message("can_main: can_devinit failed: %d\n", ret);
errval = 1;
goto errout;
}
/* Open the CAN device for reading */
message(MAIN_STRING "Hardware initialized. Opening the CAN device\n");
message("can_main: Hardware initialized. Opening the CAN device\n");
fd = open(CONFIG_EXAMPLES_CAN_DEVPATH, CAN_OFLAGS);
if (fd < 0)
{
message(MAIN_STRING "open %s failed: %d\n",
message("can_main: open %s failed: %d\n",
CONFIG_EXAMPLES_CAN_DEVPATH, errno);
errval = 2;
goto errout_with_dev;

View File

@ -53,16 +53,10 @@
****************************************************************************/
/****************************************************************************
* user_start/hello_main
* hello_main
****************************************************************************/
#ifdef CONFIG_EXAMPLES_HELLO_BUILTIN
# define MAIN_NAME hello_main
#else
# define MAIN_NAME user_start
#endif
int MAIN_NAME(int argc, char *argv[])
int hello_main(int argc, char *argv[])
{
printf("Hello, World!!\n");
return 0;

View File

@ -124,24 +124,11 @@ static CHelloWorld g_HelloWorld;
// Public Functions
//***************************************************************************
//***************************************************************************
// user_start
//***************************************************************************
/****************************************************************************
* Name: user_start/nxhello_main
* Name: helloxx_main
****************************************************************************/
#ifdef CONFIG_EXAMPLES_HELLOXX_BUILTIN
extern "C" int helloxx_main(int argc, char *argv[]);
# define MAIN_NAME helloxx_main
# define MAIN_STRING "helloxx_main: "
#else
# define MAIN_NAME user_start
# define MAIN_STRING "user_start: "
#endif
int MAIN_NAME(int argc, char *argv[])
int helloxx_main(int argc, char *argv[])
{
// If C++ initialization for static constructors is supported, then do
// that first
@ -153,7 +140,7 @@ int MAIN_NAME(int argc, char *argv[])
// Exercise an explictly instantiated C++ object
CHelloWorld *pHelloWorld = new CHelloWorld;
printf(MAIN_STRING "Saying hello from the dynamically constructed instance\n");
printf("helloxx_main: Saying hello from the dynamically constructed instance\n");
pHelloWorld->HelloWorld();
// Exercise an C++ object instantiated on the stack
@ -161,14 +148,14 @@ int MAIN_NAME(int argc, char *argv[])
#ifndef CONFIG_EXAMPLES_HELLOXX_NOSTACKCONST
CHelloWorld HelloWorld;
printf(MAIN_STRING "Saying hello from the instance constructed on the stack\n");
printf("helloxx_main: Saying hello from the instance constructed on the stack\n");
HelloWorld.HelloWorld();
#endif
// Exercise an statically constructed C++ object
#ifdef CONFIG_HAVE_CXXINITIALIZE
printf(MAIN_STRING "Saying hello from the statically constructed instance\n");
printf("helloxx_main: Saying hello from the statically constructed instance\n");
g_HelloWorld.HelloWorld();
#endif

View File

@ -152,16 +152,10 @@ static inline int lcdrw_initialize(FAR struct lcdrw_instance_s *inst)
****************************************************************************/
/****************************************************************************
* Name: lcdrw_main/user_start
* Name: lcdrw_main
****************************************************************************/
#ifdef CONFIG_EXAMPLES_LCDRW_BUILTIN
# define MAIN_NAME lcdrw_main
#else
# define MAIN_NAME user_start
#endif
int MAIN_NAME(int argc, char *argv[])
int lcdrw_main(int argc, char *argv[])
{
struct lcdrw_instance_s inst;
nxgl_coord_t row;

View File

@ -267,10 +267,10 @@ static void do_frees(void **mem, const int *size, const int *seq, int n)
****************************************************************************/
/****************************************************************************
* Name: user_start
* Name: mm_main
****************************************************************************/
int user_start(int argc, char *argv[])
int mm_main(int argc, char *argv[])
{
mm_showmallinfo();

View File

@ -567,10 +567,10 @@ static void succeed_stat(const char *path)
****************************************************************************/
/****************************************************************************
* Name: user_start
* Name: mount_main
****************************************************************************/
int user_start(int argc, char *argv[])
int mount_main(int argc, char *argv[])
{
int ret;
@ -580,18 +580,18 @@ int user_start(int argc, char *argv[])
ret = create_ramdisk();
if (ret < 0)
{
printf("user_start: ERROR failed to create RAM disk\n");
printf("mount_main: ERROR failed to create RAM disk\n");
return 1;
}
#endif
/* Mount the test file system (see arch/sim/src/up_deviceimage.c */
printf("user_start: mounting %s filesystem at target=%s with source=%s\n",
printf("mount_main: mounting %s filesystem at target=%s with source=%s\n",
g_filesystemtype, g_target, g_source);
ret = mount(g_source, g_target, g_filesystemtype, 0, NULL);
printf("user_start: mount() returned %d\n", ret);
printf("mount_main: mount() returned %d\n", ret);
if (ret == 0)
{
@ -737,16 +737,16 @@ int user_start(int argc, char *argv[])
/* Unmount the file system */
printf("user_start: Try unmount(%s)\n", g_target);
printf("mount_main: Try unmount(%s)\n", g_target);
ret = umount(g_target);
if (ret != 0)
{
printf("user_start: ERROR umount() failed, errno %d\n", errno);
printf("mount_main: ERROR umount() failed, errno %d\n", errno);
g_nerrors++;
}
printf("user_start: %d errors reported\n", g_nerrors);
printf("mount_main: %d errors reported\n", g_nerrors);
}
fflush(stdout);

View File

@ -84,10 +84,10 @@
****************************************************************************/
/****************************************************************************
* Name: user_start
* Name: nsh_main
****************************************************************************/
int user_start(int argc, char *argv[])
int nsh_main(int argc, char *argv[])
{
int exitval = 0;
int ret;

View File

@ -58,10 +58,10 @@
****************************************************************************/
/****************************************************************************
* Name: user_start
* Name: null_main
****************************************************************************/
int user_start(int argc, char *argv[])
int null_main(int argc, char *argv[])
{
return 0;
}

View File

@ -409,7 +409,7 @@ static int user_main(int argc, char *argv[])
check_test_memory_usage();
#endif /* CONFIG_PRIORITY_INHERITANCE && !CONFIG_DISABLE_SIGNALS && !CONFIG_DISABLE_PTHREAD */
/* Compare memory usage at time user_start started until
/* Compare memory usage at time ostest_main started until
* user_main exits. These should not be identical, but should
* be similar enough that we can detect any serious OS memory
* leaks.
@ -458,18 +458,10 @@ static void stdio_test(void)
****************************************************************************/
/****************************************************************************
* user_start/ostest_main
* ostest_main
****************************************************************************/
#ifdef CONFIG_EXAMPLES_OSTEST_BUILTIN
# define MAIN_NAME ostest_main
# define MAIN_STRING "ostest_main: "
#else
# define MAIN_NAME user_start
# define MAIN_STRING "user_start: "
#endif
int MAIN_NAME(int argc, char *argv[])
int ostest_main(int argc, char *argv[])
{
int result;
@ -492,19 +484,19 @@ int MAIN_NAME(int argc, char *argv[])
/* Set up some environment variables */
#ifndef CONFIG_DISABLE_ENVIRON
printf(MAIN_STRING "putenv(%s)\n", g_putenv_value);
printf("ostest_main: putenv(%s)\n", g_putenv_value);
putenv(g_putenv_value); /* Varaible1=BadValue3 */
printf(MAIN_STRING "setenv(%s, %s, TRUE)\n", g_var1_name, g_var1_value);
printf("ostest_main: setenv(%s, %s, TRUE)\n", g_var1_name, g_var1_value);
setenv(g_var1_name, g_var1_value, TRUE); /* Variable1=GoodValue1 */
printf(MAIN_STRING "setenv(%s, %s, FALSE)\n", g_var2_name, g_bad_value1);
printf("ostest_main: setenv(%s, %s, FALSE)\n", g_var2_name, g_bad_value1);
setenv(g_var2_name, g_bad_value1, FALSE); /* Variable2=BadValue1 */
printf(MAIN_STRING "setenv(%s, %s, TRUE)\n", g_var2_name, g_var2_value);
printf("ostest_main: setenv(%s, %s, TRUE)\n", g_var2_name, g_var2_value);
setenv(g_var2_name, g_var2_value, TRUE); /* Variable2=GoodValue2 */
printf(MAIN_STRING "setenv(%s, %s, FALSE)\n", g_var3_name, g_var3_name);
printf("ostest_main: setenv(%s, %s, FALSE)\n", g_var3_name, g_var3_name);
setenv(g_var3_name, g_var3_value, FALSE); /* Variable3=GoodValue3 */
printf(MAIN_STRING "setenv(%s, %s, FALSE)\n", g_var3_name, g_var3_name);
printf("ostest_main: setenv(%s, %s, FALSE)\n", g_var3_name, g_var3_name);
setenv(g_var3_name, g_bad_value2, FALSE); /* Variable3=GoodValue3 */
show_environment(true, true, true);
#endif
@ -518,13 +510,13 @@ int MAIN_NAME(int argc, char *argv[])
#endif
if (result == ERROR)
{
printf(MAIN_STRING "ERROR Failed to start user_main\n");
printf("ostest_main: ERROR Failed to start user_main\n");
}
else
{
printf(MAIN_STRING "Started user_main at PID=%d\n", result);
printf("ostest_main: Started user_main at PID=%d\n", result);
}
printf(MAIN_STRING "Exitting\n");
printf("ostest_main: Exitting\n");
return 0;
}

View File

@ -69,21 +69,21 @@
****************************************************************************/
/****************************************************************************
* Name: user_start
* Name: pipe_main
****************************************************************************/
int user_start(int argc, char *argv[])
int pipe_main(int argc, char *argv[])
{
int filedes[2];
int ret;
/* Test FIFO logic */
printf("\nuser_start: Performing FIFO test\n");
printf("\npipe_main: Performing FIFO test\n");
ret = mkfifo(FIFO_PATH1, 0666);
if (ret < 0)
{
fprintf(stderr, "user_start: mkfifo failed with errno=%d\n", errno);
fprintf(stderr, "pipe_main: mkfifo failed with errno=%d\n", errno);
return 1;
}
@ -96,7 +96,7 @@ int user_start(int argc, char *argv[])
filedes[1] = open(FIFO_PATH1, O_WRONLY);
if (filedes[1] < 0)
{
fprintf(stderr, "user_start: Failed to open FIFO %s for writing, errno=%d\n",
fprintf(stderr, "pipe_main: Failed to open FIFO %s for writing, errno=%d\n",
FIFO_PATH1, errno);
return 2;
}
@ -104,11 +104,11 @@ int user_start(int argc, char *argv[])
filedes[0] = open(FIFO_PATH1, O_RDONLY);
if (filedes[0] < 0)
{
fprintf(stderr, "user_start: Failed to open FIFO %s for reading, errno=%d\n",
fprintf(stderr, "pipe_main: Failed to open FIFO %s for reading, errno=%d\n",
FIFO_PATH1, errno);
if (close(filedes[1]) != 0)
{
fprintf(stderr, "user_start: close failed: %d\n", errno);
fprintf(stderr, "pipe_main: close failed: %d\n", errno);
}
return 3;
}
@ -118,28 +118,28 @@ int user_start(int argc, char *argv[])
ret = transfer_test(filedes[0], filedes[1]);
if (close(filedes[0]) != 0)
{
fprintf(stderr, "user_start: close failed: %d\n", errno);
fprintf(stderr, "pipe_main: close failed: %d\n", errno);
}
if (close(filedes[1]) != 0)
{
fprintf(stderr, "user_start: close failed: %d\n", errno);
fprintf(stderr, "pipe_main: close failed: %d\n", errno);
}
/* unlink(FIFO_PATH1); fails */
if (ret != 0)
{
fprintf(stderr, "user_start: FIFO test FAILED (%d)\n", ret);
fprintf(stderr, "pipe_main: FIFO test FAILED (%d)\n", ret);
return 4;
}
printf("user_start: FIFO test PASSED\n");
printf("pipe_main: FIFO test PASSED\n");
/* Test PIPE logic */
printf("\nuser_start: Performing pipe test\n");
printf("\npipe_main: Performing pipe test\n");
ret = pipe(filedes);
if (ret < 0)
{
fprintf(stderr, "user_start: pipe failed with errno=%d\n", errno);
fprintf(stderr, "pipe_main: pipe failed with errno=%d\n", errno);
return 5;
}
@ -148,41 +148,41 @@ int user_start(int argc, char *argv[])
ret = transfer_test(filedes[0], filedes[1]);
if (close(filedes[0]) != 0)
{
fprintf(stderr, "user_start: close failed: %d\n", errno);
fprintf(stderr, "pipe_main: close failed: %d\n", errno);
}
if (close(filedes[1]) != 0)
{
fprintf(stderr, "user_start: close failed: %d\n", errno);
fprintf(stderr, "pipe_main: close failed: %d\n", errno);
}
if (ret != 0)
{
fprintf(stderr, "user_start: PIPE test FAILED (%d)\n", ret);
fprintf(stderr, "pipe_main: PIPE test FAILED (%d)\n", ret);
return 6;
}
printf("user_start: PIPE test PASSED\n");
printf("pipe_main: PIPE test PASSED\n");
/* Perform the FIFO interlock test */
printf("\nuser_start: Performing pipe interlock test\n");
printf("\npipe_main: Performing pipe interlock test\n");
ret = interlock_test();
if (ret != 0)
{
fprintf(stderr, "user_start: FIFO interlock test FAILED (%d)\n", ret);
fprintf(stderr, "pipe_main: FIFO interlock test FAILED (%d)\n", ret);
return 7;
}
printf("user_start: PIPE interlock test PASSED\n");
printf("pipe_main: PIPE interlock test PASSED\n");
/* Perform the pipe redirection test */
printf("\nuser_start: Performing redirection test\n");
printf("\npipe_main: Performing redirection test\n");
ret = redirection_test();
if (ret != 0)
{
fprintf(stderr, "user_start: FIFO redirection test FAILED (%d)\n", ret);
fprintf(stderr, "pipe_main: FIFO redirection test FAILED (%d)\n", ret);
return 7;
}
printf("user_start: PIPE redirection test PASSED\n");
printf("pipe_main: PIPE redirection test PASSED\n");
fflush(stdout);
return 0;

View File

@ -301,16 +301,16 @@ int redirection_test(void)
if (close(filedes[0]) != 0)
{
fprintf(stderr, "user_start: close failed: %d\n", errno);
fprintf(stderr, "pipe_main: close failed: %d\n", errno);
}
if (close(filedes[1]) != 0)
{
fprintf(stderr, "user_start: close failed: %d\n", errno);
fprintf(stderr, "pipe_main: close failed: %d\n", errno);
}
if (ret != 0)
{
fprintf(stderr, "user_start: PIPE test FAILED (%d)\n", ret);
fprintf(stderr, "pipe_main: PIPE test FAILED (%d)\n", ret);
return 6;
}

View File

@ -74,10 +74,10 @@
****************************************************************************/
/****************************************************************************
* Name: user_start
* Name: poll_main
****************************************************************************/
int user_start(int argc, char *argv[])
int poll_main(int argc, char *argv[])
{
char buffer[64];
ssize_t nbytes;
@ -94,20 +94,20 @@ int user_start(int argc, char *argv[])
/* Open FIFOs */
message("\nuser_start: Creating FIFO %s\n", FIFO_PATH1);
message("\npoll_main: Creating FIFO %s\n", FIFO_PATH1);
ret = mkfifo(FIFO_PATH1, 0666);
if (ret < 0)
{
message("user_start: mkfifo failed: %d\n", errno);
message("poll_main: mkfifo failed: %d\n", errno);
exitcode = 1;
goto errout;
}
message("\nuser_start: Creating FIFO %s\n", FIFO_PATH2);
message("\npoll_main: Creating FIFO %s\n", FIFO_PATH2);
ret = mkfifo(FIFO_PATH2, 0666);
if (ret < 0)
{
message("user_start: mkfifo failed: %d\n", errno);
message("poll_main: mkfifo failed: %d\n", errno);
exitcode = 2;
goto errout;
}
@ -117,7 +117,7 @@ int user_start(int argc, char *argv[])
fd1 = open(FIFO_PATH1, O_WRONLY);
if (fd1 < 0)
{
message("user_start: Failed to open FIFO %s for writing, errno=%d\n",
message("poll_main: Failed to open FIFO %s for writing, errno=%d\n",
FIFO_PATH1, errno);
exitcode = 3;
goto errout;
@ -126,7 +126,7 @@ int user_start(int argc, char *argv[])
fd2 = open(FIFO_PATH2, O_WRONLY);
if (fd2 < 0)
{
message("user_start: Failed to open FIFO %s for writing, errno=%d\n",
message("poll_main: Failed to open FIFO %s for writing, errno=%d\n",
FIFO_PATH2, errno);
exitcode = 4;
goto errout;
@ -134,39 +134,39 @@ int user_start(int argc, char *argv[])
/* Start the listeners */
message("user_start: Starting poll_listener thread\n");
message("poll_main: Starting poll_listener thread\n");
ret = pthread_create(&tid1, NULL, poll_listener, NULL);
if (ret != 0)
{
message("user_start: Failed to create poll_listener thread: %d\n", ret);
message("poll_main: Failed to create poll_listener thread: %d\n", ret);
exitcode = 5;
goto errout;
}
message("user_start: Starting select_listener thread\n");
message("poll_main: Starting select_listener thread\n");
ret = pthread_create(&tid2, NULL, select_listener, NULL);
if (ret != 0)
{
message("user_start: Failed to create select_listener thread: %d\n", ret);
message("poll_main: Failed to create select_listener thread: %d\n", ret);
exitcode = 6;
goto errout;
}
#ifdef HAVE_NETPOLL
#ifdef CONFIG_NET_TCPBACKLOG
message("user_start: Starting net_listener thread\n");
message("poll_main: Starting net_listener thread\n");
ret = pthread_create(&tid3, NULL, net_listener, NULL);
#else
message("user_start: Starting net_reader thread\n");
message("poll_main: Starting net_reader thread\n");
ret = pthread_create(&tid3, NULL, net_reader, NULL);
#endif
if (ret != 0)
{
message("user_start: Failed to create net_listener thread: %d\n", ret);
message("poll_main: Failed to create net_listener thread: %d\n", ret);
}
#endif
@ -182,7 +182,7 @@ int user_start(int argc, char *argv[])
nbytes = write(fd1, buffer, strlen(buffer));
if (nbytes < 0)
{
message("user_start: Write to fd1 failed: %d\n", errno);
message("poll_main: Write to fd1 failed: %d\n", errno);
exitcode = 7;
goto errout;
}
@ -190,12 +190,12 @@ int user_start(int argc, char *argv[])
nbytes = write(fd2, buffer, strlen(buffer));
if (nbytes < 0)
{
message("user_start: Write fd2 failed: %d\n", errno);
message("poll_main: Write fd2 failed: %d\n", errno);
exitcode = 8;
goto errout;
}
message("\nuser_start: Sent '%s' (%d bytes)\n", buffer, nbytes);
message("\npoll_main: Sent '%s' (%d bytes)\n", buffer, nbytes);
msgflush();
/* Wait awhile. This delay should be long enough that the

View File

@ -269,7 +269,7 @@ static void parse_args(FAR struct pwm_state_s *pwm, int argc, FAR char **argv)
****************************************************************************/
/****************************************************************************
* Name: user_start/pwm_main
* Name: pwm_main
****************************************************************************/
int pwm_main(int argc, char *argv[])

View File

@ -59,14 +59,6 @@
* Pre-processor Definitions
****************************************************************************/
#ifdef CONFIG_NSH_BUILTIN_APPS
# define MAIN_NAME qe_main
# define MAIN_STRING "qe_main: "
#else
# define MAIN_NAME user_start
# define MAIN_STRING "user_start: "
#endif
/****************************************************************************
* Private Types
****************************************************************************/
@ -245,10 +237,10 @@ static void parse_args(int argc, FAR char **argv)
****************************************************************************/
/****************************************************************************
* Name: user_start/qe_main
* Name: qe_main
****************************************************************************/
int MAIN_NAME(int argc, char *argv[])
int qe_main(int argc, char *argv[])
{
int32_t position;
int fd;
@ -266,11 +258,11 @@ int MAIN_NAME(int argc, char *argv[])
* this test.
*/
message(MAIN_STRING "Initializing external encoder(s)\n");
message("qe_main: Initializing external encoder(s)\n");
ret = qe_devinit();
if (ret != OK)
{
message(MAIN_STRING "qe_devinit failed: %d\n", ret);
message("qe_main: qe_devinit failed: %d\n", ret);
exitval = EXIT_FAILURE;
goto errout;
}
@ -289,13 +281,13 @@ int MAIN_NAME(int argc, char *argv[])
/* Open the encoder device for reading */
message(MAIN_STRING "Hardware initialized. Opening the encoder device: %s\n",
message("qe_main: Hardware initialized. Opening the encoder device: %s\n",
g_qeexample.devpath);
fd = open(g_qeexample.devpath, O_RDONLY);
if (fd < 0)
{
message(MAIN_STRING "open %s failed: %d\n", g_qeexample.devpath, errno);
message("qe_main: open %s failed: %d\n", g_qeexample.devpath, errno);
exitval = EXIT_FAILURE;
goto errout_with_dev;
}
@ -304,11 +296,11 @@ int MAIN_NAME(int argc, char *argv[])
if (g_qeexample.reset)
{
message(MAIN_STRING "Resetting the count...\n");
message("qe_main: Resetting the count...\n");
ret = ioctl(fd, QEIOC_RESET, 0);
if (ret < 0)
{
message(MAIN_STRING "ioctl(QEIOC_RESET) failed: %d\n", errno);
message("qe_main: ioctl(QEIOC_RESET) failed: %d\n", errno);
exitval = EXIT_FAILURE;
goto errout_with_dev;
}
@ -319,10 +311,10 @@ int MAIN_NAME(int argc, char *argv[])
*/
#if defined(CONFIG_NSH_BUILTIN_APPS)
message(MAIN_STRING "Number of samples: %d\n", g_qeexample.nloops);
message("qe_main: Number of samples: %d\n", g_qeexample.nloops);
for (nloops = 0; nloops < g_qeexample.nloops; nloops++)
#elif defined(CONFIG_EXAMPLES_QENCODER_NSAMPLES)
message(MAIN_STRING "Number of samples: %d\n", CONFIG_EXAMPLES_QENCODER_NSAMPLES);
message("qe_main: Number of samples: %d\n", CONFIG_EXAMPLES_QENCODER_NSAMPLES);
for (nloops = 0; nloops < CONFIG_EXAMPLES_QENCODER_NSAMPLES; nloops++)
#else
for (;;)
@ -339,7 +331,7 @@ int MAIN_NAME(int argc, char *argv[])
ret = ioctl(fd, QEIOC_POSITION, (unsigned long)((uintptr_t)&position));
if (ret < 0)
{
message(MAIN_STRING "ioctl(QEIOC_POSITION) failed: %d\n", errno);
message("qe_main: ioctl(QEIOC_POSITION) failed: %d\n", errno);
exitval = EXIT_FAILURE;
goto errout_with_dev;
}
@ -348,7 +340,7 @@ int MAIN_NAME(int argc, char *argv[])
else
{
message(MAIN_STRING "%3d. %d\n", nloops+1, position);
message("qe_main: %3d. %d\n", nloops+1, position);
}
/* Delay a little bit */

View File

@ -452,10 +452,10 @@ static void checkdirectories(struct node_s *entry)
****************************************************************************/
/****************************************************************************
* Name: user_start
* Name: romfs_main
****************************************************************************/
int user_start(int argc, char *argv[])
int romfs_main(int argc, char *argv[])
{
int ret;

View File

@ -56,10 +56,10 @@
****************************************************************************/
/****************************************************************************
* user_start
* serloop_main
****************************************************************************/
int user_start(int argc, char *argv[])
int serloop_main(int argc, char *argv[])
{
#ifdef CONFIG_EXAMPLES_SERLOOP_BUFIO
int ch;

View File

@ -217,7 +217,7 @@ static void parse_args(FAR struct wdog_example_s *wdog, int argc, FAR char **arg
****************************************************************************/
/****************************************************************************
* Name: user_start/wdog_main
* Name: wdog_main
****************************************************************************/
int wdog_main(int argc, char *argv[])

View File

@ -58,7 +58,7 @@ pcode
Pascal P-Code at runtime. To use this example, place the following in
your appconfig file"
# Path to example in apps/examples containing the user_start entry point
# Path to example in apps/examples containing the passhello_main entry point
CONFIGURED_APPS += examples/pashello

View File

@ -62,7 +62,6 @@
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/rc_channels.h>
#include <uORB/topics/ardrone_control.h>
#include <uORB/topics/fixedwing_control.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_global_position.h>
@ -74,6 +73,7 @@
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <systemlib/param/param.h>
@ -126,16 +126,15 @@ static struct vehicle_attitude_s hil_attitude;
static struct vehicle_global_position_s hil_global_pos;
static struct fixedwing_control_s fw_control;
static struct ardrone_motors_setpoint_s ardrone_motors;
static struct vehicle_command_s vcmd;
static struct actuator_armed_s armed;
static orb_advert_t pub_hil_global_pos = -1;
static orb_advert_t ardrone_motors_pub = -1;
static orb_advert_t cmd_pub = -1;
static int local_pos_sub = -1;
static orb_advert_t flow_pub = -1;
static orb_advert_t global_position_setpoint_pub = -1;
static orb_advert_t local_position_setpoint_pub = -1;
@ -143,6 +142,8 @@ static bool mavlink_hil_enabled = false;
static char mavlink_message_string[51] = {0};
static int baudrate = 57600;
/* interface mode */
static enum {
MAVLINK_INTERFACE_MODE_OFFBOARD,
@ -159,6 +160,12 @@ static struct mavlink_subscriptions {
int act_3_sub;
int gps_sub;
int man_control_sp_sub;
int armed_sub;
int actuators_sub;
int local_pos_sub;
int spa_sub;
int spl_sub;
int spg_sub;
bool initialized;
} mavlink_subs = {
.sensor_sub = 0,
@ -170,6 +177,12 @@ static struct mavlink_subscriptions {
.act_3_sub = 0,
.gps_sub = 0,
.man_control_sp_sub = 0,
.armed_sub = 0,
.actuators_sub = 0,
.local_pos_sub = 0,
.spa_sub = 0,
.spl_sub = 0,
.spg_sub = 0,
.initialized = false
};
@ -192,7 +205,7 @@ int set_hil_on_off(bool hil_enabled);
/**
* Translate the custom state into standard mavlink modes and state.
*/
void get_mavlink_mode_and_state(const struct vehicle_status_s *c_status, uint8_t *mavlink_state, uint8_t *mavlink_mode);
void get_mavlink_mode_and_state(const struct vehicle_status_s *c_status, const struct actuator_armed_s *actuator, uint8_t *mavlink_state, uint8_t *mavlink_mode);
int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_config_original, bool *is_usb);
@ -345,16 +358,34 @@ int set_hil_on_off(bool hil_enabled)
printf("\n pub_hil_attitude :%i\n", pub_hil_attitude);
printf("\n pub_hil_global_pos :%i\n", pub_hil_global_pos);
if (pub_hil_attitude > 0 && pub_hil_global_pos > 0) {
mavlink_hil_enabled = true;
mavlink_hil_enabled = true;
/* ramp up some HIL-related subscriptions */
unsigned hil_rate_interval;
if (baudrate < 19200) {
/* 10 Hz */
hil_rate_interval = 100;
} else if (baudrate < 38400) {
/* 10 Hz */
hil_rate_interval = 100;
} else if (baudrate < 115200) {
/* 20 Hz */
hil_rate_interval = 50;
} else if (baudrate < 460800) {
/* 50 Hz */
hil_rate_interval = 20;
} else {
ret = ERROR;
/* 100 Hz */
hil_rate_interval = 10;
}
orb_set_interval(mavlink_subs.spa_sub, hil_rate_interval);
}
if (!hil_enabled && mavlink_hil_enabled) {
mavlink_hil_enabled = false;
orb_set_interval(mavlink_subs.spa_sub, 200);
(void)close(pub_hil_attitude);
(void)close(pub_hil_global_pos);
@ -365,7 +396,7 @@ int set_hil_on_off(bool hil_enabled)
return ret;
}
void get_mavlink_mode_and_state(const struct vehicle_status_s *c_status, uint8_t *mavlink_state, uint8_t *mavlink_mode)
void get_mavlink_mode_and_state(const struct vehicle_status_s *c_status, const struct actuator_armed_s *actuator, uint8_t *mavlink_state, uint8_t *mavlink_mode)
{
/* reset MAVLink mode bitfield */
*mavlink_mode = 0;
@ -375,70 +406,65 @@ void get_mavlink_mode_and_state(const struct vehicle_status_s *c_status, uint8_t
*mavlink_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
}
/* set arming state */
if (actuator->armed) {
*mavlink_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
} else {
*mavlink_mode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
}
switch (c_status->state_machine) {
case SYSTEM_STATE_PREFLIGHT:
if (c_status->flag_preflight_gyro_calibration ||
c_status->flag_preflight_mag_calibration ||
c_status->flag_preflight_accel_calibration) {
*mavlink_state = MAV_STATE_CALIBRATING;
*mavlink_mode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
} else {
*mavlink_state = MAV_STATE_UNINIT;
*mavlink_mode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
}
break;
case SYSTEM_STATE_STANDBY:
*mavlink_state = MAV_STATE_STANDBY;
*mavlink_mode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
break;
case SYSTEM_STATE_GROUND_READY:
*mavlink_state = MAV_STATE_ACTIVE;
*mavlink_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
break;
case SYSTEM_STATE_MANUAL:
*mavlink_state = MAV_STATE_ACTIVE;
*mavlink_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
*mavlink_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
break;
case SYSTEM_STATE_STABILIZED:
*mavlink_state = MAV_STATE_ACTIVE;
*mavlink_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
*mavlink_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
break;
case SYSTEM_STATE_AUTO:
*mavlink_state = MAV_STATE_ACTIVE;
*mavlink_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
*mavlink_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
break;
case SYSTEM_STATE_MISSION_ABORT:
*mavlink_state = MAV_STATE_EMERGENCY;
*mavlink_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
break;
case SYSTEM_STATE_EMCY_LANDING:
*mavlink_state = MAV_STATE_EMERGENCY;
*mavlink_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
break;
case SYSTEM_STATE_EMCY_CUTOFF:
*mavlink_state = MAV_STATE_EMERGENCY;
*mavlink_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
break;
case SYSTEM_STATE_GROUND_ERROR:
*mavlink_state = MAV_STATE_EMERGENCY;
*mavlink_mode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
break;
case SYSTEM_STATE_REBOOT:
*mavlink_state = MAV_STATE_POWEROFF;
*mavlink_mode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
break;
}
@ -495,6 +521,10 @@ static int set_mavlink_interval_limit(struct mavlink_subscriptions *subs, int ma
/* senser sub triggers scaled IMU */
if (subs->sensor_sub) orb_set_interval(subs->sensor_sub, min_interval);
break;
case MAVLINK_MSG_ID_HIGHRES_IMU:
/* senser sub triggers highres IMU */
if (subs->sensor_sub) orb_set_interval(subs->sensor_sub, min_interval);
break;
case MAVLINK_MSG_ID_RAW_IMU:
/* senser sub triggers RAW IMU */
if (subs->sensor_sub) orb_set_interval(subs->sensor_sub, min_interval);
@ -557,6 +587,7 @@ static void *uorb_receiveloop(void *arg)
struct vehicle_attitude_setpoint_s att_sp;
struct actuator_outputs_s act_outputs;
struct manual_control_setpoint_s man_control;
struct actuator_controls_s actuators;
} buf;
/* --- SENSORS RAW VALUE --- */
@ -582,14 +613,6 @@ static void *uorb_receiveloop(void *arg)
fds[fdsc_count].events = POLLIN;
fdsc_count++;
// /* --- ARDRONE CONTROL --- */
// /* subscribe to ORB for AR.Drone controller outputs */
// int ar_sub = orb_subscribe(ORB_ID(ardrone_control));
// orb_set_interval(ar_sub, 200); /* 5Hz updates */
// fds[fdsc_count].fd = ar_sub;
// fds[fdsc_count].events = POLLIN;
// fdsc_count++;
/* --- SYSTEM STATE --- */
/* struct already globally allocated */
/* subscribe to topic */
@ -608,15 +631,6 @@ static void *uorb_receiveloop(void *arg)
fds[fdsc_count].events = POLLIN;
fdsc_count++;
/* --- FIXED WING CONTROL VALUE --- */
/* struct already globally allocated */
/* subscribe to ORB for fixed wing control */
int fw_sub = orb_subscribe(ORB_ID(fixedwing_control));
orb_set_interval(fw_sub, 50); /* 20 Hz updates */
fds[fdsc_count].fd = fw_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
/* --- GLOBAL POS VALUE --- */
/* struct already globally allocated and topic already subscribed */
fds[fdsc_count].fd = subs->global_pos_sub;
@ -625,34 +639,34 @@ static void *uorb_receiveloop(void *arg)
/* --- LOCAL POS VALUE --- */
/* struct and topic already globally subscribed */
fds[fdsc_count].fd = local_pos_sub;
fds[fdsc_count].fd = subs->local_pos_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
/* --- GLOBAL SETPOINT VALUE --- */
/* subscribe to ORB for local setpoint */
/* struct already allocated */
int spg_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
orb_set_interval(spg_sub, 2000); /* 0.5 Hz updates */
fds[fdsc_count].fd = spg_sub;
subs->spg_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
orb_set_interval(subs->spg_sub, 2000); /* 0.5 Hz updates */
fds[fdsc_count].fd = subs->spg_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
/* --- LOCAL SETPOINT VALUE --- */
/* subscribe to ORB for local setpoint */
/* struct already allocated */
int spl_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
orb_set_interval(spl_sub, 2000); /* 0.5 Hz updates */
fds[fdsc_count].fd = spl_sub;
subs->spl_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
orb_set_interval(subs->spl_sub, 2000); /* 0.5 Hz updates */
fds[fdsc_count].fd = subs->spl_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
/* --- ATTITUDE SETPOINT VALUE --- */
/* subscribe to ORB for attitude setpoint */
/* struct already allocated */
int spa_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
orb_set_interval(spa_sub, 2000); /* 0.5 Hz updates */
fds[fdsc_count].fd = spa_sub;
subs->spa_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
orb_set_interval(subs->spa_sub, 2000); /* 0.5 Hz updates */
fds[fdsc_count].fd = subs->spa_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
@ -680,6 +694,21 @@ static void *uorb_receiveloop(void *arg)
fds[fdsc_count].events = POLLIN;
fdsc_count++;
/* --- ACTUATOR ARMED VALUE --- */
/* subscribe to ORB for actuator armed */
subs->armed_sub = orb_subscribe(ORB_ID(actuator_armed));
fds[fdsc_count].fd = subs->armed_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
/* --- ACTUATOR CONTROL VALUE --- */
/* subscribe to ORB for actuator control */
subs->actuators_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
orb_set_interval(subs->actuators_sub, 2000); /* 0.5 Hz updates */
fds[fdsc_count].fd = subs->actuators_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
/* all subscriptions initialized, return success */
subs->initialized = true;
@ -724,9 +753,18 @@ static void *uorb_receiveloop(void *arg)
/* send raw imu data */
mavlink_msg_raw_imu_send(MAVLINK_COMM_0, buf.raw.timestamp, buf.raw.accelerometer_raw[0], buf.raw.accelerometer_raw[1], buf.raw.accelerometer_raw[2], buf.raw.gyro_raw[0], buf.raw.gyro_raw[1], buf.raw.gyro_raw[2], buf.raw.magnetometer_raw[0], buf.raw.magnetometer_raw[1], buf.raw.magnetometer_raw[2]);
/* send scaled imu data (m/s^2 accelerations scaled back to milli-g) */
mavlink_msg_scaled_imu_send(MAVLINK_COMM_0, buf.raw.timestamp, buf.raw.accelerometer_m_s2[0] * 101.936799f, buf.raw.accelerometer_m_s2[1] * 101.936799f, buf.raw.accelerometer_m_s2[2] * 101.936799f, buf.raw.gyro_rad_s[0] * 1000, buf.raw.gyro_rad_s[1] * 1000, buf.raw.gyro_rad_s[2] * 1000, buf.raw.magnetometer_ga[0] * 1000, buf.raw.magnetometer_ga[1] * 1000, buf.raw.magnetometer_ga[2] * 1000);
//mavlink_msg_scaled_imu_send(MAVLINK_COMM_0, buf.raw.timestamp, buf.raw.accelerometer_m_s2[0] * 101.936799f, buf.raw.accelerometer_m_s2[1] * 101.936799f, buf.raw.accelerometer_m_s2[2] * 101.936799f, buf.raw.gyro_rad_s[0] * 1000, buf.raw.gyro_rad_s[1] * 1000, buf.raw.gyro_rad_s[2] * 1000, buf.raw.magnetometer_ga[0] * 1000, buf.raw.magnetometer_ga[1] * 1000, buf.raw.magnetometer_ga[2] * 1000);
/* send scaled imu data */
mavlink_msg_highres_imu_send(MAVLINK_COMM_0, buf.raw.timestamp,
buf.raw.accelerometer_m_s2[0], buf.raw.accelerometer_m_s2[1],
buf.raw.accelerometer_m_s2[2], buf.raw.gyro_rad_s[0],
buf.raw.gyro_rad_s[1], buf.raw.gyro_rad_s[2],
buf.raw.magnetometer_ga[0],
buf.raw.magnetometer_ga[1],buf.raw.magnetometer_ga[2],
buf.raw.baro_pres_mbar, 0 /* no diff pressure yet */,
buf.raw.baro_alt_meter, buf.raw.baro_temp_celcius);
/* send pressure */
mavlink_msg_scaled_pressure_send(MAVLINK_COMM_0, buf.raw.timestamp / 1000, buf.raw.baro_pres_mbar, buf.raw.baro_alt_meter, buf.raw.baro_temp_celcius * 100);
//mavlink_msg_scaled_pressure_send(MAVLINK_COMM_0, buf.raw.timestamp / 1000, buf.raw.baro_pres_mbar, buf.raw.baro_alt_meter, buf.raw.baro_temp_celcius * 100);
sensors_raw_counter++;
}
@ -781,13 +819,14 @@ static void *uorb_receiveloop(void *arg)
if (fds[ifds++].revents & POLLIN) {
/* immediately communicate state changes back to user */
orb_copy(ORB_ID(vehicle_status), status_sub, &v_status);
orb_copy(ORB_ID(actuator_armed), mavlink_subs.armed_sub, &armed);
/* enable or disable HIL */
set_hil_on_off(v_status.flag_hil_enabled);
/* translate the current syste state to mavlink state and mode */
uint8_t mavlink_state = 0;
uint8_t mavlink_mode = 0;
get_mavlink_mode_and_state(&v_status, &mavlink_state, &mavlink_mode);
get_mavlink_mode_and_state(&v_status, &armed, &mavlink_state, &mavlink_mode);
/* send heartbeat */
mavlink_msg_heartbeat_send(chan, mavlink_system.type, MAV_AUTOPILOT_PX4, mavlink_mode, v_status.state_machine, mavlink_state);
@ -801,71 +840,6 @@ static void *uorb_receiveloop(void *arg)
// TODO decide where to send channels
}
/* --- FIXED WING CONTROL CHANNELS --- */
if (fds[ifds++].revents & POLLIN) {
/* copy fixed wing control into local buffer */
orb_copy(ORB_ID(fixedwing_control), fw_sub, &fw_control);
/* send control output via MAVLink */
mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(MAVLINK_COMM_0, fw_control.timestamp / 1000, fw_control.attitude_control_output[0],
fw_control.attitude_control_output[1], fw_control.attitude_control_output[2],
fw_control.attitude_control_output[3]);
/* Only send in HIL mode */
if (v_status.flag_hil_enabled) {
/* Send the desired attitude from RC or from the autonomous controller */
// XXX it should not depend on a RC setting, but on a system_state value
float roll_ail, pitch_elev, throttle, yaw_rudd;
if (rc.chan[rc.function[OVERRIDE]].scale < 2000) {
//orb_copy(ORB_ID(fixedwing_control), fixed_wing_control_sub, &fixed_wing_control);
roll_ail = fw_control.attitude_control_output[ROLL];
pitch_elev = fw_control.attitude_control_output[PITCH];
throttle = fw_control.attitude_control_output[THROTTLE];
yaw_rudd = fw_control.attitude_control_output[YAW];
} else {
roll_ail = rc.chan[rc.function[ROLL]].scale;
pitch_elev = rc.chan[rc.function[PITCH]].scale;
throttle = rc.chan[rc.function[THROTTLE]].scale;
yaw_rudd = rc.chan[rc.function[YAW]].scale;
}
/* hacked HIL implementation in order for the APM Planner to work
* (correct cmd: mavlink_msg_hil_controls_send())
*/
mavlink_msg_rc_channels_scaled_send(chan,
hrt_absolute_time(),
0, // port 0
roll_ail,
pitch_elev,
throttle,
yaw_rudd,
0,
0,
0,
0,
1 /*rssi=1*/);
/* correct command duplicate */
mavlink_msg_hil_controls_send(chan,
hrt_absolute_time(),
roll_ail,
pitch_elev,
yaw_rudd,
throttle,
0,
0,
0,
0,
32, /* HIL_MODE */
0);
}
}
/* --- VEHICLE GLOBAL POSITION --- */
if (fds[ifds++].revents & POLLIN) {
/* copy global position data into local buffer */
@ -881,37 +855,82 @@ static void *uorb_receiveloop(void *arg)
/* heading in degrees * 10, from 0 to 36.000) */
uint16_t hdg = (global_pos.hdg / M_PI_F) * (180.0f * 10.0f) + (180.0f * 10.0f);
mavlink_msg_global_position_int_send(MAVLINK_COMM_0, timestamp / 1000, lat, lon, alt, relative_alt, vx, vy, vz, hdg);
mavlink_msg_global_position_int_send(MAVLINK_COMM_0, timestamp / 1000, lat, lon, alt,
relative_alt, vx, vy, vz, hdg);
}
/* --- VEHICLE LOCAL POSITION --- */
if (fds[ifds++].revents & POLLIN) {
/* copy local position data into local buffer */
orb_copy(ORB_ID(vehicle_local_position), local_pos_sub, &local_pos);
mavlink_msg_local_position_ned_send(MAVLINK_COMM_0, local_pos.timestamp / 1000, local_pos.x, local_pos.y, local_pos.z, local_pos.vx, local_pos.vy, local_pos.vz);
orb_copy(ORB_ID(vehicle_local_position), subs->local_pos_sub, &local_pos);
mavlink_msg_local_position_ned_send(MAVLINK_COMM_0, local_pos.timestamp / 1000, local_pos.x,
local_pos.y, local_pos.z, local_pos.vx, local_pos.vy, local_pos.vz);
}
/* --- VEHICLE GLOBAL SETPOINT --- */
if (fds[ifds++].revents & POLLIN) {
/* copy local position data into local buffer */
orb_copy(ORB_ID(vehicle_global_position_setpoint), spg_sub, &buf.global_sp);
orb_copy(ORB_ID(vehicle_global_position_setpoint), subs->spg_sub, &buf.global_sp);
uint8_t coordinate_frame = MAV_FRAME_GLOBAL;
if (buf.global_sp.altitude_is_relative) coordinate_frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
mavlink_msg_global_position_setpoint_int_send(MAVLINK_COMM_0, coordinate_frame, buf.global_sp.lat, buf.global_sp.lon, buf.global_sp.altitude, buf.global_sp.yaw);
mavlink_msg_global_position_setpoint_int_send(MAVLINK_COMM_0, coordinate_frame, buf.global_sp.lat,
buf.global_sp.lon, buf.global_sp.altitude, buf.global_sp.yaw);
}
/* --- VEHICLE LOCAL SETPOINT --- */
if (fds[ifds++].revents & POLLIN) {
/* copy local position data into local buffer */
orb_copy(ORB_ID(vehicle_local_position_setpoint), spl_sub, &buf.local_sp);
mavlink_msg_local_position_setpoint_send(MAVLINK_COMM_0, MAV_FRAME_LOCAL_NED, buf.local_sp.x, buf.local_sp.y, buf.local_sp.z, buf.local_sp.yaw);
orb_copy(ORB_ID(vehicle_local_position_setpoint), subs->spl_sub, &buf.local_sp);
mavlink_msg_local_position_setpoint_send(MAVLINK_COMM_0, MAV_FRAME_LOCAL_NED, buf.local_sp.x,
buf.local_sp.y, buf.local_sp.z, buf.local_sp.yaw);
}
/* --- VEHICLE ATTITUDE SETPOINT --- */
if (fds[ifds++].revents & POLLIN) {
/* copy local position data into local buffer */
orb_copy(ORB_ID(vehicle_attitude_setpoint), spa_sub, &buf.att_sp);
mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(MAVLINK_COMM_0, buf.att_sp.timestamp/1000, buf.att_sp.roll_body, buf.att_sp.pitch_body, buf.att_sp.yaw_body, buf.att_sp.thrust);
orb_copy(ORB_ID(vehicle_attitude_setpoint), subs->spa_sub, &buf.att_sp);
mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(MAVLINK_COMM_0, buf.att_sp.timestamp/1000,
buf.att_sp.roll_body, buf.att_sp.pitch_body, buf.att_sp.yaw_body, buf.att_sp.thrust);
/* Only send in HIL mode */
if (mavlink_hil_enabled) {
/* hacked HIL implementation in order for the APM Planner to work
* (correct cmd: mavlink_msg_hil_controls_send())
*/
mavlink_msg_rc_channels_scaled_send(chan,
hrt_absolute_time(),
0, // port 0
buf.att_sp.roll_body,
buf.att_sp.pitch_body,
buf.att_sp.thrust,
buf.att_sp.yaw_body,
0,
0,
0,
0,
1 /*rssi=1*/);
/* translate the current syste state to mavlink state and mode */
uint8_t mavlink_state = 0;
uint8_t mavlink_mode = 0;
get_mavlink_mode_and_state(&v_status, &armed, &mavlink_state, &mavlink_mode);
/* correct HIL message as per MAVLink spec */
mavlink_msg_hil_controls_send(chan,
hrt_absolute_time(),
buf.att_sp.roll_body,
buf.att_sp.pitch_body,
buf.att_sp.yaw_body,
buf.att_sp.thrust,
0,
0,
0,
0,
mavlink_mode,
0);
}
}
/* --- ACTUATOR OUTPUTS 0 --- */
@ -1033,6 +1052,19 @@ static void *uorb_receiveloop(void *arg)
mavlink_msg_manual_control_send(MAVLINK_COMM_0, mavlink_system.sysid, buf.man_control.roll,
buf.man_control.pitch, buf.man_control.yaw, buf.man_control.throttle, 1, 1, 1, 1);
}
/* --- ACTUATOR ARMED --- */
if (fds[ifds++].revents & POLLIN) {
}
/* --- ACTUATOR CONTROL --- */
if (fds[ifds++].revents & POLLIN) {
orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, subs->actuators_sub, &buf.actuators);
mavlink_msg_named_value_float_send(MAVLINK_COMM_0, hrt_absolute_time() / 1000, "ctrl0", buf.actuators.control[0]);
mavlink_msg_named_value_float_send(MAVLINK_COMM_0, hrt_absolute_time() / 1000, "ctrl1", buf.actuators.control[1]);
mavlink_msg_named_value_float_send(MAVLINK_COMM_0, hrt_absolute_time() / 1000, "ctrl2", buf.actuators.control[2]);
mavlink_msg_named_value_float_send(MAVLINK_COMM_0, hrt_absolute_time() / 1000, "ctrl3", buf.actuators.control[3]);
}
}
}
@ -1252,12 +1284,12 @@ void handleMessage(mavlink_message_t *msg)
}
}
int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_config_original, bool *is_usb)
int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_config_original, bool *is_usb)
{
/* process baud rate */
int speed;
switch (baudrate) {
switch (baud) {
case 0: speed = B0; break;
case 50: speed = B50; break;
@ -1301,12 +1333,12 @@ int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_
case 921600: speed = B921600; break;
default:
fprintf(stderr, "[mavlink] ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baudrate);
fprintf(stderr, "[mavlink] ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud);
return -EINVAL;
}
/* open uart */
printf("[mavlink] UART is %s, baudrate is %d\n", uart_name, baudrate);
printf("[mavlink] UART is %s, baudrate is %d\n", uart_name, baud);
uart = open(uart_name, O_RDWR | O_NOCTTY);
/* Try to set baud rate */
@ -1363,7 +1395,6 @@ int mavlink_thread_main(int argc, char *argv[])
memset(&rc, 0, sizeof(rc));
memset(&hil_attitude, 0, sizeof(hil_attitude));
memset(&hil_global_pos, 0, sizeof(hil_global_pos));
memset(&fw_control, 0, sizeof(fw_control));
memset(&ardrone_motors, 0, sizeof(ardrone_motors));
memset(&vcmd, 0, sizeof(vcmd));
@ -1375,7 +1406,7 @@ int mavlink_thread_main(int argc, char *argv[])
/* default values for arguments */
char *uart_name = "/dev/ttyS1";
int baudrate = 57600;
baudrate = 57600;
/* read program arguments */
int i;
@ -1435,8 +1466,8 @@ int mavlink_thread_main(int argc, char *argv[])
mavlink_subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
orb_set_interval(mavlink_subs.global_pos_sub, 1000); /* 1Hz active updates */
/* subscribe to ORB for local position */
local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
orb_set_interval(local_pos_sub, 1000); /* 1Hz active updates */
mavlink_subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
orb_set_interval(mavlink_subs.local_pos_sub, 1000); /* 1Hz active updates */
pthread_attr_t receiveloop_attr;
@ -1467,6 +1498,7 @@ int mavlink_thread_main(int argc, char *argv[])
/* 500 Hz / 2 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SCALED_IMU, 2);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 2);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_HIGHRES_IMU, 2);
/* 200 Hz / 5 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 5);
/* 5 Hz */
@ -1475,6 +1507,7 @@ int mavlink_thread_main(int argc, char *argv[])
/* 250 Hz / 4 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SCALED_IMU, 5);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 5);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_HIGHRES_IMU, 5);
/* 50 Hz / 20 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 20);
/* 2 Hz */
@ -1483,6 +1516,7 @@ int mavlink_thread_main(int argc, char *argv[])
/* 50 Hz / 20 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SCALED_IMU, 50);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 50);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_HIGHRES_IMU, 50);
/* 10 Hz / 100 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 100);
/* 1 Hz */
@ -1491,6 +1525,7 @@ int mavlink_thread_main(int argc, char *argv[])
/* 10 Hz / 100 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SCALED_IMU, 100);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 100);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_HIGHRES_IMU, 100);
/* 5 Hz / 200 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 200);
/* 0.2 Hz */
@ -1499,6 +1534,7 @@ int mavlink_thread_main(int argc, char *argv[])
/* very low baud rate, limit to 1 Hz / 1000 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SCALED_IMU, 1000);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 1000);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_HIGHRES_IMU, 1000);
/* 0.5 Hz */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 2000);
/* 0.1 Hz */
@ -1511,7 +1547,8 @@ int mavlink_thread_main(int argc, char *argv[])
/* get local and global position */
orb_copy(ORB_ID(vehicle_global_position), mavlink_subs.global_pos_sub, &global_pos);
orb_copy(ORB_ID(vehicle_local_position), local_pos_sub, &local_pos);
orb_copy(ORB_ID(vehicle_local_position), mavlink_subs.local_pos_sub, &local_pos);
orb_copy(ORB_ID(actuator_armed), mavlink_subs.armed_sub, &armed);
/* 1 Hz */
if (lowspeed_counter == 10) {
@ -1537,7 +1574,7 @@ int mavlink_thread_main(int argc, char *argv[])
/* translate the current syste state to mavlink state and mode */
uint8_t mavlink_state = 0;
uint8_t mavlink_mode = 0;
get_mavlink_mode_and_state(&v_status, &mavlink_state, &mavlink_mode);
get_mavlink_mode_and_state(&v_status, &armed, &mavlink_state, &mavlink_mode);
/* send heartbeat */
mavlink_msg_heartbeat_send(chan, system_type, MAV_AUTOPILOT_PX4, mavlink_mode, v_status.state_machine, mavlink_state);
@ -1607,7 +1644,7 @@ exit_cleanup:
/* close subscriptions */
close(mavlink_subs.global_pos_sub);
close(local_pos_sub);
close(mavlink_subs.local_pos_sub);
fflush(stdout);
fflush(stderr);

View File

@ -117,7 +117,6 @@ mc_thread_main(int argc, char *argv[])
actuators.control[i] = 0.0f;
orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators);
armed.armed = false;
orb_advert_t armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed);
orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
/* register the perf counter */
@ -151,25 +150,13 @@ mc_thread_main(int argc, char *argv[])
att_sp.yaw_body = 0.0f;
att_sp.thrust = 0.1f;
} else {
if (state.flag_system_armed) {
att_sp.thrust = manual.throttle;
armed.armed = true;
} else if (state.state_machine == SYSTEM_STATE_EMCY_CUTOFF) {
/* immediately cut off motors */
armed.armed = false;
} else {
/* limit motor throttle to zero for an unknown mode */
armed.armed = false;
}
att_sp.thrust = manual.throttle;
}
multirotor_control_attitude(&att_sp, &att, &state, &actuators, motor_test_mode);
multirotor_control_attitude(&att_sp, &att, &actuators);
/* publish the result */
orb_publish(ORB_ID(actuator_armed), armed_pub, &armed);
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
@ -179,8 +166,6 @@ mc_thread_main(int argc, char *argv[])
printf("[multirotor att control] stopping, disarming motors.\n");
/* kill all outputs */
armed.armed = false;
orb_publish(ORB_ID(actuator_armed), armed_pub, &armed);
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++)
actuators.control[i] = 0.0f;
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
@ -190,7 +175,6 @@ mc_thread_main(int argc, char *argv[])
close(state_sub);
close(manual_sub);
close(actuator_pub);
close(armed_pub);
close(att_sp_pub);
perf_print_counter(mc_loop_perf);

View File

@ -188,8 +188,7 @@ static int parameters_update(const struct mc_att_control_param_handles *h, struc
}
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
const struct vehicle_attitude_s *att, const struct vehicle_status_s *status,
struct actuator_controls_s *actuators, bool verbose)
const struct vehicle_attitude_s *att, struct actuator_controls_s *actuators)
{
static uint64_t last_run = 0;
const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
@ -218,7 +217,7 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
PID_MODE_DERIVATIV_CALC, 155);
pid_init(&pitch_controller, p.att_p, p.att_i, p.att_d, p.att_awu,
PID_MODE_DERIVATIV_SET, 156);
pid_init(&roll_controller, p.att_d, p.att_i, p.att_d, p.att_awu,
pid_init(&roll_controller, p.att_p, p.att_i, p.att_d, p.att_awu,
PID_MODE_DERIVATIV_SET, 157);
initialized = true;

View File

@ -54,8 +54,6 @@
#include <uORB/topics/actuator_controls.h>
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const struct vehicle_attitude_s *att,
const struct vehicle_status_s *status, struct actuator_controls_s *actuators, bool verbose);
void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls_s *actuators, bool verbose);
struct actuator_controls_s *actuators);
#endif /* MULTIROTOR_ATTITUDE_CONTROL_H_ */

View File

@ -148,9 +148,12 @@ config NSH_FILEIOSIZE
config NSH_STRERROR
bool "Use strerror()"
default n
depends on LIBC_STRERROR
---help---
strerror(errno) makes more readable output but strerror() is
very large and will not be used unless this setting is 'y'
This setting depends upon the strerror() having been enabled
with LIBC_STRERROR.
config NSH_LINELEN
int "Max command line length"

View File

@ -915,7 +915,9 @@ NSH-Specific Configuration Settings
* CONFIG_NSH_STRERROR
strerror(errno) makes more readable output but strerror() is
very large and will not be used unless this setting is 'y'
very large and will not be used unless this setting is 'y'.
This setting depends upon the strerror() having been enabled
with CONFIG_LIBC_STRERROR.
* CONFIG_NSH_LINELEN
The maximum length of one command line and of one output line.

View File

@ -238,9 +238,14 @@
#define NSH_MAX_ARGUMENTS 6
/* strerror() produces much nicer output but is, however, quite large and
* will only be used if CONFIG_NSH_STRERROR is defined.
* will only be used if CONFIG_NSH_STRERROR is defined. Note that the strerror
* interface must also have been enabled with CONFIG_LIBC_STRERROR.
*/
#ifndef CONFIG_LIBC_STRERROR
# undef CONFIG_NSH_STRERROR
#endif
#ifdef CONFIG_NSH_STRERROR
# define NSH_ERRNO strerror(errno)
# define NSH_ERRNO_OF(err) strerror(err)

View File

@ -552,7 +552,7 @@ void
fake(int argc, char *argv[])
{
if (argc < 5) {
puts("fmu fake <roll> <pitch> <yaw> <thrust> (values -100 - 100)");
puts("fmu fake <roll> <pitch> <yaw> <thrust> (values -100 .. 100)");
exit(1);
}

View File

@ -351,15 +351,7 @@ static void i2c_teardown(FAR struct i2ctool_s *i2ctool)
* Name: i2c_main
****************************************************************************/
#ifdef CONFIG_I2CTOOL_BUILTIN
# define MAIN_NAME i2c_main
# define MAIN_NAME_STRING "i2c_main"
#else
# define MAIN_NAME user_start
# define MAIN_NAME_STRING "user_start"
#endif
int MAIN_NAME(int argc, char *argv[])
int i2c_main(int argc, char *argv[])
{
/* Verify settings */

View File

@ -64,52 +64,52 @@ namespace
* These tables automatically generated by multi_tables - do not edit.
*/
const MultirotorMixer::Rotor _config_quad_x[] = {
{ -0.707107, 0.707107, 1.00 },
{ 0.707107, -0.707107, 1.00 },
{ 0.707107, 0.707107, -1.00 },
{ -0.707107, -0.707107, -1.00 },
{ -0.707107, 0.707107, -1.00 },
{ 0.707107, -0.707107, -1.00 },
{ 0.707107, 0.707107, 1.00 },
{ -0.707107, -0.707107, 1.00 },
};
const MultirotorMixer::Rotor _config_quad_plus[] = {
{ -1.000000, 0.000000, 1.00 },
{ 1.000000, 0.000000, 1.00 },
{ 0.000000, 1.000000, -1.00 },
{ -0.000000, -1.000000, -1.00 },
{ -1.000000, 0.000000, -1.00 },
{ 1.000000, 0.000000, -1.00 },
{ 0.000000, 1.000000, 1.00 },
{ -0.000000, -1.000000, 1.00 },
};
const MultirotorMixer::Rotor _config_hex_x[] = {
{ -1.000000, 0.000000, -1.00 },
{ 1.000000, 0.000000, 1.00 },
{ 0.500000, 0.866025, -1.00 },
{ -0.500000, -0.866025, 1.00 },
{ -0.500000, 0.866025, 1.00 },
{ 0.500000, -0.866025, -1.00 },
{ -1.000000, 0.000000, 1.00 },
{ 1.000000, 0.000000, -1.00 },
{ 0.500000, 0.866025, 1.00 },
{ -0.500000, -0.866025, -1.00 },
{ -0.500000, 0.866025, -1.00 },
{ 0.500000, -0.866025, 1.00 },
};
const MultirotorMixer::Rotor _config_hex_plus[] = {
{ 0.000000, 1.000000, -1.00 },
{ -0.000000, -1.000000, 1.00 },
{ 0.866025, -0.500000, -1.00 },
{ -0.866025, 0.500000, 1.00 },
{ 0.866025, 0.500000, 1.00 },
{ -0.866025, -0.500000, -1.00 },
{ 0.000000, 1.000000, 1.00 },
{ -0.000000, -1.000000, -1.00 },
{ 0.866025, -0.500000, 1.00 },
{ -0.866025, 0.500000, -1.00 },
{ 0.866025, 0.500000, -1.00 },
{ -0.866025, -0.500000, 1.00 },
};
const MultirotorMixer::Rotor _config_octa_x[] = {
{ -0.382683, 0.923880, -1.00 },
{ 0.382683, -0.923880, -1.00 },
{ -0.923880, 0.382683, 1.00 },
{ -0.382683, -0.923880, 1.00 },
{ 0.382683, 0.923880, 1.00 },
{ 0.923880, -0.382683, 1.00 },
{ 0.923880, 0.382683, -1.00 },
{ -0.923880, -0.382683, -1.00 },
{ -0.382683, 0.923880, 1.00 },
{ 0.382683, -0.923880, 1.00 },
{ -0.923880, 0.382683, -1.00 },
{ -0.382683, -0.923880, -1.00 },
{ 0.382683, 0.923880, -1.00 },
{ 0.923880, -0.382683, -1.00 },
{ 0.923880, 0.382683, 1.00 },
{ -0.923880, -0.382683, 1.00 },
};
const MultirotorMixer::Rotor _config_octa_plus[] = {
{ 0.000000, 1.000000, -1.00 },
{ -0.000000, -1.000000, -1.00 },
{ -0.707107, 0.707107, 1.00 },
{ -0.707107, -0.707107, 1.00 },
{ 0.707107, 0.707107, 1.00 },
{ 0.707107, -0.707107, 1.00 },
{ 1.000000, 0.000000, -1.00 },
{ -1.000000, 0.000000, -1.00 },
{ 0.000000, 1.000000, 1.00 },
{ -0.000000, -1.000000, 1.00 },
{ -0.707107, 0.707107, -1.00 },
{ -0.707107, -0.707107, -1.00 },
{ 0.707107, 0.707107, -1.00 },
{ 0.707107, -0.707107, -1.00 },
{ 1.000000, 0.000000, 1.00 },
{ -1.000000, 0.000000, 1.00 },
};
const MultirotorMixer::Rotor *_config_index[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
&_config_quad_x[0],

View File

@ -62,7 +62,7 @@ set octa_plus {
set tables {quad_x quad_plus hex_x hex_plus octa_x octa_plus}
proc factors {a d} { puts [format "\t{ %9.6f, %9.6f, %5.2f }," [rcos [expr $a + 90]] [rcos $a] $d]}
proc factors {a d} { puts [format "\t{ %9.6f, %9.6f, %5.2f }," [rcos [expr $a + 90]] [rcos $a] [expr -$d]]}
foreach table $tables {
puts [format "const MultirotorMixer::Rotor _config_%s\[\] = {" $table]

File diff suppressed because one or more lines are too long

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Aug 23 16:39:14 2012"
#define MAVLINK_BUILD_DATE "Mon Sep 3 14:55:54 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

File diff suppressed because one or more lines are too long

View File

@ -5,9 +5,9 @@
typedef struct __mavlink_attitude_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
float roll; ///< Roll angle (rad)
float pitch; ///< Pitch angle (rad)
float yaw; ///< Yaw angle (rad)
float roll; ///< Roll angle (rad, -pi..+pi)
float pitch; ///< Pitch angle (rad, -pi..+pi)
float yaw; ///< Yaw angle (rad, -pi..+pi)
float rollspeed; ///< Roll angular speed (rad/s)
float pitchspeed; ///< Pitch angular speed (rad/s)
float yawspeed; ///< Yaw angular speed (rad/s)
@ -39,9 +39,9 @@ typedef struct __mavlink_attitude_t
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param roll Roll angle (rad, -pi..+pi)
* @param pitch Pitch angle (rad, -pi..+pi)
* @param yaw Yaw angle (rad, -pi..+pi)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
@ -85,9 +85,9 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param roll Roll angle (rad, -pi..+pi)
* @param pitch Pitch angle (rad, -pi..+pi)
* @param yaw Yaw angle (rad, -pi..+pi)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
@ -143,9 +143,9 @@ static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t co
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param roll Roll angle (rad, -pi..+pi)
* @param pitch Pitch angle (rad, -pi..+pi)
* @param yaw Yaw angle (rad, -pi..+pi)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
@ -197,7 +197,7 @@ static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_messa
/**
* @brief Get field roll from attitude message
*
* @return Roll angle (rad)
* @return Roll angle (rad, -pi..+pi)
*/
static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg)
{
@ -207,7 +207,7 @@ static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg)
/**
* @brief Get field pitch from attitude message
*
* @return Pitch angle (rad)
* @return Pitch angle (rad, -pi..+pi)
*/
static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg)
{
@ -217,7 +217,7 @@ static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg)
/**
* @brief Get field yaw from attitude message
*
* @return Yaw angle (rad)
* @return Yaw angle (rad, -pi..+pi)
*/
static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg)
{

View File

@ -0,0 +1,430 @@
// MESSAGE HIGHRES_IMU PACKING
#define MAVLINK_MSG_ID_HIGHRES_IMU 105
typedef struct __mavlink_highres_imu_t
{
uint64_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
float xacc; ///< X acceleration (m/s^2)
float yacc; ///< Y acceleration (m/s^2)
float zacc; ///< Z acceleration (m/s^2)
float xgyro; ///< Angular speed around X axis (rad / sec)
float ygyro; ///< Angular speed around Y axis (rad / sec)
float zgyro; ///< Angular speed around Z axis (rad / sec)
float xmag; ///< X Magnetic field (Gauss)
float ymag; ///< Y Magnetic field (Gauss)
float zmag; ///< Z Magnetic field (Gauss)
float abs_pressure; ///< Absolute pressure in hectopascal
float diff_pressure; ///< Differential pressure in hectopascal
float pressure_alt; ///< Altitude calculated from pressure
float temperature; ///< Temperature in degrees celsius
} mavlink_highres_imu_t;
#define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 60
#define MAVLINK_MSG_ID_105_LEN 60
#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \
"HIGHRES_IMU", \
14, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_highres_imu_t, time_boot_ms) }, \
{ "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_highres_imu_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_highres_imu_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_highres_imu_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_highres_imu_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_highres_imu_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_highres_imu_t, zgyro) }, \
{ "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_highres_imu_t, xmag) }, \
{ "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_highres_imu_t, ymag) }, \
{ "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_highres_imu_t, zmag) }, \
{ "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_highres_imu_t, abs_pressure) }, \
{ "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_highres_imu_t, diff_pressure) }, \
{ "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_highres_imu_t, pressure_alt) }, \
{ "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_highres_imu_t, temperature) }, \
} \
}
/**
* @brief Pack a highres_imu message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis (rad / sec)
* @param ygyro Angular speed around Y axis (rad / sec)
* @param zgyro Angular speed around Z axis (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in hectopascal
* @param diff_pressure Differential pressure in hectopascal
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_boot_ms, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[60];
_mav_put_uint64_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 8, xacc);
_mav_put_float(buf, 12, yacc);
_mav_put_float(buf, 16, zacc);
_mav_put_float(buf, 20, xgyro);
_mav_put_float(buf, 24, ygyro);
_mav_put_float(buf, 28, zgyro);
_mav_put_float(buf, 32, xmag);
_mav_put_float(buf, 36, ymag);
_mav_put_float(buf, 40, zmag);
_mav_put_float(buf, 44, abs_pressure);
_mav_put_float(buf, 48, diff_pressure);
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 60);
#else
mavlink_highres_imu_t packet;
packet.time_boot_ms = time_boot_ms;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
packet.abs_pressure = abs_pressure;
packet.diff_pressure = diff_pressure;
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 60);
#endif
msg->msgid = MAVLINK_MSG_ID_HIGHRES_IMU;
return mavlink_finalize_message(msg, system_id, component_id, 60, 106);
}
/**
* @brief Pack a highres_imu message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis (rad / sec)
* @param ygyro Angular speed around Y axis (rad / sec)
* @param zgyro Angular speed around Z axis (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in hectopascal
* @param diff_pressure Differential pressure in hectopascal
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_boot_ms,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[60];
_mav_put_uint64_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 8, xacc);
_mav_put_float(buf, 12, yacc);
_mav_put_float(buf, 16, zacc);
_mav_put_float(buf, 20, xgyro);
_mav_put_float(buf, 24, ygyro);
_mav_put_float(buf, 28, zgyro);
_mav_put_float(buf, 32, xmag);
_mav_put_float(buf, 36, ymag);
_mav_put_float(buf, 40, zmag);
_mav_put_float(buf, 44, abs_pressure);
_mav_put_float(buf, 48, diff_pressure);
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 60);
#else
mavlink_highres_imu_t packet;
packet.time_boot_ms = time_boot_ms;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
packet.abs_pressure = abs_pressure;
packet.diff_pressure = diff_pressure;
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 60);
#endif
msg->msgid = MAVLINK_MSG_ID_HIGHRES_IMU;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 60, 106);
}
/**
* @brief Encode a highres_imu struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param highres_imu C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_highres_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu)
{
return mavlink_msg_highres_imu_pack(system_id, component_id, msg, highres_imu->time_boot_ms, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature);
}
/**
* @brief Send a highres_imu message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis (rad / sec)
* @param ygyro Angular speed around Y axis (rad / sec)
* @param zgyro Angular speed around Z axis (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in hectopascal
* @param diff_pressure Differential pressure in hectopascal
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_highres_imu_send(mavlink_channel_t chan, uint64_t time_boot_ms, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[60];
_mav_put_uint64_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 8, xacc);
_mav_put_float(buf, 12, yacc);
_mav_put_float(buf, 16, zacc);
_mav_put_float(buf, 20, xgyro);
_mav_put_float(buf, 24, ygyro);
_mav_put_float(buf, 28, zgyro);
_mav_put_float(buf, 32, xmag);
_mav_put_float(buf, 36, ymag);
_mav_put_float(buf, 40, zmag);
_mav_put_float(buf, 44, abs_pressure);
_mav_put_float(buf, 48, diff_pressure);
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, 60, 106);
#else
mavlink_highres_imu_t packet;
packet.time_boot_ms = time_boot_ms;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
packet.abs_pressure = abs_pressure;
packet.diff_pressure = diff_pressure;
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, 60, 106);
#endif
}
#endif
// MESSAGE HIGHRES_IMU UNPACKING
/**
* @brief Get field time_boot_ms from highres_imu message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint64_t mavlink_msg_highres_imu_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field xacc from highres_imu message
*
* @return X acceleration (m/s^2)
*/
static inline float mavlink_msg_highres_imu_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field yacc from highres_imu message
*
* @return Y acceleration (m/s^2)
*/
static inline float mavlink_msg_highres_imu_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field zacc from highres_imu message
*
* @return Z acceleration (m/s^2)
*/
static inline float mavlink_msg_highres_imu_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field xgyro from highres_imu message
*
* @return Angular speed around X axis (rad / sec)
*/
static inline float mavlink_msg_highres_imu_get_xgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field ygyro from highres_imu message
*
* @return Angular speed around Y axis (rad / sec)
*/
static inline float mavlink_msg_highres_imu_get_ygyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field zgyro from highres_imu message
*
* @return Angular speed around Z axis (rad / sec)
*/
static inline float mavlink_msg_highres_imu_get_zgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field xmag from highres_imu message
*
* @return X Magnetic field (Gauss)
*/
static inline float mavlink_msg_highres_imu_get_xmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field ymag from highres_imu message
*
* @return Y Magnetic field (Gauss)
*/
static inline float mavlink_msg_highres_imu_get_ymag(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field zmag from highres_imu message
*
* @return Z Magnetic field (Gauss)
*/
static inline float mavlink_msg_highres_imu_get_zmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field abs_pressure from highres_imu message
*
* @return Absolute pressure in hectopascal
*/
static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Get field diff_pressure from highres_imu message
*
* @return Differential pressure in hectopascal
*/
static inline float mavlink_msg_highres_imu_get_diff_pressure(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 48);
}
/**
* @brief Get field pressure_alt from highres_imu message
*
* @return Altitude calculated from pressure
*/
static inline float mavlink_msg_highres_imu_get_pressure_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 52);
}
/**
* @brief Get field temperature from highres_imu message
*
* @return Temperature in degrees celsius
*/
static inline float mavlink_msg_highres_imu_get_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 56);
}
/**
* @brief Decode a highres_imu message into a struct
*
* @param msg The message to decode
* @param highres_imu C-struct to decode the message contents into
*/
static inline void mavlink_msg_highres_imu_decode(const mavlink_message_t* msg, mavlink_highres_imu_t* highres_imu)
{
#if MAVLINK_NEED_BYTE_SWAP
highres_imu->time_boot_ms = mavlink_msg_highres_imu_get_time_boot_ms(msg);
highres_imu->xacc = mavlink_msg_highres_imu_get_xacc(msg);
highres_imu->yacc = mavlink_msg_highres_imu_get_yacc(msg);
highres_imu->zacc = mavlink_msg_highres_imu_get_zacc(msg);
highres_imu->xgyro = mavlink_msg_highres_imu_get_xgyro(msg);
highres_imu->ygyro = mavlink_msg_highres_imu_get_ygyro(msg);
highres_imu->zgyro = mavlink_msg_highres_imu_get_zgyro(msg);
highres_imu->xmag = mavlink_msg_highres_imu_get_xmag(msg);
highres_imu->ymag = mavlink_msg_highres_imu_get_ymag(msg);
highres_imu->zmag = mavlink_msg_highres_imu_get_zmag(msg);
highres_imu->abs_pressure = mavlink_msg_highres_imu_get_abs_pressure(msg);
highres_imu->diff_pressure = mavlink_msg_highres_imu_get_diff_pressure(msg);
highres_imu->pressure_alt = mavlink_msg_highres_imu_get_pressure_alt(msg);
highres_imu->temperature = mavlink_msg_highres_imu_get_temperature(msg);
#else
memcpy(highres_imu, _MAV_PAYLOAD(msg), 60);
#endif
}

View File

@ -3715,6 +3715,75 @@ static void mavlink_test_vicon_position_estimate(uint8_t system_id, uint8_t comp
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_highres_imu(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_highres_imu_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
241.0,
269.0,
297.0,
325.0,
353.0,
381.0,
409.0,
};
mavlink_highres_imu_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.xacc = packet_in.xacc;
packet1.yacc = packet_in.yacc;
packet1.zacc = packet_in.zacc;
packet1.xgyro = packet_in.xgyro;
packet1.ygyro = packet_in.ygyro;
packet1.zgyro = packet_in.zgyro;
packet1.xmag = packet_in.xmag;
packet1.ymag = packet_in.ymag;
packet1.zmag = packet_in.zmag;
packet1.abs_pressure = packet_in.abs_pressure;
packet1.diff_pressure = packet_in.diff_pressure;
packet1.pressure_alt = packet_in.pressure_alt;
packet1.temperature = packet_in.temperature;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_highres_imu_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_highres_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_highres_imu_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.abs_pressure , packet1.diff_pressure , packet1.pressure_alt , packet1.temperature );
mavlink_msg_highres_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_highres_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.abs_pressure , packet1.diff_pressure , packet1.pressure_alt , packet1.temperature );
mavlink_msg_highres_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_highres_imu_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_highres_imu_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.abs_pressure , packet1.diff_pressure , packet1.pressure_alt , packet1.temperature );
mavlink_msg_highres_imu_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_memory_vect(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
@ -4072,6 +4141,7 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_vision_position_estimate(system_id, component_id, last_msg);
mavlink_test_vision_speed_estimate(system_id, component_id, last_msg);
mavlink_test_vicon_position_estimate(system_id, component_id, last_msg);
mavlink_test_highres_imu(system_id, component_id, last_msg);
mavlink_test_memory_vect(system_id, component_id, last_msg);
mavlink_test_debug_vect(system_id, component_id, last_msg);
mavlink_test_named_value_float(system_id, component_id, last_msg);

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Aug 23 16:39:58 2012"
#define MAVLINK_BUILD_DATE "Mon Sep 3 14:56:15 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

File diff suppressed because one or more lines are too long

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Aug 23 16:39:39 2012"
#define MAVLINK_BUILD_DATE "Mon Sep 3 14:56:05 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

File diff suppressed because one or more lines are too long

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Aug 23 16:39:49 2012"
#define MAVLINK_BUILD_DATE "Mon Sep 3 14:56:15 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

View File

@ -3202,4 +3202,51 @@
for control transfers but does not resolve all of the issues.
* configs/stm3220g-eval/*/defconfig: Calibrated delay loop. It had
never been calibrated was was way off.
* sched/sem_holder.c: Add logic to handler some priority inheritance
cases when sem_post() is called from an interrupt handler. The
logic is clearly wrong, but it is not known if this is the
cause of any known bugs.
* lib/stdio/lib_perror(): Add perror(). Contributed by Kate.
* lib/string/lib_strerror(): Add option CONFIG_LIBC_STRERROR that
is now required to enabled strerror(). Add an option
CONFIG_LIBC_STRERROR_SHORT that can be used to output shortened
strings by strerror().
* arch/arm/src/stm32/stm32_usbotghost.c: Finally... the USB OTG FS
appears to handle NAKing correctly is complete.
* configs/stm32f4discovery/*: Added and verifed support for USB OTG FS
host on the STM32F4Discovery board.
* configs/*/defconfig: Remove configuration documentation from config
files. It is redundant, error-prone, and difficult to maintain.
Configuration documentation is available in configs/README.txt for
common configurations and in configs/*/README.txt for board and MCU_
specific configurations.
* configs/stm3240g-eval: Add USB host support.
* sched/os_bring.c, configs/*/defconfig, tools/mkconfig.c, and others: Added
configuration variable CONFIG_USER_ENTRYPOINT that may be used to change
the default entry from user_start to some other symbol. Contributed by
Kate. NOTE: This change does introduce a minor backward incompatibility.
For example, if your application uses NSH as its start-up program, then your
code will not fail because it will be unable to find "user_start". The fix
for this link failure is to add the following to your configuration file:
CONFIG_USER_ENTRYPOINT="nsh_main".
* libs/stdio/lib_libfread.c and lib_*flush*.c: Correct a couple of
error cases where the lib semaphore was not be released on error
exits (thanks Ronen Vainish). Also, improved some error reporting:
the generic ERROR was being used instead of the specific errno
value; the errno variable was not always set correctly.
* tools/mkfsdata.pl: The uIP web server CGI image making perl script was
moved from apps/netutils/webserver/makefsdata to nuttx/tools/mkfsdata.pl
(Part of a larger change submitted by Max Holtzberg).
* configs/stm3240g-eval/script/ld.script: All of the identical ld.script
files for the STM3240G-EVAL were replaced by one version in this directory.
* configs/stm3240g-eval/webserver: Configuration submitted by Max Holtzberg
for testing the changes to the uIP web server (see apps/ChangeLog.txt).
* lib/stdio/lib_perror.c: Remove CONFIG_LIBC_PERROR_DEVNAME. What was I
thinking? Arbitrary streams cannot be shared by different tasks.
* tools/mksyscall.c, csvparser.c, and csvparser.h: Separate CSV parsing
logic from mksyscall.c into files where it can be shared.
* tools/mksymtab.c: Add a tool that can be used to convert a CSV file
into a NuttX-style symbol table.
* sched/work_cancel.c: Fix a bad assertion (reported by Mike Smith)
* configs/stm3210e-eval/src/up_idle.c: Correct some power management
compilation errors (reported by Diego Sanchez).

View File

@ -43,15 +43,12 @@
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include <unistd.h>
#include <semaphore.h>
#include <string.h>
#include <errno.h>
#include <debug.h>
#if !defined(CONFIG_DEBUG_VERBOSE) && !defined(CONFIG_DEBUG_USB)
# include <debug.h>
#endif
#include <nuttx/arch.h>
#include <nuttx/kmalloc.h>
#include <nuttx/usb/usb.h>
@ -315,6 +312,10 @@ static int stm32_ctrl_senddata(FAR struct stm32_usbhost_s *priv,
FAR uint8_t *buffer, unsigned int buflen);
static int stm32_ctrl_recvdata(FAR struct stm32_usbhost_s *priv,
FAR uint8_t *buffer, unsigned int buflen);
static int stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx,
FAR uint8_t *buffer, size_t buflen);
static int stm32_out_transfer(FAR struct stm32_usbhost_s *priv, int chidx,
FAR uint8_t *buffer, size_t buflen);
/* Interrupt handling **********************************************************/
/* Lower level interrupt handlers */
@ -751,7 +752,7 @@ static void stm32_chan_configure(FAR struct stm32_usbhost_s *priv, int chidx)
stm32_putreg(STM32_OTGFS_HCINTMSK(chidx), regval);
/* Enable the top level host channel interrupt. */
stm32_modifyreg(STM32_OTGFS_HAINTMSK, 0, OTGFS_HAINT(chidx));
/* Make sure host channel interrupts are enabled. */
@ -808,7 +809,7 @@ static void stm32_chan_halt(FAR struct stm32_usbhost_s *priv, int chidx,
uint32_t eptype;
unsigned int avail;
/* Save the recon for the halt. We need this in the channel halt interrrupt
/* Save the reason for the halt. We need this in the channel halt interrrupt
* handling logic to know what to do next.
*/
@ -1157,7 +1158,7 @@ static void stm32_transfer_start(FAR struct stm32_usbhost_s *priv, int chidx)
unsigned int wrpackets = avail / chan->maxpacket;
wrsize = wrpackets * chan->maxpacket;
}
/* Write packet into the Tx FIFO. */
stm32_gint_wrpacket(priv, chan->buffer, chidx, wrsize);
@ -1354,6 +1355,254 @@ static int stm32_ctrl_recvdata(FAR struct stm32_usbhost_s *priv,
return stm32_chan_wait(priv, chan);
}
/*******************************************************************************
* Name: stm32_in_transfer
*
* Description:
* Transfer 'buflen' bytes into 'buffer' from an IN channel.
*
*******************************************************************************/
static int stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx,
FAR uint8_t *buffer, size_t buflen)
{
FAR struct stm32_chan_s *chan;
uint16_t start;
uint16_t elapsed;
int ret = OK;
/* Loop until the transfer completes (i.e., buflen is decremented to zero)
* or a fatal error occurs (any error other than a simple NAK)
*/
chan = &priv->chan[chidx];
chan->buffer = buffer;
chan->buflen = buflen;
start = stm32_getframe();
while (chan->buflen > 0)
{
/* Set up for the wait BEFORE starting the transfer */
ret = stm32_chan_waitsetup(priv, chan);
if (ret != OK)
{
udbg("ERROR: Device disconnected\n");
return ret;
}
/* Set up for the transfer based on the direction and the endpoint type */
switch (chan->eptype)
{
default:
case OTGFS_EPTYPE_CTRL: /* Control */
{
/* This kind of transfer on control endpoints other than EP0 are not
* currently supported
*/
return -ENOSYS;
}
case OTGFS_EPTYPE_ISOC: /* Isochronous */
{
/* Set up the IN data PID */
chan->pid = OTGFS_PID_DATA0;
}
break;
case OTGFS_EPTYPE_BULK: /* Bulk */
case OTGFS_EPTYPE_INTR: /* Interrupt */
{
/* Setup the IN data PID */
chan->pid = chan->indata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
}
break;
}
/* Start the transfer */
stm32_transfer_start(priv, chidx);
/* Wait for the transfer to complete and get the result */
ret = stm32_chan_wait(priv, chan);
/* EAGAIN indicates that the device NAKed the transfer and we need
* do try again. Anything else (success or other errors) will
* cause use to return
*/
if (ret != OK)
{
udbg("Transfer failed: %d\n", ret);
/* Check for a special case: If (1) the transfer was NAKed and (2)
* no Tx FIFO empty or Rx FIFO not-empty event occurred, then we
* should be able to just flush the Rx and Tx FIFOs and try again.
* We can detect this latter case becasue the then the transfer
* buffer pointer and buffer size will be unaltered.
*/
elapsed = stm32_getframe() - start;
if (ret != -EAGAIN || /* Not a NAK condition OR */
elapsed >= STM32_DATANAK_DELAY || /* Timeout has elapsed OR */
chan->buflen != buflen) /* Data has been partially transferred */
{
/* Break out and return the error */
break;
}
}
}
return ret;
}
/*******************************************************************************
* Name: stm32_out_transfer
*
* Description:
* Transfer the 'buflen' bytes in 'buffer' through an OUT channel.
*
*******************************************************************************/
static int stm32_out_transfer(FAR struct stm32_usbhost_s *priv, int chidx,
FAR uint8_t *buffer, size_t buflen)
{
FAR struct stm32_chan_s *chan;
uint16_t start;
uint16_t elapsed;
size_t xfrlen;
int ret = OK;
/* Loop until the transfer completes (i.e., buflen is decremented to zero)
* or a fatal error occurs (any error other than a simple NAK)
*/
chan = &priv->chan[chidx];
start = stm32_getframe();
while (buflen > 0)
{
/* Transfer one packet at a time. The hardware is capable of queueing
* multiple OUT packets, but I just haven't figured out how to handle
* the case where a single OUT packet in the group is NAKed.
*/
xfrlen = MIN(chan->maxpacket, buflen);
chan->buffer = buffer;
chan->buflen = xfrlen;
/* Set up for the wait BEFORE starting the transfer */
ret = stm32_chan_waitsetup(priv, chan);
if (ret != OK)
{
udbg("ERROR: Device disconnected\n");
return ret;
}
/* Set up for the transfer based on the direction and the endpoint type */
switch (chan->eptype)
{
default:
case OTGFS_EPTYPE_CTRL: /* Control */
{
/* This kind of transfer on control endpoints other than EP0 are not
* currently supported
*/
return -ENOSYS;
}
case OTGFS_EPTYPE_ISOC: /* Isochronous */
{
/* Set up the OUT data PID */
chan->pid = OTGFS_PID_DATA0;
}
break;
case OTGFS_EPTYPE_BULK: /* Bulk */
{
/* Setup the OUT data PID */
chan->pid = chan->outdata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
}
break;
case OTGFS_EPTYPE_INTR: /* Interrupt */
{
/* Setup the OUT data PID */
chan->pid = chan->outdata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
/* Toggle the OUT data PID for the next transfer */
chan->outdata1 ^= true;
}
}
/* Start the transfer */
stm32_transfer_start(priv, chidx);
/* Wait for the transfer to complete and get the result */
ret = stm32_chan_wait(priv, chan);
/* Handle transfer failures */
if (ret != OK)
{
udbg("Transfer failed: %d\n", ret);
/* Check for a special case: If (1) the transfer was NAKed and (2)
* no Tx FIFO empty or Rx FIFO not-empty event occurred, then we
* should be able to just flush the Rx and Tx FIFOs and try again.
* We can detect this latter case becasue the then the transfer
* buffer pointer and buffer size will be unaltered.
*/
elapsed = stm32_getframe() - start;
if (ret != -EAGAIN || /* Not a NAK condition OR */
elapsed >= STM32_DATANAK_DELAY || /* Timeout has elapsed OR */
chan->buflen != xfrlen) /* Data has been partially transferred */
{
/* Break out and return the error */
break;
}
/* Is this flush really necessary? What does the hardware do with the
* data in the FIFO when the NAK occurs? Does it discard it?
*/
stm32_flush_txfifos(OTGFS_GRSTCTL_TXFNUM_HALL);
/* Get the device a little time to catch up. Then retry the transfer
* using the same buffer pointer and length.
*/
usleep(20*1000);
}
else
{
/* Successfully transferred. Update the buffer pointer and length */
buffer += xfrlen;
buflen -= xfrlen;
}
}
return ret;
}
/*******************************************************************************
* Name: stm32_gint_wrpacket
*
@ -1923,7 +2172,7 @@ static void stm32_gint_disconnected(FAR struct stm32_usbhost_s *priv)
if (!priv->connected)
{
/* Yes.. then we no longer connected */
ullvdbg("Disconnected\n");
/* Are we bound to a class driver? */
@ -2148,7 +2397,7 @@ static inline void stm32_gint_nptxfeisr(FAR struct stm32_usbhost_s *priv)
unsigned int wrpackets = avail / chan->maxpacket;
wrsize = wrpackets * chan->maxpacket;
}
/* Otherwise, this will be the last packet to be sent in this transaction.
* We now need to disable further NPTXFE interrupts.
*/
@ -2238,7 +2487,7 @@ static inline void stm32_gint_ptxfeisr(FAR struct stm32_usbhost_s *priv)
unsigned int wrpackets = avail / chan->maxpacket;
wrsize = wrpackets * chan->maxpacket;
}
/* Otherwise, this will be the last packet to be sent in this transaction.
* We now need to disable further PTXFE interrupts.
*/
@ -2382,7 +2631,7 @@ static inline void stm32_gint_hprtisr(FAR struct stm32_usbhost_s *priv)
/* Set the Host Frame Interval Register for the 6KHz speed */
stm32_putreg(STM32_OTGFS_HFIR, 6000);
/* Are we switching from FS to LS? */
if ((hcfg & OTGFS_HCFG_FSLSPCS_MASK) != OTGFS_HCFG_FSLSPCS_LS6MHz)
@ -2459,7 +2708,7 @@ static inline void stm32_gint_iisooxfrisr(FAR struct stm32_usbhost_s *priv)
/* CHENA : Set to enable the channel
* CHDIS : Set to stop transmitting/receiving data on a channel
*/
regval = stm32_getreg(STM32_OTGFS_HCCHAR(0));
regval |= (OTGFS_HCCHAR_CHDIS | OTGFS_HCCHAR_CHENA);
stm32_putreg(STM32_OTGFS_HCCHAR(0), regval);
@ -2718,7 +2967,7 @@ static void stm32_txfe_enable(FAR struct stm32_usbhost_s *priv, int chidx)
/* Disable all interrupts so that we have exclusive access to the GINTMSK
* (it would be sufficent just to disable the GINT interrupt).
*/
flags = irqsave();
/* Should we enable the periodic or non-peridic Tx FIFO empty interrupts */
@ -2842,7 +3091,7 @@ static int stm32_enumerate(FAR struct usbhost_driver_s *drvr)
}
DEBUGASSERT(priv->smstate == SMSTATE_ATTACHED);
/* Allocate and initialize the control OUT channel */
chidx = stm32_chan_alloc(priv);
@ -2869,9 +3118,9 @@ static int stm32_enumerate(FAR struct usbhost_driver_s *drvr)
priv->chan[chidx].indata1 = false;
priv->chan[chidx].outdata1 = false;
/* USB 2.0 spec says at least 50ms delay before port reset */
/* USB 2.0 spec says at least 50ms delay before port reset. We wait 100ms. */
up_mdelay(100);
usleep(100*1000);
/* Reset the host port */
@ -2956,12 +3205,12 @@ static int stm32_ep0configure(FAR struct usbhost_driver_s *drvr, uint8_t funcadd
priv->chan[priv->ep0out].maxpacket = maxpacketsize;
stm32_chan_configure(priv, priv->ep0out);
/* Configure the EP0 IN channel */
priv->chan[priv->ep0in].maxpacket = maxpacketsize;
stm32_chan_configure(priv, priv->ep0in);
stm32_givesem(&priv->exclsem);
return OK;
}
@ -3427,7 +3676,7 @@ static int stm32_ctrlout(FAR struct usbhost_driver_s *drvr,
}
/* Handle the status IN phase */
if (ret == OK)
{
ret = stm32_ctrl_recvdata(priv, NULL, 0);
@ -3492,145 +3741,33 @@ static int stm32_ctrlout(FAR struct usbhost_driver_s *drvr,
* - Never called from an interrupt handler.
*
*******************************************************************************/
static int stm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep,
FAR uint8_t *buffer, size_t buflen)
{
struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
FAR struct stm32_chan_s *chan;
FAR struct stm32_usbhost_s *priv = (FAR struct stm32_usbhost_s *)drvr;
unsigned int chidx = (unsigned int)ep;
int ret = OK;
int ret;
uvdbg("chidx: %d buflen: %d\n", (unsigned int)ep, buflen);
DEBUGASSERT(priv && buffer && chidx < STM32_MAX_TX_FIFOS && buflen > 0);
chan = &priv->chan[chidx];
/* We must have exclusive access to the USB host hardware and state structures */
stm32_takesem(&priv->exclsem);
/* Loop until the transfer completes (i.e., buflen is decremented to zero)
* or a fatal error occurs (any error other than a simple NAK)
*/
/* Handle IN and OUT transfer slightly differently */
chan->buffer = buffer;
chan->buflen = buflen;
while (chan->buflen > 0)
if (priv->chan[chidx].in)
{
/* Set up for the wait BEFORE starting the transfer */
ret = stm32_chan_waitsetup(priv, chan);
if (ret != OK)
{
udbg("ERROR: Device disconnected\n");
goto errout;
}
/* Set up for the transfer based on the direction and the endpoint type */
switch (chan->eptype)
{
default:
case OTGFS_EPTYPE_CTRL: /* Control */
{
/* This kind of transfer on control endpoints other than EP0 are not
* currently supported
*/
ret = -ENOSYS;
goto errout;
}
case OTGFS_EPTYPE_ISOC: /* Isochronous */
{
/* Set up the IN/OUT data PID */
chan->pid = OTGFS_PID_DATA0;
}
break;
case OTGFS_EPTYPE_BULK: /* Bulk */
{
/* Handle the bulk transfer based on the direction of the transfer. */
if (chan->in)
{
/* Setup the IN data PID */
chan->pid = chan->indata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
}
else
{
/* Setup the OUT data PID */
chan->pid = chan->outdata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
}
}
break;
case OTGFS_EPTYPE_INTR: /* Interrupt */
{
/* Handle the interrupt transfer based on the direction of the
* transfer.
*/
if (chan->in)
{
/* Setup the IN data PID */
chan->pid = chan->indata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
/* The indata1 data toggle will be updated in the Rx FIFO
* interrupt handling logic as each packet is received.
*/
}
else
{
/* Setup the OUT data PID */
chan->pid = chan->outdata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
/* Toggle the OUT data PID for the next transfer */
chan->outdata1 ^= true;
}
}
}
/* There is a bug in the code at present. With debug OFF, this driver
* overruns the typical FLASH device and there are many problems with
* NAKS sticking a big delay here allows the driver to work but with
* very poor performance when debug is off.
*/
#if !defined(CONFIG_DEBUG_VERBOSE) && !defined(CONFIG_DEBUG_USB)
#warning "REVISIT this delay"
usleep(100*1000);
#endif
/* Start the transfer */
stm32_transfer_start(priv, chidx);
/* Wait for the transfer to complete and get the result */
ret = stm32_chan_wait(priv, chan);
/* EAGAIN indicates that the device NAKed the transfer and we need
* do try again. Anything else (success or other errors) will
* cause use to return
*/
if (ret != OK)
{
udbg("Transfer failed: %d\n", ret);
break;
}
ret = stm32_in_transfer(priv, chidx, buffer, buflen);
}
else
{
ret = stm32_out_transfer(priv, chidx, buffer, buflen);
}
errout:
stm32_givesem(&priv->exclsem);
return ret;
}
@ -3663,7 +3800,7 @@ static void stm32_disconnect(FAR struct usbhost_driver_s *drvr)
struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
priv->class = NULL;
}
/*******************************************************************************
* Initialization
*******************************************************************************/
@ -3979,7 +4116,7 @@ static inline int stm32_hw_initialize(FAR struct stm32_usbhost_s *priv)
/* Set the PHYSEL bit in the GUSBCFG register to select the OTG FS serial
* transceiver: "This bit is always 1 with write-only access"
*/
regval = stm32_getreg(STM32_OTGFS_GUSBCFG);;
regval |= OTGFS_GUSBCFG_PHYSEL;
stm32_putreg(STM32_OTGFS_GUSBCFG, regval);
@ -4128,7 +4265,7 @@ FAR struct usbhost_driver_s *usbhost_initialize(int controller)
stm32_configgpio(GPIO_OTGFS_SOF);
#endif
/* Initialize the USB OTG FS core */
/* Initialize the USB OTG FS core */
stm32_hw_initialize(priv);

View File

@ -7,6 +7,7 @@ Table of Contents
o Summary of Files
o Supported Architectures
o Configuring NuttX
o Building Symbol Tables
Board-Specific Configurations
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
@ -268,6 +269,7 @@ defconfig -- This is a configuration file similar to the Linux
by default)
CONFIG_DEBUG_GRAPHICS - enable NX graphics debug output
(disabled by default)
CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot
time console output
CONFIG_MM_REGIONS - If the architecture includes multiple
@ -331,7 +333,7 @@ defconfig -- This is a configuration file similar to the Linux
threads (minus 1) than can be waiting for another thread
to release a count on a semaphore. This value may be set
to zero if no more than one thread is expected to wait for
a semaphore. If defined, then this should be a relatively
a semaphore. If defined, then this should be a relatively
small number because this the number of maximumum of waiters
on one semaphore (like 4 or 8).
CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors
@ -375,6 +377,10 @@ defconfig -- This is a configuration file similar to the Linux
CONFIG_SCHED_ONEXIT_MAX - By default if CONFIG_SCHED_ONEXIT is selected,
only a single on_exit() function is supported. That number can be
increased by defined this setting to the number that you require.
CONFIG_USER_ENTRYPOINT - The name of the entry point for user
applications. For the example applications this is of the form 'app_main'
where 'app' is the application name. If not defined, CONFIG_USER_ENTRYPOINT
defaults to user_start.
System Logging:
CONFIG_SYSLOG enables general system logging support.
@ -546,10 +552,28 @@ defconfig -- This is a configuration file similar to the Linux
Misc libc settings
CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a
little smaller if we do not support fieldwidthes
CONFIG_LIBC_FLOATINGPOINT - By default, floating point
support in printf, sscanf, etc. is disabled.
CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a little smaller
if we do not support fieldwidthes
CONFIG_LIBC_FLOATINGPOINT - By default, floating point support in printf,
sscanf, etc. is disabled.
CONFIG_LIBC_STRERROR - strerror() is useful because it decodes 'errno'
values into a human readable strings. But it can also require
a lot of memory. If this option is selected, strerror() will still
exist in the build but it will not decode error values. This option
should be used by other logic to decide if it should use strerror() or
not. For example, the NSH application will not use strerror() if this
option is not selected; perror() will not use strerror() is this option
is not selected (see also CONFIG_NSH_STRERROR).
CONFIG_LIBC_STRERROR_SHORT - If this option is selected, then strerror()
will use a shortened string when it decodes the error. Specifically,
strerror() is simply use the string that is the common name for the
error. For example, the 'errno' value of 2 will produce the string
"No such file or directory" if CONFIG_LIBC_STRERROR_SHORT is not
defined but the string "ENOENT" if CONFIG_LIBC_STRERROR_SHORT is
defined.
CONFIG_LIBC_PERROR_STDOUT - POSIX requires that perror() provide its output
on stderr. This option may be defined, however, to provide perror() output
that is serialized with other stdout messages.
Allow for architecture optimized implementations
@ -1782,3 +1806,26 @@ command line like:
cd tools
./configure.sh -a <app-dir> <board-name>/<config-dir>
Building Symbol Tables
^^^^^^^^^^^^^^^^^^^^^^
Symbol tables are needed at several of the binfmt interfaces in order to bind
a module to the base code. These symbol tables can be tricky to create and
will probably have to be tailored for any specific application, balancing
the number of symbols and the size of the symbol table against the symbols
required by the applications.
The top-level System.map file is one good source of symbol information
(which, or course, was just generated from the top-level nuttx file
using the GNU 'nm' tool).
There are also common-separated value (CSV) values in the source try that
provide information about symbols. In particular:
nuttx/syscall/syscall.csv - Describes the NuttX RTOS interface, and
nuttx/lib/lib.csv - Describes the NuttX C library interface.
There is a tool at nuttx/tools/mksymtab that will use these CSV files as
input to generate a generic symbol table. See nuttx/tools/README.txt for
more information about using the mksymtab tool.

View File

@ -510,6 +510,7 @@ CONFIG_HAVE_LIBM=y
# CONFIG_SCHED_WAITPID - Enable the waitpid() API
# CONFIG_SCHED_ATEXIT - Enabled the atexit() API
#
CONFIG_USER_ENTRYPOINT="nsh_main"
#CONFIG_APPS_DIR=
CONFIG_DEBUG=y
CONFIG_DEBUG_VERBOSE=y

View File

@ -323,6 +323,7 @@ CONFIG_HAVE_LIBM=n
# CONFIG_SCHED_WAITPID - Enable the waitpid() API
# CONFIG_SCHED_ATEXIT - Enabled the atexit() API
#
CONFIG_USER_ENTRYPOINT="user_start"
#CONFIG_APPS_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n

View File

@ -42,6 +42,7 @@
#include <sys/types.h>
#include <stdint.h>
#include <string.h>
#include <unistd.h>
#include <errno.h>
#include <assert.h>
#include <debug.h>
@ -317,7 +318,7 @@ int usbhost_enumerate(FAR struct usbhost_driver_s *drvr, uint8_t funcaddr,
DEBUGASSERT(drvr && class);
/* Allocate TD buffers for use in this function. We will need two:
/* Allocate descriptor buffers for use in this function. We will need two:
* One for the request and one for the data buffer.
*/
@ -400,7 +401,7 @@ int usbhost_enumerate(FAR struct usbhost_driver_s *drvr, uint8_t funcaddr,
udbg("ERROR: SETADDRESS DRVR_CTRLOUT returned %d\n", ret);
goto errout;
}
up_mdelay(2);
usleep(2*1000);
/* Modify control pipe with the provided USB device address */
@ -461,9 +462,9 @@ int usbhost_enumerate(FAR struct usbhost_driver_s *drvr, uint8_t funcaddr,
goto errout;
}
/* Free the TD that we were using for the request buffer. It is not needed
* further here but it may be needed by the class driver during its connection
* operations.
/* Free the descriptor buffer that we were using for the request buffer.
* It is not needed further here but it may be needed by the class driver
* during its connection operations.
*/
DRVR_FREE(drvr, (uint8_t*)ctrlreq);
@ -488,9 +489,9 @@ int usbhost_enumerate(FAR struct usbhost_driver_s *drvr, uint8_t funcaddr,
}
}
/* Some devices may require this delay before initialization */
/* Some devices may require some delay before initialization */
up_mdelay(100);
usleep(100*1000);
/* Parse the configuration descriptor and bind to the class instance for the
* device. This needs to be the last thing done because the class driver

View File

@ -42,6 +42,7 @@
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <semaphore.h>
#include <assert.h>
#include <errno.h>
@ -724,6 +725,7 @@ static inline int usbhost_testunitready(FAR struct usbhost_state_s *priv)
usbhost_dumpcsw((FAR struct usbmsc_csw_s *)priv->tbuffer);
}
}
return result;
}
@ -1195,13 +1197,15 @@ static inline int usbhost_initvolume(FAR struct usbhost_state_s *priv)
uvdbg("Get max LUN\n");
ret = usbhost_maxlunreq(priv);
/* Wait for the unit to be ready */
for (retries = 0; retries < USBHOST_MAX_RETRIES && ret == OK; retries++)
for (retries = 0; retries < USBHOST_MAX_RETRIES /* && ret == OK */; retries++)
{
uvdbg("Test unit ready, retries=%d\n", retries);
/* Send TESTUNITREADY to see the unit is ready */
/* Wait just a bit */
usleep(50*1000);
/* Send TESTUNITREADY to see if the unit is ready */
ret = usbhost_testunitready(priv);
if (ret == OK)

View File

@ -91,6 +91,10 @@
#endif
#ifndef assert
#define assert ASSERT
#endif
/****************************************************************************
* Included Files
****************************************************************************/

View File

@ -55,8 +55,8 @@ extern "C" {
#define EXTERN extern
#endif
EXTERN char *basename(char *path);
EXTERN char *dirname(char *path);
EXTERN FAR char *basename(FAR char *path);
EXTERN FAR char *dirname(FAR char *path);
#undef EXTERN
#ifdef __cplusplus

View File

@ -63,7 +63,7 @@ extern "C" {
#define EXTERN extern
#endif
EXTERN char *ether_ntoa(const struct ether_addr *addr);
EXTERN FAR char *ether_ntoa(FAR const struct ether_addr *addr);
EXTERN struct ether_addr *ether_aton(const char *asc);
EXTERN int ether_ntohost(char *hostname, const struct ether_addr *addr);
EXTERN int ether_hostton(const char *hostname, struct ether_addr *addr);

View File

@ -68,7 +68,7 @@ extern "C" {
/* This entry point must be supplied by the application */
EXTERN int user_start(int argc, char *argv[]);
EXTERN int CONFIG_USER_ENTRYPOINT(int argc, char *argv[]);
/* Functions contained in os_task.c *****************************************/

View File

@ -128,6 +128,7 @@ EXTERN int sprintf(FAR char *buf, const char *format, ...);
EXTERN int asprintf (FAR char **ptr, const char *fmt, ...);
EXTERN int snprintf(FAR char *buf, size_t size, const char *format, ...);
EXTERN int sscanf(const char *buf, const char *fmt, ...);
EXTERN void perror(FAR const char *s);
EXTERN int ungetc(int c, FAR FILE *stream);
EXTERN int vprintf(FAR const char *format, va_list ap);

View File

@ -23,7 +23,7 @@ config NUNGET_CHARS
---help---
Number of characters that can be buffered by ungetc() (Only if NFILE_STREAMS > 0)
config CONFIG_LIB_HOMEDIR
config LIB_HOMEDIR
string "Home directory"
default "/"
depends on !DISABLE_ENVIRON
@ -51,6 +51,46 @@ config LIBC_FLOATINGPOINT
By default, floating point
support in printf, sscanf, etc. is disabled.
config LIBC_STRERROR
bool "Enable strerror"
default n
---help---
strerror() is useful because it decodes 'errno' values into a human readable
strings. But it can also require a lot of memory. If this option is selected,
strerror() will still exist in the build but it will not decode error values.
This option should be used by other logic to decide if it should use strerror()
or not. For example, the NSH application will not use strerror() if this
option is not selected; perror() will not use strerror() is this option is not
selected (see also NSH_STRERROR).
config LIBC_STRERROR_SHORT
bool "Use short error descriptions in strerror()"
default n
depends on LIBC_STRERROR
---help---
If this option is selected, then strerror() will use a shortened string when
it decodes the error. Specifically, strerror() is simply use the string that
is the common name for the error. For example, the 'errno' value of 2 will
produce the string "No such file or directory" is LIBC_STRERROR_SHORT
is not defined but the string "ENOENT" is LIBC_STRERROR_SHORT is defined.
config LIBC_PERROR_STDOUT
bool "perror() to stdout"
default n
---help---
POSIX requires that perror() provide its output on stderr. This option may
be defined, however, to provide perror() output that is serialized with
other stdout messages.
config LIBC_PERROR_DEVNAME
string "perror() to device"
default "/dev/console"
depends on !LIBC_PERROR_STDOUT
---help---
Another non-standard option is to provide perror() output to a logging device
or file. LIBC_PERROR_DEVNAME may be defined to be any write-able,
character device (or file).
config ARCH_LOWPUTC
bool "Low-level console output"
default "y"
@ -68,7 +108,7 @@ config ENABLE_ARCH_OPTIMIZED_FUN
The architecture may provide custom versions of certain
standard header files:
config ARCH_MATH_H, CONFIG_ARCH_STDBOOL_H, CONFIG_ARCH_STDINT_H
config ARCH_MATH_H, ARCH_STDBOOL_H, ARCH_STDINT_H
if ENABLE_ARCH_OPTIMIZED_FUN
config ARCH_MEMCPY

View File

@ -45,3 +45,40 @@ directory:
misc - Nonstandard "glue" logic, debug.h, crc32.h, dirent.h
Library Database
================
Information about functions available in the NuttX C library information is
maintained in a database. That "database" is implemented as a simple comma-
separated-value file, lib.csv. Most spreadsheets programs will accept this
format and can be used to maintain the library database.
This library database will (eventually) be used to generate symbol library
symbol table information that can be exported to external applications.
The format of the CSV file for each line is:
Field 1: Function name
Field 2: The header file that contains the function prototype
Field 3: Condition for compilation
Field 4: The type of function return value.
Field 5 - N+5: The type of each of the N formal parameters of the function
Each type field has a format as follows:
type name:
For all simpler types
formal type | actual type:
For array types where the form of the formal (eg. int parm[2])
differs from the type of actual passed parameter (eg. int*). This
is necessary because you cannot do simple casts to array types.
formal type | union member actual type | union member fieldname:
A similar situation exists for unions. For example, the formal
parameter type union sigval -- You cannot cast a uintptr_t to
a union sigval, but you can cast to the type of one of the union
member types when passing the actual paramter. Similarly, we
cannot cast a union sigval to a uinptr_t either. Rather, we need
to cast a specific union member fieldname to uintptr_t.
NOTE: The tool mksymtab can be used to generate a symbol table from this CSV
file. See nuttx/tools/README.txt for further details about the use of mksymtab.

170
nuttx/lib/lib.csv Normal file
View File

@ -0,0 +1,170 @@
"_inet_ntoa","arpa/inet.h","!defined(CONFIG_NET_IPv6) && !defined(CONFIG_CAN_PASS_STRUCTS)","FAR char","in_addr_t"
"abort","stdlib.h","","void"
"abs","stdlib.h","","int","int"
"asprintf","stdio.h","","int","FAR char **","const char *","..."
"avsprintf","stdio.h","","int","FAR char **","const char *","va_list"
"b16atan2","fixedmath.h","","b16_t","b16_t","b16_t"
"b16cos","fixedmath.h","","b16_t","b16_t"
"b16divb16","fixedmath.h","","b16_t","b16_t","b16_t"
"b16mulb16","fixedmath.h","","b16_t","b16_t","b16_t"
"b16sin","fixedmath.h","","b16_t","b16_t"
"b16sqr","fixedmath.h","","b16_t","b16_t"
"basename","libgen.h","","FAR char","FAR char *"
"cfgetspeed","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","speed_t","FAR const struct termios *"
"cfsetspeed","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","FAR struct termios *","speed_t"
"chdir","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)","int","FAR const char *"
"crc32","crc32.h","","uint32_t","FAR const uint8_t *","size_t"
"crc32part","crc32.h","","uint32_t","FAR const uint8_t *","size_t","uint32_t"
"dbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG)","int","const char *","..."
"dbg_enable","debug.h","defined(CONFIG_DEBUG_ENABLE)","void","bool"
"dirname","libgen.h","","FAR char","FAR char *"
"dq_addafter","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *"
"dq_addbefore","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *"
"dq_addfirst","queue.h","","void","FAR dq_entry_t *","dq_queue_t *"
"dq_addlast","queue.h","","void","FAR dq_entry_t *","dq_queue_t *"
"dq_rem","queue.h","","void","FAR dq_entry_t *","dq_queue_t *"
"dq_remfirst","queue.h","","FAR dq_entry_t","dq_queue_t *"
"dq_remlast","queue.h","","FAR dq_entry_t","dq_queue_t *"
"ether_ntoa","netinet/ether.h","","FAR char","FAR const struct ether_addr *"
"fclose","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *"
"fdopen","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR FILE","int","FAR const char *"
"fflush","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *"
"fgetc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *"
"fgetpos","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR fpos_t *"
"fgets","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR char","FAR char *","int","FAR FILE *"
"fileno","stdio.h","","int","FAR FILE *"
"fopen","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR FILE","FAR const char *","FAR const char *"
"fprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR const char *","..."
"fputc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","int c","FAR FILE *"
"fputs","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *","FAR FILE *"
"fread","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","size_t","FAR void *","size_t","size_t","FAR FILE *"
"fseek","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","long int","int"
"fsetpos","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","FAR fpos_t *"
"ftell","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","long","FAR FILE *"
"fwrite","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","size_t","FAR const void *","size_t","size_t","FAR FILE *"
"getcwd","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)","FAR char","FAR char *","size_t"
"getopt","unistd.h","","int","int","FAR char *const[]","FAR const char *"
"getoptargp","unistd.h","","FAR char *"
"getoptindp","unistd.h","","int"
"getoptoptp","unistd.h","","int"
"gets","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR char","FAR char *"
"gmtime","time.h","","struct tm","const time_t *"
"gmtime_r","time.h","","FAR struct tm","FAR const time_t *","FAR struct tm *"
"htonl","arpa/inet.h","","uint32_t","uint32_t"
"htons","arpa/inet.h","","uint16_t","uint16_t"
"imaxabs","stdlib.h","","intmax_t","intmax_t"
"inet_addr","arpa/inet.h","","in_addr_t","FAR const char "
"inet_ntoa","arpa/inet.h","!defined(CONFIG_NET_IPv6) && defined(CONFIG_CAN_PASS_STRUCTS)","FAR char","struct in_addr"
"inet_ntop","arpa/inet.h","","FAR const char","int","FAR const void *","FAR char *","socklen_t"
"inet_pton","arpa/inet.h","","int","int","FAR const char *","FAR void *"
"labs","stdlib.h","","long int","long int"
"lib_dumpbuffer","debug.h","","void","FAR const char *","FAR const uint8_t *","unsigned int"
"lib_lowprintf","debug.h","","int","FAR const char *","..."
"lib_rawprintf","debug.h","","int","FAR const char *","..."
"llabs","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long int","long long int"
"lldbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..."
"llvdbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..."
"match","","","int","const char *","const char *"
"memccpy","string.h","","FAR void","FAR void *","FAR const void *","int c","size_t"
"memchr","string.h","","FAR void","FAR const void *","int c","size_t"
"memcmp","string.h","","int","FAR const void *","FAR const void *","size_t"
"memcpy","string.h","","FAR void","FAR void *","FAR const void *","size_t"
"memmove","string.h","","FAR void","FAR void *","FAR const void *","size_t"
"memset","string.h","","FAR void","FAR void *","int c","size_t"
"mktime","time.h","","time_t","const struct tm *"
"mq_getattr","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","int","mqd_t","struct mq_attr *"
"mq_setattr","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","int","mqd_t","const struct mq_attr *","struct mq_attr *"
"ntohl","arpa/inet.h","","uint32_t","uint32_t"
"ntohs","arpa/inet.h","","uint16_t","uint16_t"
"perror","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","void","FAR const char *"
"printf","stdio.h","","int","const char *","..."
"pthread_attr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *"
"pthread_attr_getinheritsched","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR const pthread_attr_t *","FAR int *"
"pthread_attr_getschedparam","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR struct sched_param *"
"pthread_attr_getschedpolicy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int *"
"pthread_attr_getstacksize","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR long *"
"pthread_attr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *"
"pthread_attr_setinheritsched","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int"
"pthread_attr_setschedparam","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","FAR const struct sched_param *"
"pthread_attr_setschedpolicy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","int"
"pthread_attr_setstacksize","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_attr_t *","long"
"pthread_barrierattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *"
"pthread_barrierattr_getpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR const pthread_barrierattr_t *","FAR int *"
"pthread_barrierattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *"
"pthread_barrierattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrierattr_t *","int"
"pthread_condattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *"
"pthread_condattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_condattr_t *"
"pthread_mutexattr_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *"
"pthread_mutexattr_getpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","FAR int *"
"pthread_mutexattr_gettype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_MUTEX_TYPES)","int","const pthread_mutexattr_t *","int *"
"pthread_mutexattr_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *"
"pthread_mutexattr_setpshared","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutexattr_t *","int "
"pthread_mutexattr_settype","pthread.h","!defined(CONFIG_DISABLE_PTHREAD) && defined(CONFIG_MUTEX_TYPES)","int","pthread_mutexattr_t *","int"
"puts","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *"
"qsort","stdlib.h","","void","void *","size_t","size_t","int(*)(const void *","const void *)"
"rand","stdlib.h","","int"
"readdir_r","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","int","FAR DIR *","FAR struct dirent *","FAR struct dirent **"
"rint","","","double_t","double_t"
"sched_get_priority_max","sched.h","","int","int"
"sched_get_priority_min","sched.h","","int","int"
"sem_getvalue","semaphore.h","","int","FAR sem_t *","FAR int *"
"sem_init","semaphore.h","","int","FAR sem_t *","int","unsigned int"
"sigaddset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *","int"
"sigdelset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *","int"
"sigemptyset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *"
"sigfillset","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t *"
"sigismember","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR const sigset_t *","int"
"snprintf","stdio.h","","int","FAR char *","size_t","const char *","..."
"sprintf","stdio.h","","int","FAR char *","const char *","..."
"sq_addafter","queue.h","","void","FAR sq_entry_t *","FAR sq_entry_t *","FAR sq_queue_t *"
"sq_addfirst","queue.h","","void","FAR sq_entry_t *","sq_queue_t *"
"sq_addlast","queue.h","","void","FAR sq_entry_t *","sq_queue_t *"
"sq_rem","queue.h","","void","FAR sq_entry_t *","sq_queue_t *"
"sq_remafter","queue.h","","FAR sq_entry_t","FAR sq_entry_t *","sq_queue_t *"
"sq_remfirst","queue.h","","FAR sq_entry_t","sq_queue_t *"
"sq_remlast","queue.h","","FAR sq_entry_t","sq_queue_t *"
"srand","stdlib.h","","void","unsigned int"
"sscanf","stdio.h","","int","const char *","const char *","..."
"strcasecmp","string.h","","int","FAR const char *","FAR const char *"
"strcasestr","string.h","","FAR char","FAR const char *","FAR const char *"
"strcat","string.h","","FAR char","FAR char *","FAR const char *"
"strchr","string.h","","FAR char","FAR const char *","int"
"strcmp","string.h","","int","FAR const char *","FAR const char *"
"strcpy","string.h","","FAR char","char *","FAR const char *"
"strcspn","string.h","","size_t","FAR const char *","FAR const char *"
"strdup","string.h","","FAR char","FAR const char *"
"strerror","string.h","","FAR const char","int"
"strftime","time.h","","size_t","char *","size_t","const char *","const struct tm *"
"strlen","string.h","","size_t","FAR const char *"
"strncasecmp","string.h","","int","FAR const char *","FAR const char *","size_t"
"strncat","string.h","","FAR char","FAR char *","FAR const char *","size_t"
"strncmp","string.h","","int","FAR const char *","FAR const char *","size_t"
"strncpy","string.h","","FAR char","char *","FAR const char *","size_t"
"strndup","string.h","","FAR char","FAR const char *","size_t"
"strnlen","string.h","","size_t","FAR const char *","size_t"
"strpbrk","string.h","","FAR char","FAR const char *","FAR const char *"
"strrchr","string.h","","FAR char","FAR const char *","int"
"strspn","string.h","","size_t","FAR const char *","FAR const char *"
"strstr","string.h","","FAR char","FAR const char *","FAR const char *"
"strtod","stdlib.h","","double_t","const char *str","char **endptr"
"strtok","string.h","","FAR char","FAR char *","FAR const char *"
"strtok_r","string.h","","FAR char","FAR char *","FAR const char *","FAR char **"
"strtol","string.h","","long","const char *","char **","int"
"strtoll","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long","const char *nptr","char **endptr","int base"
"strtoul","stdlib.h","","unsigned long","const char *","char **","int"
"strtoull","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","unsigned long long","const char *","char **","int"
"tcflush","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int"
"tcgetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","FAR struct termios *"
"tcsetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int","FAR const struct termios *"
"telldir","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","off_t","FAR DIR *"
"time","time.h","","time_t","time_t *"
"ub16divub16","fixedmath.h","","ub16_t","ub16_t","ub16_t"
"ub16mulub16","fixedmath.h","","ub16_t","ub16_t","ub16_t"
"ub16sqr","fixedmath.h","","ub16_t","ub16_t"
"ungetc","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","int","FAR FILE *"
"vdbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_VERBOSE)","int","const char *","..."
"vfprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR FILE *","const char *","va_list"
"vprintf","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","int","FAR const char *","va_list"
"vsnprintf","stdio.h","","int","FAR char *","size_t","const char *","va_list"
"vsprintf","stdio.h","","int","FAR char *","const char *","va_list"
"vsscanf","stdio.h","","int","char *","const char *","va_list"
Can't render this file because it has a wrong number of fields in line 2.

View File

@ -1,8 +1,8 @@
/****************************************************************************
* lib/libgen/lib_basename.c
*
* Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Copyright (C) 2007, 2009, 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -78,7 +78,7 @@ static char g_retchar[2];
*
****************************************************************************/
char *basename(char *path)
FAR char *basename(FAR char *path)
{
char *p;
int len;

View File

@ -1,8 +1,8 @@
/****************************************************************************
* lib/libgen/lib_dirname.c
*
* Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Copyright (C) 2007, 2009, 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -78,7 +78,7 @@ static char g_retchar[2];
*
****************************************************************************/
char *dirname(char *path)
FAR char *dirname(FAR char *path)
{
char *p;
int len;

View File

@ -2,7 +2,7 @@
* lib/math/lib_b16atan2.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/math/lib_b16cos.c
*
* Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/math/lib_b16sin.c
*
* Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/math/lib_fixedmath.c
*
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -165,7 +165,7 @@ ub16_t ub16mulub16(ub16_t m1, ub16_t m2)
}
/****************************************************************************
* Name: b16divb16
* Name: b16sqr
**************************************************************************/
b16_t b16sqr(b16_t a)

View File

@ -2,7 +2,7 @@
* lib/math/lib_rint.c
*
* Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/net/lib_etherntoa.c
*
* Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -58,7 +58,7 @@
*
****************************************************************************/
char *ether_ntoa(const struct ether_addr *addr)
FAR char *ether_ntoa(FAR const struct ether_addr *addr)
{
static char buffer[20];
sprintf(buffer, "%02x:%02x:%02x:%02x:%02x:%02x",

View File

@ -2,7 +2,7 @@
* lib/net/lib_ntohl.c
*
* Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/net/lib_htons.c
*
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_attrdestroy.c
*
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_attrgetinheritsched.c
*
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_attrgetschedparam.c
*
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_attrgetschedpolicy.c
*
* Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_attrgetstacksize.c
*
* Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_attrinit.c
*
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_attrsetinheritsched.c
*
* Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_attrsetschedparam.c
*
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_attrsetschedpolicy.c
*
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_attrsetstacksize.c
*
* Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_barrierattrdestroy.c
*
* Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_barrierattrgetpshared.c
*
* Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_barrierattrinit.c
*
* Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_barrierattrsetpshared.c
*
* Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_condattrdestroy.c
*
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_condattrinit.c
*
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_mutexattrdestroy.c
*
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_mutexattrgetpshared.c
*
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_mutexattrgettype.c
*
* Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_mutexattrinit.c
*
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_mutexattrsetpshared.c
*
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/pthread/pthread_mutexattrsettype.c
*
* Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/sched/sched_getprioritymax.c
*
* Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/sched/sched_getprioritymin.c
*
* Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* lib/semaphore/sem_getvalue.c
*
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions

Some files were not shown because too many files have changed in this diff Show More