move posix, nuttx, qurt components into platforms

This commit is contained in:
Daniel Agar
2018-01-15 15:34:18 -05:00
committed by Lorenz Meier
parent a644ed90dd
commit 2ff81393bc
115 changed files with 251 additions and 306 deletions

View File

@@ -1,5 +1,7 @@
include (common/px4_upload)
add_subdirectory(src)
include_directories(${CMAKE_CURRENT_BINARY_DIR})
get_property(module_libraries GLOBAL PROPERTY PX4_LIBRARIES)
@@ -10,7 +12,7 @@ px4_posix_generate_builtin_commands(
# Define build target
set(APP_NAME px4)
set(MAIN_SRC ${PX4_SOURCE_DIR}/src/platforms/posix/main.cpp)
set(MAIN_SRC src/main.cpp)
set(UPLOAD_NAME upload)
if ("${BOARD}" STREQUAL "eagle" OR ("${BOARD}" STREQUAL "excelsior"))

View File

@@ -165,9 +165,7 @@ function(px4_os_add_flags)
DEFINITIONS ${DEFINITIONS})
set(added_include_dirs
src/modules/systemlib
src/platforms/posix/include
mavlink/include/mavlink
platforms/posix/include
)
# This block sets added_definitions and added_cxx_flags.

View File

@@ -32,7 +32,7 @@ endfunction()
# sitl run targets
#
set(SITL_RUNNER_MAIN_CPP ${PX4_SOURCE_DIR}/src/platforms/posix/main.cpp)
set(SITL_RUNNER_MAIN_CPP src/main.cpp)
px4_add_sitl_app(APP_NAME px4
UPLOAD_NAME upload
MAIN_SRC ${SITL_RUNNER_MAIN_CPP}
@@ -111,7 +111,7 @@ foreach(viewer ${viewers})
set(SITL_RUNNER_MODEL_FILE ${PX4_SOURCE_DIR}/${config_sitl_rcS_dir}/${model})
set(SITL_RUNNER_WORKING_DIRECTORY ${SITL_WORKING_DIR})
configure_file(${PX4_SOURCE_DIR}/src/platforms/posix/sitl_runner_main.cpp.in sitl_runner_main_${model}.cpp @ONLY)
configure_file(src/sitl_runner_main.cpp.in sitl_runner_main_${model}.cpp @ONLY)
px4_add_sitl_app(APP_NAME px4_${model}
UPLOAD_NAME upload_${model}

View File

@@ -0,0 +1,83 @@
/****************************************************************************
* include/crc.h
*
* Copyright (C) 2010 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __INCLUDE_CRC32_H
#define __INCLUDE_CRC32_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <sys/types.h>
#include <stdint.h>
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C" {
#else
#define EXTERN extern
#endif
/****************************************************************************
* Name: crc32part
*
* Description:
* Continue CRC calculation on a part of the buffer.
*
****************************************************************************/
EXTERN uint32_t crc32part(const uint8_t *src, size_t len,
uint32_t crc32val);
/****************************************************************************
* Name: crc32
*
* Description:
* Return a 32-bit CRC of the contents of the 'src' buffer, length 'len'
*
****************************************************************************/
EXTERN uint32_t crc32(const uint8_t *src, size_t len);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* __INCLUDE_CRC32_H */

View File

@@ -0,0 +1,63 @@
/****************************************************************************
*
* Copyright (C) 2015 Mark Charlebois. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_log.h>
#include <px4_posix.h>
#include <semaphore.h>
#include <px4_workqueue.h>
#pragma once
__BEGIN_DECLS
extern px4_sem_t _hrt_work_lock;
extern struct wqueue_s g_hrt_work;
void hrt_work_queue_init(void);
int hrt_work_queue(struct work_s *work, worker_t worker, void *arg, uint32_t usdelay);
void hrt_work_cancel(struct work_s *work);
static inline void hrt_work_lock(void);
static inline void hrt_work_lock()
{
px4_sem_wait(&_hrt_work_lock);
}
static inline void hrt_work_unlock(void);
static inline void hrt_work_unlock()
{
px4_sem_post(&_hrt_work_lock);
}
__END_DECLS

View File

@@ -0,0 +1,3 @@
#ifdef __PX4_QURT
#include <dspal_types.h>
#endif

View File

@@ -0,0 +1,134 @@
/************************************************************************
* include/queue.h
*
* Copyright (C) 2007-2009 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************/
#ifndef __INCLUDE_QUEUE_H
#define __INCLUDE_QUEUE_H
/************************************************************************
* Included Files
************************************************************************/
#include <sys/types.h>
#ifdef __cplusplus
#include <cstddef> // NULL
#else
#include <stddef.h> // NULL
#endif
/************************************************************************
* Pre-processor Definitions
************************************************************************/
#define sq_init(q) do { (q)->head = NULL; (q)->tail = NULL; } while (0)
#define dq_init(q) do { (q)->head = NULL; (q)->tail = NULL; } while (0)
#define sq_next(p) ((p)->flink)
#define dq_next(p) ((p)->flink)
#define dq_prev(p) ((p)->blink)
#define sq_empty(q) ((q)->head == NULL)
#define dq_empty(q) ((q)->head == NULL)
#define sq_peek(q) ((q)->head)
#define dq_peek(q) ((q)->head)
// Required for Linux
#define FAR
/************************************************************************
* Global Type Declarations
************************************************************************/
struct sq_entry_s {
FAR struct sq_entry_s *flink;
};
typedef struct sq_entry_s sq_entry_t;
struct dq_entry_s {
FAR struct dq_entry_s *flink;
FAR struct dq_entry_s *blink;
};
typedef struct dq_entry_s dq_entry_t;
struct sq_queue_s {
FAR sq_entry_t *head;
FAR sq_entry_t *tail;
};
typedef struct sq_queue_s sq_queue_t;
struct dq_queue_s {
FAR dq_entry_t *head;
FAR dq_entry_t *tail;
};
typedef struct dq_queue_s dq_queue_t;
/************************************************************************
* Global Function Prototypes
************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C" {
#else
#define EXTERN extern
#endif
EXTERN void sq_addfirst(FAR sq_entry_t *node, sq_queue_t *queue);
EXTERN void dq_addfirst(FAR dq_entry_t *node, dq_queue_t *queue);
EXTERN void sq_addlast(FAR sq_entry_t *node, sq_queue_t *queue);
EXTERN void dq_addlast(FAR dq_entry_t *node, dq_queue_t *queue);
EXTERN void sq_addafter(FAR sq_entry_t *prev, FAR sq_entry_t *node,
sq_queue_t *queue);
EXTERN void dq_addafter(FAR dq_entry_t *prev, FAR dq_entry_t *node,
dq_queue_t *queue);
EXTERN void dq_addbefore(FAR dq_entry_t *next, FAR dq_entry_t *node,
dq_queue_t *queue);
EXTERN FAR sq_entry_t *sq_remafter(FAR sq_entry_t *node, sq_queue_t *queue);
EXTERN void sq_rem(FAR sq_entry_t *node, sq_queue_t *queue);
EXTERN void dq_rem(FAR dq_entry_t *node, dq_queue_t *queue);
EXTERN FAR sq_entry_t *sq_remlast(sq_queue_t *queue);
EXTERN FAR dq_entry_t *dq_remlast(dq_queue_t *queue);
EXTERN FAR sq_entry_t *sq_remfirst(sq_queue_t *queue);
EXTERN FAR dq_entry_t *dq_remfirst(dq_queue_t *queue);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* __INCLUDE_QUEUE_H_ */

View File

@@ -0,0 +1,74 @@
/****************************************************************************
*
* Copyright (c) 2017 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file system_config.h
*
* Definitions used by all SITL and Linux targets
*/
#pragma once
#define ADC_BATTERY_VOLTAGE_CHANNEL 10
#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
#define ADCSIM0_DEVICE_PATH "/dev/adc0"
#define SIM_FORMATED_UUID "000000010000000200000003"
#define PX4_CPU_UUID_BYTE_LENGTH 12
#define PX4_CPU_UUID_WORD32_LENGTH 3
#define PX4_CPU_MFGUID_BYTE_LENGTH PX4_CPU_UUID_BYTE_LENGTH
#define PX4_CPU_UUID_WORD32_UNIQUE_H 2 /* Most significant digits change the least */
#define PX4_CPU_UUID_WORD32_UNIQUE_M 1 /* Middle significant digits */
#define PX4_CPU_UUID_WORD32_UNIQUE_L 0 /* Least significant digits change the most */
#define PX4_CPU_UUID_WORD32_FORMAT_SIZE (PX4_CPU_UUID_WORD32_LENGTH-1+(2*PX4_CPU_UUID_BYTE_LENGTH)+1)
#define PX4_CPU_MFGUID_FORMAT_SIZE ((2*PX4_CPU_MFGUID_BYTE_LENGTH)+1)
#define BOARD_OVERRIDE_CPU_VERSION (-1)
#define board_mcu_version(rev, revstr, errata) BOARD_OVERRIDE_CPU_VERSION
#define board_get_uuid32(id) do {for(int _idi=0; _idi < PX4_CPU_UUID_WORD32_LENGTH; _idi++) {id[_idi] = _idi;}} while(0)
#define board_get_uuid32_formated(format_buffer, size, format, seperator) do { strcpy(format_buffer, SIM_FORMATED_UUID); } while(0)
#define BOARD_HAS_NO_UUID
#define CONFIG_NFILE_STREAMS 1
#define CONFIG_SCHED_WORKQUEUE 1
#define CONFIG_SCHED_HPWORK 1
#define CONFIG_SCHED_LPWORK 1
/** time in ms between checks for work in work queues **/
#define CONFIG_SCHED_WORKPERIOD 50000
#define CONFIG_SCHED_INSTRUMENTATION 1
#define CONFIG_MAX_TASKS 32

View File

@@ -0,0 +1,34 @@
############################################################################
#
# Copyright (c) 2017 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
add_subdirectory(px4_layer)

View File

@@ -0,0 +1,670 @@
/****************************************************************************
*
* Copyright (C) 2015 Mark Charlebois. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file main.cpp
* Basic shell to execute builtin "apps"
*
* @author Mark Charlebois <charlebm@gmail.com>
* @author Roman Bapst <bapstroman@gmail.com>
*/
#include <iostream>
#include <fstream>
#include <string>
#include <sstream>
#include <vector>
#include <signal.h>
#include <unistd.h>
#include <stdio.h>
#include "apps.h"
#include "px4_middleware.h"
#include "px4_posix.h"
#include "px4_log.h"
#include "DriverFramework.hpp"
#include <termios.h>
#include <sys/stat.h>
namespace px4
{
void init_once();
}
using namespace std;
typedef int (*px4_main_t)(int argc, char *argv[]);
#define CMD_BUFF_SIZE 100
#ifdef PATH_MAX
const unsigned path_max_len = PATH_MAX;
#else
const unsigned path_max_len = 1024;
#endif
static volatile bool _ExitFlag = false;
static struct termios orig_term;
extern "C" {
void _SigIntHandler(int sig_num);
void _SigIntHandler(int sig_num)
{
cout.flush();
cout << endl << "Exiting..." << endl;
cout.flush();
_ExitFlag = true;
}
void _SigFpeHandler(int sig_num);
void _SigFpeHandler(int sig_num)
{
cout.flush();
cout << endl << "floating point exception" << endl;
PX4_BACKTRACE();
cout.flush();
}
}
static inline bool fileExists(const string &name)
{
struct stat buffer;
return (stat(name.c_str(), &buffer) == 0);
}
static inline bool dirExists(const string &path)
{
struct stat info;
if (stat(path.c_str(), &info) != 0) {
return false;
} else if (info.st_mode & S_IFDIR) {
return true;
} else {
return false;
}
}
static inline void touch(const string &name)
{
fstream fs;
fs.open(name, ios::out);
fs.close();
}
static int mkpath(const char *path, mode_t mode);
static int do_mkdir(const char *path, mode_t mode)
{
struct stat st;
int status = 0;
if (stat(path, &st) != 0) {
/* Directory does not exist. EEXIST for race condition */
if (mkdir(path, mode) != 0 && errno != EEXIST) {
status = -1;
}
} else if (!S_ISDIR(st.st_mode)) {
errno = ENOTDIR;
status = -1;
}
return (status);
}
/**
** mkpath - ensure all directories in path exist
** Algorithm takes the pessimistic view and works top-down to ensure
** each directory in path exists, rather than optimistically creating
** the last element and working backwards.
*/
static int mkpath(const char *path, mode_t mode)
{
char *pp;
char *sp;
int status;
char *copypath = strdup(path);
status = 0;
pp = copypath;
while (status == 0 && (sp = strchr(pp, '/')) != nullptr) {
if (sp != pp) {
/* Neither root nor double slash in path */
*sp = '\0';
status = do_mkdir(copypath, mode);
*sp = '/';
}
pp = sp + 1;
}
if (status == 0) {
status = do_mkdir(path, mode);
}
free(copypath);
return (status);
}
static string pwd()
{
char temp[path_max_len];
return (getcwd(temp, path_max_len) ? string(temp) : string(""));
}
static void print_prompt()
{
cout.flush();
cout << "pxh> ";
cout.flush();
}
static void run_cmd(const vector<string> &appargs, bool exit_on_fail, bool silently_fail = false)
{
static apps_map_type apps;
static bool initialized = false;
if (!initialized) {
init_app_map(apps);
initialized = true;
}
// command is appargs[0]
string command = appargs[0];
if (apps.find(command) != apps.end()) {
const char *arg[appargs.size() + 2];
unsigned int i = 0;
while (i < appargs.size() && appargs[i] != "") {
arg[i] = (char *)appargs[i].c_str();
++i;
}
arg[i] = (char *)nullptr;
int retval = apps[command](i, (char **)arg);
if (retval) {
cout << "Command '" << command << "' failed, returned " << retval << endl;
if (exit_on_fail && retval) {
exit(retval);
}
}
} else if (command == "help") {
list_builtins(apps);
} else if (command.length() == 0 || command[0] == '#') {
// Do nothing
} else if (!silently_fail) {
cout << "Invalid command: " << command << "\ntype 'help' for a list of commands" << endl;
}
}
static void usage()
{
cout << "./px4 [-d] [data_directory] startup_config [-h]" << endl;
cout << " -d - Optional flag to run the app in daemon mode and does not listen for user input." <<
endl;
cout << " This is needed if px4 is intended to be run as a upstart job on linux" << endl;
cout << "<data_directory> - directory where ROMFS and posix-configs are located (if not given, CWD is used)" << endl;
cout << "<startup_config> - config file for starting/stopping px4 modules" << endl;
cout << " -h - help/usage information" << endl;
}
static void process_line(string &line, bool exit_on_fail)
{
vector<string> appargs(20);
stringstream(line) >> appargs[0] >> appargs[1] >> appargs[2] >> appargs[3] >> appargs[4] >> appargs[5] >> appargs[6] >>
appargs[7] >> appargs[8] >> appargs[9] >> appargs[10] >> appargs[11] >> appargs[12] >> appargs[13] >>
appargs[14] >> appargs[15] >> appargs[16] >> appargs[17] >> appargs[18] >> appargs[19];
run_cmd(appargs, exit_on_fail);
}
static void restore_term()
{
cout << "Restoring terminal\n";
tcsetattr(0, TCSANOW, &orig_term);
}
bool px4_exit_requested(void)
{
return _ExitFlag;
}
static void set_cpu_scaling()
{
#if defined(__PX4_POSIX_EAGLE) || defined(__PX4_POSIX_EXCELSIOR)
// On Snapdragon we miss updates in sdlog2 unless all 4 CPUs are run
// at the maximum frequency all the time.
// Interestingely, cpu0 and cpu3 set the scaling for all 4 CPUs on Snapdragon.
system("echo performance > /sys/devices/system/cpu/cpu0/cpufreq/scaling_governor");
system("echo performance > /sys/devices/system/cpu/cpu3/cpufreq/scaling_governor");
// Alternatively we could also raise the minimum frequency to save some power,
// unfortunately this still lead to some drops.
//system("echo 1190400 > /sys/devices/system/cpu/cpu0/cpufreq/scaling_min_freq");
#endif
}
#ifdef __PX4_SITL_MAIN_OVERRIDE
int SITL_MAIN(int argc, char **argv);
int SITL_MAIN(int argc, char **argv)
#else
int main(int argc, char **argv)
#endif
{
bool daemon_mode = false;
bool chroot_on = false;
tcgetattr(0, &orig_term);
atexit(restore_term);
struct sigaction sig_int;
memset(&sig_int, 0, sizeof(struct sigaction));
sig_int.sa_handler = _SigIntHandler;
sig_int.sa_flags = 0;// not SA_RESTART!;
struct sigaction sig_fpe;
memset(&sig_fpe, 0, sizeof(struct sigaction));
sig_fpe.sa_handler = _SigFpeHandler;
sig_fpe.sa_flags = 0;// not SA_RESTART!;
sigaction(SIGINT, &sig_int, nullptr);
//sigaction(SIGTERM, &sig_int, NULL);
sigaction(SIGFPE, &sig_fpe, nullptr);
set_cpu_scaling();
int index = 1;
string commands_file;
int positional_arg_count = 0;
string data_path;
string node_name;
// parse arguments
while (index < argc) {
//cout << "arg: " << index << " : " << argv[index] << endl;
if (argv[index][0] == '-') {
// the arg starts with -
if (strncmp(argv[index], "-d", 2) == 0) {
daemon_mode = true;
} else if (strncmp(argv[index], "-h", 2) == 0) {
usage();
return 0;
} else if (strncmp(argv[index], "-c", 2) == 0) {
chroot_on = true;
} else {
PX4_ERR("Unknown/unhandled parameter: %s", argv[index]);
return 1;
}
} else if (!strncmp(argv[index], "__", 2)) {
//cout << "ros argument" << endl;
// ros arguments
if (!strncmp(argv[index], "__name:=", 8)) {
string name_arg = argv[index];
node_name = name_arg.substr(8);
cout << "node name: " << node_name << endl;
}
} else {
//cout << "positional argument" << endl;
positional_arg_count += 1;
if (positional_arg_count == 1) {
data_path = argv[index];
} else if (positional_arg_count == 2) {
commands_file = argv[index];
}
}
++index;
}
if (positional_arg_count != 2 && positional_arg_count != 1) {
PX4_ERR("Error expected 1 or 2 position arguments, got %d", positional_arg_count);
usage();
return -1;
}
bool symlinks_needed = true;
if (positional_arg_count == 1) { //data path is optional
commands_file = data_path;
symlinks_needed = false;
} else {
cout << "data path: " << data_path << endl;
}
cout << "commands file: " << commands_file << endl;
if (commands_file.empty()) {
PX4_ERR("Error commands file not specified");
return -1;
}
if (!fileExists(commands_file)) {
PX4_ERR("Error opening commands file, does not exist: %s", commands_file.c_str());
return -1;
}
// create sym-links
if (symlinks_needed) {
vector<string> path_sym_links;
path_sym_links.push_back("ROMFS");
path_sym_links.push_back("posix-configs");
path_sym_links.push_back("test_data");
for (unsigned i = 0; i < path_sym_links.size(); i++) {
string path_sym_link = path_sym_links[i];
//cout << "path sym link: " << path_sym_link << endl;
string src_path = data_path + "/" + path_sym_link;
string dest_path = pwd() + "/" + path_sym_link;
PX4_DEBUG("Creating symlink %s -> %s", src_path.c_str(), dest_path.c_str());
if (dirExists(path_sym_link)) { continue; }
// create sym-links
int ret = symlink(src_path.c_str(), dest_path.c_str());
if (ret != 0) {
PX4_ERR("Error creating symlink %s -> %s",
src_path.c_str(), dest_path.c_str());
return ret;
} else {
PX4_DEBUG("Successfully created symlink %s -> %s",
src_path.c_str(), dest_path.c_str());
}
}
}
// setup rootfs
const string eeprom_path = "./rootfs/eeprom/";
const string microsd_path = "./rootfs/fs/microsd/";
if (!fileExists(eeprom_path + "parameters")) {
cout << "creating new parameters file" << endl;
mkpath(eeprom_path.c_str(), S_IRUSR | S_IWUSR | S_IXUSR);
touch(eeprom_path + "parameters");
}
if (!fileExists(microsd_path + "dataman")) {
cout << "creating new dataman file" << endl;
mkpath(microsd_path.c_str(), S_IRUSR | S_IWUSR | S_IXUSR);
touch(microsd_path + "dataman");
}
// initialize
DriverFramework::Framework::initialize();
px4::init_once();
px4::init(argc, argv, "px4");
// if commandfile is present, process the commands from the file
if (!commands_file.empty()) {
ifstream infile(commands_file.c_str());
if (infile.is_open()) {
for (string line; getline(infile, line, '\n');) {
if (px4_exit_requested()) {
break;
}
// TODO: this should be true but for that we have to check all startup files
process_line(line, false);
}
} else {
PX4_ERR("Error opening commands file: %s", commands_file.c_str());
}
}
if (chroot_on) {
// Lock this application in the current working dir
// this is not an attempt to secure the environment,
// rather, to replicate a deployed file system.
char pwd_path[path_max_len];
const char *folderpath = "/rootfs/";
if (nullptr == getcwd(pwd_path, sizeof(pwd_path))) {
PX4_ERR("Failed acquiring working dir, abort.");
exit(1);
}
if (nullptr == strcat(pwd_path, folderpath)) {
PX4_ERR("Failed completing path, abort.");
exit(1);
}
if (chroot(pwd_path)) {
PX4_ERR("Failed chrooting application, path: %s, error: %s.", pwd_path, strerror(errno));
exit(1);
}
if (chdir("/")) {
PX4_ERR("Failed changing to root dir, path: %s, error: %s.", pwd_path, strerror(errno));
exit(1);
}
}
if (!daemon_mode) {
string mystr;
string string_buffer[CMD_BUFF_SIZE];
int buf_ptr_write = 0;
int buf_ptr_read = 0;
uint8_t cursor_position =
0; // position of the cursor from right to left (0: all the way to the right, mystr.length: all the way to the left)
print_prompt();
// change input mode so that we can manage shell
struct termios term;
tcgetattr(0, &term);
term.c_lflag &= ~ICANON;
term.c_lflag &= ~ECHO;
tcsetattr(0, TCSANOW, &term);
setbuf(stdin, nullptr);
while (!_ExitFlag) {
char c = getchar();
string add_string; // string to add at current cursor position
bool update_prompt = true;
switch (c) {
case 127: // backslash
if (mystr.length() - cursor_position > 0) {
mystr.erase(mystr.length() - cursor_position - 1, 1);
}
break;
case '\n': // user hit enter
if (buf_ptr_write == CMD_BUFF_SIZE) {
buf_ptr_write = 0;
}
if (buf_ptr_write > 0) {
if (!mystr.empty() && mystr != string_buffer[buf_ptr_write - 1]) {
string_buffer[buf_ptr_write] = mystr;
buf_ptr_write++;
}
} else {
if (!mystr.empty() && mystr != string_buffer[CMD_BUFF_SIZE - 1]) {
string_buffer[buf_ptr_write] = mystr;
buf_ptr_write++;
}
}
cout << endl;
process_line(mystr, false);
// reset string and cursor position
mystr = "";
cursor_position = 0;
buf_ptr_read = buf_ptr_write;
print_prompt();
break;
case '\033': { // arrow keys
c = getchar(); // skip first one, does not have the info
c = getchar();
if (c == 'A') { // arrow up
buf_ptr_read--;
} else if (c == 'B') { // arrow down
if (buf_ptr_read < buf_ptr_write) {
buf_ptr_read++;
}
} else if (c == 'C') { // arrow right
if (cursor_position > 0) {
printf("\033[1C");
cursor_position--;
}
break;
} else if (c == 'D') { // arrow left
if (cursor_position < mystr.length()) {
printf("\033[1D");
cursor_position++;
}
break;
} else if (c == 'H') { // Home (go to the beginning of the command)
cursor_position = mystr.length();
break;
} else if (c == '1') { // Home (go to the beginning of the command, Editing key)
(void)getchar(); // swallow '~'
cursor_position = mystr.length();
break;
} else if (c == 'F') { // End (go to the end of the command)
cursor_position = 0;
break;
} else if (c == '4') { // End (go to the end of the command, Editing key)
(void)getchar(); // swallow '~'
cursor_position = 0;
break;
}
if (buf_ptr_read < 0) {
buf_ptr_read = 0;
}
string saved_cmd = string_buffer[buf_ptr_read];
mystr = saved_cmd;
cursor_position = 0; // move cursor to end of line
break;
}
default: // any other input
if (c > 3) {
add_string += c;
} else {
update_prompt = false;
}
break;
}
if (update_prompt) {
// reprint prompt with mystr
mystr.insert(mystr.length() - cursor_position, add_string);
printf("%c[2K", 27);
cout << (char)13;
print_prompt();
cout << mystr;
// Move the cursor to its position
if (cursor_position > 0) {
printf("\033[%dD", cursor_position);
}
}
}
} else {
while (!_ExitFlag) {
usleep(100000);
}
}
// TODO: Always try to stop muorb for QURT because px4_task_is_running doesn't seem to work.
if (true) {
//if (px4_task_is_running("muorb")) {
// sending muorb stop is needed if it is running to exit cleanly
vector<string> muorb_stop_cmd = { "muorb", "stop" };
run_cmd(muorb_stop_cmd, !daemon_mode, true);
}
vector<string> shutdown_cmd = { "shutdown" };
run_cmd(shutdown_cmd, true);
DriverFramework::Framework::shutdown();
return OK;
}
/* vim: set noet fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */

View File

@@ -0,0 +1,61 @@
############################################################################
#
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
set(EXTRA_DEPENDS)
if("${CONFIG_SHMEM}" STREQUAL "1")
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${PX4_SOURCE_DIR}/cmake/cmake_hexagon")
include(hexagon_sdk)
include_directories(${HEXAGON_SDK_INCLUDES})
include_directories(${PX4_BINARY_DIR}/platforms/posix)
list(APPEND SHMEM_SRCS
shmem_posix.c
)
# TODO: This didn't seem to be tracked correctly from posix_eagle_release.cmake
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DCONFIG_SHMEM")
set(EXTRA_DEPENDS generate_px4muorb_stubs)
endif()
px4_add_module(
MODULE platforms__posix__px4_layer
COMPILE_FLAGS
SRCS
px4_posix_impl.cpp
px4_posix_tasks.cpp
px4_sem.cpp
lib_crc32.c
drv_hrt.c
${SHMEM_SRCS}
DEPENDS
platforms__common
${EXTRA_DEPENDS}
)

View File

@@ -0,0 +1,603 @@
/****************************************************************************
*
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file drv_hrt.c
*
* High-resolution timer with callouts and timekeeping.
*/
#include <px4_time.h>
#include <px4_posix.h>
#include <px4_defines.h>
#include <px4_workqueue.h>
#include <px4_tasks.h>
#include <drivers/drv_hrt.h>
#include <semaphore.h>
#include <time.h>
#include <string.h>
#include <inttypes.h>
#include <errno.h>
#include "hrt_work.h"
static struct sq_queue_s callout_queue;
/* latency histogram */
#define LATENCY_BUCKET_COUNT 8
__EXPORT const uint16_t latency_bucket_count = LATENCY_BUCKET_COUNT;
__EXPORT const uint16_t latency_buckets[LATENCY_BUCKET_COUNT] = { 1, 2, 5, 10, 20, 50, 100, 1000 };
__EXPORT uint32_t latency_counters[LATENCY_BUCKET_COUNT + 1];
static void hrt_call_reschedule(void);
// Intervals in usec
#define HRT_INTERVAL_MIN 50
#define HRT_INTERVAL_MAX 50000000
static px4_sem_t _hrt_lock;
static struct work_s _hrt_work;
#ifndef __PX4_QURT
static hrt_abstime px4_timestart = 0;
#else
static int32_t dsp_offset = 0;
#endif
static hrt_abstime _start_delay_time = 0;
static hrt_abstime _delay_interval = 0;
static hrt_abstime max_time = 0;
pthread_mutex_t _hrt_mutex = PTHREAD_MUTEX_INITIALIZER;
static void
hrt_call_invoke(void);
static hrt_abstime
_hrt_absolute_time_internal(void);
__EXPORT hrt_abstime hrt_reset(void);
static void hrt_lock(void)
{
px4_sem_wait(&_hrt_lock);
}
static void hrt_unlock(void)
{
px4_sem_post(&_hrt_lock);
}
#if defined(__PX4_APPLE_LEGACY)
#include <sys/time.h>
int px4_clock_gettime(clockid_t clk_id, struct timespec *tp)
{
struct timeval now;
int rv = gettimeofday(&now, NULL);
if (rv) {
return rv;
}
tp->tv_sec = now.tv_sec;
tp->tv_nsec = now.tv_usec * 1000;
return 0;
}
int px4_clock_settime(clockid_t clk_id, struct timespec *tp)
{
/* do nothing right now */
return 0;
}
#elif defined(__PX4_QURT)
#include "dspal_time.h"
int px4_clock_settime(clockid_t clk_id, struct timespec *tp)
{
/* do nothing right now */
return 0;
}
int px4_clock_gettime(clockid_t clk_id, struct timespec *tp)
{
return clock_gettime(clk_id, tp);
}
#endif
#ifndef __PX4_QURT
/*
* Get system time in us
*/
uint64_t hrt_system_time(void)
{
struct timespec ts;
px4_clock_gettime(CLOCK_MONOTONIC, &ts);
return ts_to_abstime(&ts);
}
#endif
/*
* Get absolute time.
*/
hrt_abstime _hrt_absolute_time_internal(void)
{
struct timespec ts;
#if defined(__PX4_QURT)
// Don't use the timestart on the DSP on Snapdragon because we manually
// set the px4_timestart using the hrt_set_absolute_time_offset().
px4_clock_gettime(CLOCK_MONOTONIC, &ts);
return ts_to_abstime(&ts) + dsp_offset;
#elif (defined(__PX4_POSIX_EAGLE) || defined(__PX4_POSIX_EXCELSIOR))
// Don't do any offseting on the Linux side on the Snapdragon.
px4_clock_gettime(CLOCK_MONOTONIC, &ts);
return ts_to_abstime(&ts);
#else
if (!px4_timestart) {
px4_clock_gettime(CLOCK_MONOTONIC, &ts);
px4_timestart = ts_to_abstime(&ts);
}
px4_clock_gettime(CLOCK_MONOTONIC, &ts);
return ts_to_abstime(&ts) - px4_timestart;
#endif
}
#ifdef __PX4_QURT
int hrt_set_absolute_time_offset(int32_t time_diff_us)
{
dsp_offset = time_diff_us;
return 0;
}
#endif
/*
* Get absolute time.
*/
hrt_abstime hrt_absolute_time(void)
{
pthread_mutex_lock(&_hrt_mutex);
hrt_abstime ret;
if (_start_delay_time > 0) {
ret = _start_delay_time;
} else {
ret = _hrt_absolute_time_internal();
}
ret -= _delay_interval;
if (ret < max_time) {
PX4_ERR("WARNING! TIME IS NEGATIVE! %d vs %d", (int)ret, (int)max_time);
ret = max_time;
}
max_time = ret;
pthread_mutex_unlock(&_hrt_mutex);
return ret;
}
__EXPORT hrt_abstime hrt_reset(void)
{
#ifndef __PX4_QURT
px4_timestart = 0;
#endif
max_time = 0;
return _hrt_absolute_time_internal();
}
/*
* Convert a timespec to absolute time.
*/
hrt_abstime ts_to_abstime(struct timespec *ts)
{
hrt_abstime result;
result = (hrt_abstime)(ts->tv_sec) * 1000000;
result += ts->tv_nsec / 1000;
return result;
}
/*
* Compute the delta between a timestamp taken in the past
* and now.
*
* This function is safe to use even if the timestamp is updated
* by an interrupt during execution.
*/
hrt_abstime hrt_elapsed_time(const volatile hrt_abstime *then)
{
hrt_abstime delta = hrt_absolute_time() - *then;
return delta;
}
/*
* Store the absolute time in an interrupt-safe fashion.
*
* This function ensures that the timestamp cannot be seen half-written by an interrupt handler.
*/
hrt_abstime hrt_store_absolute_time(volatile hrt_abstime *now)
{
hrt_abstime ts = hrt_absolute_time();
return ts;
}
/*
* If this returns true, the entry has been invoked and removed from the callout list,
* or it has never been entered.
*
* Always returns false for repeating callouts.
*/
bool hrt_called(struct hrt_call *entry)
{
return (entry->deadline == 0);
}
/*
* Remove the entry from the callout list.
*/
void hrt_cancel(struct hrt_call *entry)
{
hrt_lock();
sq_rem(&entry->link, &callout_queue);
entry->deadline = 0;
/* if this is a periodic call being removed by the callout, prevent it from
* being re-entered when the callout returns.
*/
entry->period = 0;
hrt_unlock();
// endif
}
/*
* initialise a hrt_call structure
*/
void hrt_call_init(struct hrt_call *entry)
{
memset(entry, 0, sizeof(*entry));
}
/*
* delay a hrt_call_every() periodic call by the given number of
* microseconds. This should be called from within the callout to
* cause the callout to be re-scheduled for a later time. The periodic
* callouts will then continue from that new base time at the
* previously specified period.
*/
void hrt_call_delay(struct hrt_call *entry, hrt_abstime delay)
{
entry->deadline = hrt_absolute_time() + delay;
}
/*
* Initialise the HRT.
*/
void hrt_init(void)
{
sq_init(&callout_queue);
int sem_ret = px4_sem_init(&_hrt_lock, 0, 1);
if (sem_ret) {
PX4_ERR("SEM INIT FAIL: %s", strerror(errno));
}
memset(&_hrt_work, 0, sizeof(_hrt_work));
}
void hrt_start_delay()
{
pthread_mutex_lock(&_hrt_mutex);
_start_delay_time = _hrt_absolute_time_internal();
pthread_mutex_unlock(&_hrt_mutex);
}
void hrt_stop_delay_delta(hrt_abstime delta)
{
pthread_mutex_lock(&_hrt_mutex);
uint64_t delta_measured = _hrt_absolute_time_internal() - _start_delay_time;
if (delta_measured < delta) {
delta = delta_measured;
}
_delay_interval += delta;
_start_delay_time = 0;
pthread_mutex_unlock(&_hrt_mutex);
}
void hrt_stop_delay()
{
pthread_mutex_lock(&_hrt_mutex);
uint64_t delta = _hrt_absolute_time_internal() - _start_delay_time;
_delay_interval += delta;
_start_delay_time = 0;
pthread_mutex_unlock(&_hrt_mutex);
}
static void
hrt_call_enter(struct hrt_call *entry)
{
struct hrt_call *call, *next;
//PX4_INFO("hrt_call_enter");
call = (struct hrt_call *)sq_peek(&callout_queue);
if ((call == NULL) || (entry->deadline < call->deadline)) {
sq_addfirst(&entry->link, &callout_queue);
//if (call != NULL) PX4_INFO("call enter at head, reschedule (%lu %lu)", entry->deadline, call->deadline);
/* we changed the next deadline, reschedule the timer event */
hrt_call_reschedule();
} else {
do {
next = (struct hrt_call *)sq_next(&call->link);
if ((next == NULL) || (entry->deadline < next->deadline)) {
//lldbg("call enter after head\n");
sq_addafter(&call->link, &entry->link, &callout_queue);
break;
}
} while ((call = next) != NULL);
}
//PX4_INFO("scheduled");
}
/**
* Timer interrupt handler
*
* This routine simulates a timer interrupt handler
*/
static void
hrt_tim_isr(void *p)
{
//PX4_INFO("hrt_tim_isr");
/* run any callouts that have met their deadline */
hrt_call_invoke();
hrt_lock();
/* and schedule the next interrupt */
hrt_call_reschedule();
hrt_unlock();
}
/**
* Reschedule the next timer interrupt.
*
* This routine must be called with interrupts disabled.
*/
static void
hrt_call_reschedule()
{
hrt_abstime now = hrt_absolute_time();
hrt_abstime delay = HRT_INTERVAL_MAX;
struct hrt_call *next = (struct hrt_call *)sq_peek(&callout_queue);
hrt_abstime deadline = now + HRT_INTERVAL_MAX;
//PX4_INFO("hrt_call_reschedule");
/*
* Determine what the next deadline will be.
*
* Note that we ensure that this will be within the counter
* period, so that when we truncate all but the low 16 bits
* the next time the compare matches it will be the deadline
* we want.
*
* It is important for accurate timekeeping that the compare
* interrupt fires sufficiently often that the base_time update in
* hrt_absolute_time runs at least once per timer period.
*/
if (next != NULL) {
//lldbg("entry in queue\n");
if (next->deadline <= (now + HRT_INTERVAL_MIN)) {
//lldbg("pre-expired\n");
/* set a minimal deadline so that we call ASAP */
delay = HRT_INTERVAL_MIN;
} else if (next->deadline < deadline) {
//lldbg("due soon\n");
delay = next->deadline - now;
}
}
// There is no timer ISR, so simulate one by putting an event on the
// high priority work queue
// Remove the existing expiry and update with the new expiry
hrt_work_cancel(&_hrt_work);
hrt_work_queue(&_hrt_work, (worker_t)&hrt_tim_isr, NULL, delay);
}
static void
hrt_call_internal(struct hrt_call *entry, hrt_abstime deadline, hrt_abstime interval, hrt_callout callout, void *arg)
{
PX4_DEBUG("hrt_call_internal deadline=%lu interval = %lu", deadline, interval);
hrt_lock();
//PX4_INFO("hrt_call_internal after lock");
/* if the entry is currently queued, remove it */
/* note that we are using a potentially uninitialised
entry->link here, but it is safe as sq_rem() doesn't
dereference the passed node unless it is found in the
list. So we potentially waste a bit of time searching the
queue for the uninitialised entry->link but we don't do
anything actually unsafe.
*/
if (entry->deadline != 0) {
sq_rem(&entry->link, &callout_queue);
}
#if 1
// Use this to debug busy CPU that keeps rescheduling with 0 period time
/*if (interval < HRT_INTERVAL_MIN) {*/
/*PX4_ERR("hrt_call_internal interval too short: %" PRIu64, interval);*/
/*PX4_BACKTRACE();*/
/*}*/
#endif
entry->deadline = deadline;
entry->period = interval;
entry->callout = callout;
entry->arg = arg;
hrt_call_enter(entry);
hrt_unlock();
}
/*
* Call callout(arg) after delay has elapsed.
*
* If callout is NULL, this can be used to implement a timeout by testing the call
* with hrt_called().
*/
void hrt_call_after(struct hrt_call *entry, hrt_abstime delay, hrt_callout callout, void *arg)
{
//printf("hrt_call_after\n");
hrt_call_internal(entry,
hrt_absolute_time() + delay,
0,
callout,
arg);
}
/*
* Call callout(arg) after delay, and then after every interval.
*
* Note thet the interval is timed between scheduled, not actual, call times, so the call rate may
* jitter but should not drift.
*/
void hrt_call_every(struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval, hrt_callout callout, void *arg)
{
hrt_call_internal(entry,
hrt_absolute_time() + delay,
interval,
callout,
arg);
}
/*
* Call callout(arg) at absolute time calltime.
*/
void hrt_call_at(struct hrt_call *entry, hrt_abstime calltime, hrt_callout callout, void *arg)
{
hrt_call_internal(entry, calltime, 0, callout, arg);
}
#if 0
/*
* Convert absolute time to a timespec.
*/
void abstime_to_ts(struct timespec *ts, hrt_abstime abstime);
#endif
static void
hrt_call_invoke(void)
{
struct hrt_call *call;
hrt_abstime deadline;
hrt_lock();
while (true) {
/* get the current time */
hrt_abstime now = hrt_absolute_time();
call = (struct hrt_call *)sq_peek(&callout_queue);
if (call == NULL) {
break;
}
if (call->deadline > now) {
break;
}
sq_rem(&call->link, &callout_queue);
//PX4_INFO("call pop");
/* save the intended deadline for periodic calls */
deadline = call->deadline;
/* zero the deadline, as the call has occurred */
call->deadline = 0;
/* invoke the callout (if there is one) */
if (call->callout) {
// Unlock so we don't deadlock in callback
hrt_unlock();
//PX4_INFO("call %p: %p(%p)", call, call->callout, call->arg);
call->callout(call->arg);
hrt_lock();
}
/* if the callout has a non-zero period, it has to be re-entered */
if (call->period != 0) {
// re-check call->deadline to allow for
// callouts to re-schedule themselves
// using hrt_call_delay()
if (call->deadline <= now) {
call->deadline = deadline + call->period;
//PX4_INFO("call deadline set to %lu now=%lu", call->deadline, now);
}
hrt_call_enter(call);
}
}
hrt_unlock();
}

View File

@@ -0,0 +1,125 @@
/************************************************************************************************
* libc/misc/lib_crc32.c
*
* This file is a part of NuttX:
*
* Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
*
* The logic in this file was developed by Gary S. Brown:
*
* COPYRIGHT (C) 1986 Gary S. Brown. You may use this program, or code or tables
* extracted from it, as desired without restriction.
*
* First, the polynomial itself and its table of feedback terms. The polynomial is:
*
* X^32+X^26+X^23+X^22+X^16+X^12+X^11+X^10+X^8+X^7+X^5+X^4+X^2+X^1+X^0
*
* Note that we take it "backwards" and put the highest-order term in the lowest-order bit.
* The X^32 term is "implied"; the LSB is the X^31 term, etc. The X^0 term (usually shown
* as "+1") results in the MSB being 1
*
* Note that the usual hardware shift register implementation, which is what we're using
* (we're merely optimizing it by doing eight-bit chunks at a time) shifts bits into the
* lowest-order term. In our implementation, that means shifting towards the right. Why
* do we do it this way? Because the calculated CRC must be transmitted in order from
* highest-order term to lowest-order term. UARTs transmit characters in order from LSB
* to MSB. By storing the CRC this way we hand it to the UART in the order low-byte to
* high-byte; the UART sends each low-bit to hight-bit; and the result is transmission bit
* by bit from highest- to lowest-order term without requiring any bit shuffling on our
* part. Reception works similarly
*
* The feedback terms table consists of 256, 32-bit entries. Notes
*
* - The table can be generated at runtime if desired; code to do so is shown later. It
* might not be obvious, but the feedback terms simply represent the results of eight
* shift/xor operations for all combinations of data and CRC register values
*
* - The values must be right-shifted by eight bits by the updcrc logic; the shift must
* be u_(bring in zeroes). On some hardware you could probably optimize the shift in
* assembler by using byte-swap instructions polynomial $edb88320
************************************************************************************************/
/************************************************************************************************
* Included Files
************************************************************************************************/
#include <sys/types.h>
#include <stdint.h>
#include <crc32.h>
// Needed for Linux
#define FAR
/************************************************************************************************
* Private Data
************************************************************************************************/
static const uint32_t crc32_tab[] = {
0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5,
0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f,
0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01,
0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb,
0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad,
0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7,
0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79,
0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713,
0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45,
0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d
};
/************************************************************************************************
* Public Functions
************************************************************************************************/
/************************************************************************************************
* Name: crc32part
*
* Description:
* Continue CRC calculation on a part of the buffer.
*
************************************************************************************************/
uint32_t crc32part(FAR const uint8_t *src, size_t len, uint32_t crc32val)
{
size_t i;
for (i = 0; i < len; i++) {
crc32val = crc32_tab[(crc32val ^ src[i]) & 0xff] ^ (crc32val >> 8);
}
return crc32val;
}
/************************************************************************************************
* Name: crc32
*
* Description:
* Return a 32-bit CRC of the contents of the 'src' buffer, length 'len'
*
************************************************************************************************/
uint32_t crc32(FAR const uint8_t *src, size_t len)
{
return crc32part(src, len, 0);
}

View File

@@ -0,0 +1,114 @@
/****************************************************************************
*
* Copyright (c) 2015 Mark Charlebois. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file px4_posix_impl.cpp
*
* PX4 Middleware Wrapper Linux Implementation
*/
#include <px4_defines.h>
#include <px4_middleware.h>
#include <px4_workqueue.h>
#include <px4_defines.h>
#include <stdint.h>
#include <stdio.h>
#include <signal.h>
#include <errno.h>
#include <unistd.h>
#include <systemlib/param/param.h>
#include "hrt_work.h"
#include <drivers/drv_hrt.h>
#include "px4_time.h"
#include <pthread.h>
extern pthread_t _shell_task_id;
__BEGIN_DECLS
long PX4_TICKS_PER_SEC = sysconf(_SC_CLK_TCK);
#ifdef CONFIG_SHMEM
extern void init_params(void);
#endif
__END_DECLS
namespace px4
{
void init_once();
void init_once()
{
_shell_task_id = pthread_self();
//printf("[init] shell id: %lu\n", (unsigned long)_shell_task_id);
work_queues_init();
hrt_work_queue_init();
hrt_init();
param_init();
#ifdef CONFIG_SHMEM
PX4_DEBUG("Syncing params to shared memory\n");
init_params();
#endif
}
void init(int argc, char *argv[], const char *app_name)
{
printf("\n");
printf("______ __ __ ___ \n");
printf("| ___ \\ \\ \\ / / / |\n");
printf("| |_/ / \\ V / / /| |\n");
printf("| __/ / \\ / /_| |\n");
printf("| | / /^\\ \\ \\___ |\n");
printf("\\_| \\/ \\/ |_/\n");
printf("\n");
printf("%s starting.\n", app_name);
printf("\n");
// set the threads name
#ifdef __PX4_DARWIN
(void)pthread_setname_np(app_name);
#else
(void)pthread_setname_np(pthread_self(), app_name);
#endif
}
uint64_t get_time_micros()
{
return hrt_absolute_time();
}
}

View File

@@ -0,0 +1,451 @@
/****************************************************************************
*
* Copyright (C) 2015 Mark Charlebois. All rights reserved.
* Author: @author Mark Charlebois <charlebm#gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file px4_posix_tasks.c
* Implementation of existing task API for Linux
*/
#include <px4_log.h>
#include <px4_defines.h>
#include <unistd.h>
#include <stdio.h>
#include <stdlib.h>
#include <errno.h>
#include <stdbool.h>
#include <signal.h>
#include <fcntl.h>
#include <sched.h>
#include <unistd.h>
#include <string.h>
#include <pthread.h>
#include <limits.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <string>
#include <px4_tasks.h>
#include <px4_posix.h>
#include <systemlib/err.h>
#define MAX_CMD_LEN 100
#define PX4_MAX_TASKS 50
#define SHELL_TASK_ID (PX4_MAX_TASKS+1)
pthread_t _shell_task_id = 0;
pthread_mutex_t task_mutex = PTHREAD_MUTEX_INITIALIZER;
struct task_entry {
pthread_t pid;
std::string name;
bool isused;
task_entry() : isused(false) {}
};
static task_entry taskmap[PX4_MAX_TASKS] = {};
typedef struct {
px4_main_t entry;
char name[16]; //pthread_setname_np is restricted to 16 chars
int argc;
char *argv[];
// strings are allocated after the struct data
} pthdata_t;
static void *entry_adapter(void *ptr)
{
pthdata_t *data = (pthdata_t *) ptr;
int rv;
// set the threads name
#ifdef __PX4_DARWIN
rv = pthread_setname_np(data->name);
#else
rv = pthread_setname_np(pthread_self(), data->name);
#endif
if (rv) {
PX4_ERR("px4_task_spawn_cmd: failed to set name of thread %d %d\n", rv, errno);
}
data->entry(data->argc, data->argv);
free(ptr);
PX4_DEBUG("Before px4_task_exit");
px4_task_exit(0);
PX4_DEBUG("After px4_task_exit");
return nullptr;
}
void
px4_systemreset(bool to_bootloader)
{
PX4_WARN("Called px4_system_reset");
exit(0);
}
px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, px4_main_t entry,
char *const argv[])
{
int rv;
int argc = 0;
int i;
unsigned int len = 0;
unsigned long offset;
unsigned long structsize;
char *p = (char *)argv;
pthread_attr_t attr;
struct sched_param param = {};
// Calculate argc
while (p != (char *)nullptr) {
p = argv[argc];
if (p == (char *)nullptr) {
break;
}
++argc;
len += strlen(p) + 1;
}
structsize = sizeof(pthdata_t) + (argc + 1) * sizeof(char *);
// not safe to pass stack data to the thread creation
pthdata_t *taskdata = (pthdata_t *)malloc(structsize + len);
memset(taskdata, 0, structsize + len);
offset = ((unsigned long)taskdata) + structsize;
strncpy(taskdata->name, name, 16);
taskdata->name[15] = 0;
taskdata->entry = entry;
taskdata->argc = argc;
for (i = 0; i < argc; i++) {
PX4_DEBUG("arg %d %s\n", i, argv[i]);
taskdata->argv[i] = (char *)offset;
strcpy((char *)offset, argv[i]);
offset += strlen(argv[i]) + 1;
}
// Must add NULL at end of argv
taskdata->argv[argc] = (char *)nullptr;
PX4_DEBUG("starting task %s", name);
rv = pthread_attr_init(&attr);
if (rv != 0) {
PX4_ERR("px4_task_spawn_cmd: failed to init thread attrs");
free(taskdata);
return (rv < 0) ? rv : -rv;
}
#ifndef __PX4_DARWIN
if (stack_size < PTHREAD_STACK_MIN) {
stack_size = PTHREAD_STACK_MIN;
}
rv = pthread_attr_setstacksize(&attr, PX4_STACK_ADJUSTED(stack_size));
if (rv != 0) {
PX4_ERR("pthread_attr_setstacksize to %d returned error (%d)", stack_size, rv);
pthread_attr_destroy(&attr);
free(taskdata);
return (rv < 0) ? rv : -rv;
}
#endif
rv = pthread_attr_setinheritsched(&attr, PTHREAD_EXPLICIT_SCHED);
if (rv != 0) {
PX4_ERR("px4_task_spawn_cmd: failed to set inherit sched");
pthread_attr_destroy(&attr);
free(taskdata);
return (rv < 0) ? rv : -rv;
}
rv = pthread_attr_setschedpolicy(&attr, scheduler);
if (rv != 0) {
PX4_ERR("px4_task_spawn_cmd: failed to set sched policy");
pthread_attr_destroy(&attr);
free(taskdata);
return (rv < 0) ? rv : -rv;
}
#ifdef __PX4_CYGWIN
/* Priorities on Windows are defined a lot differently */
priority = SCHED_PRIORITY_DEFAULT;
#endif
param.sched_priority = priority;
rv = pthread_attr_setschedparam(&attr, &param);
if (rv != 0) {
PX4_ERR("px4_task_spawn_cmd: failed to set sched param");
pthread_attr_destroy(&attr);
free(taskdata);
return (rv < 0) ? rv : -rv;
}
pthread_mutex_lock(&task_mutex);
int taskid = 0;
for (i = 0; i < PX4_MAX_TASKS; ++i) {
if (taskmap[i].isused == false) {
taskmap[i].name = name;
taskmap[i].isused = true;
taskid = i;
break;
}
}
if (i >= PX4_MAX_TASKS) {
pthread_attr_destroy(&attr);
pthread_mutex_unlock(&task_mutex);
free(taskdata);
return -ENOSPC;
}
rv = pthread_create(&taskmap[taskid].pid, &attr, &entry_adapter, (void *) taskdata);
if (rv != 0) {
if (rv == EPERM) {
//printf("WARNING: NOT RUNING AS ROOT, UNABLE TO RUN REALTIME THREADS\n");
rv = pthread_create(&taskmap[taskid].pid, nullptr, &entry_adapter, (void *) taskdata);
if (rv != 0) {
PX4_ERR("px4_task_spawn_cmd: failed to create thread %d %d\n", rv, errno);
taskmap[taskid].isused = false;
pthread_attr_destroy(&attr);
pthread_mutex_unlock(&task_mutex);
free(taskdata);
return (rv < 0) ? rv : -rv;
}
} else {
pthread_attr_destroy(&attr);
pthread_mutex_unlock(&task_mutex);
free(taskdata);
return (rv < 0) ? rv : -rv;
}
}
pthread_attr_destroy(&attr);
pthread_mutex_unlock(&task_mutex);
return i;
}
int px4_task_delete(px4_task_t id)
{
int rv = 0;
pthread_t pid;
PX4_DEBUG("Called px4_task_delete");
if (id < PX4_MAX_TASKS && taskmap[id].isused) {
pid = taskmap[id].pid;
} else {
return -EINVAL;
}
pthread_mutex_lock(&task_mutex);
// If current thread then exit, otherwise cancel
if (pthread_self() == pid) {
pthread_join(pid, nullptr);
taskmap[id].isused = false;
pthread_mutex_unlock(&task_mutex);
pthread_exit(nullptr);
} else {
rv = pthread_cancel(pid);
}
taskmap[id].isused = false;
pthread_mutex_unlock(&task_mutex);
return rv;
}
void px4_task_exit(int ret)
{
int i;
pthread_t pid = pthread_self();
// Get pthread ID from the opaque ID
for (i = 0; i < PX4_MAX_TASKS; ++i) {
if (taskmap[i].pid == pid) {
pthread_mutex_lock(&task_mutex);
taskmap[i].isused = false;
break;
}
}
if (i >= PX4_MAX_TASKS) {
PX4_ERR("px4_task_exit: self task not found!");
} else {
PX4_DEBUG("px4_task_exit: %s", taskmap[i].name.c_str());
}
pthread_mutex_unlock(&task_mutex);
pthread_exit((void *)(unsigned long)ret);
}
int px4_task_kill(px4_task_t id, int sig)
{
int rv = 0;
pthread_t pid;
PX4_DEBUG("Called px4_task_kill %d", sig);
if (id < PX4_MAX_TASKS && taskmap[id].isused && taskmap[id].pid != 0) {
pthread_mutex_lock(&task_mutex);
pid = taskmap[id].pid;
pthread_mutex_unlock(&task_mutex);
} else {
return -EINVAL;
}
// If current thread then exit, otherwise cancel
rv = pthread_kill(pid, sig);
return rv;
}
void px4_show_tasks()
{
int idx;
int count = 0;
PX4_INFO("Active Tasks:");
for (idx = 0; idx < PX4_MAX_TASKS; idx++) {
if (taskmap[idx].isused) {
PX4_INFO(" %-10s %lu", taskmap[idx].name.c_str(), (unsigned long)taskmap[idx].pid);
count++;
}
}
if (count == 0) {
PX4_INFO(" No running tasks");
}
}
bool px4_task_is_running(const char *taskname)
{
int idx;
for (idx = 0; idx < PX4_MAX_TASKS; idx++) {
if (taskmap[idx].isused && (strcmp(taskmap[idx].name.c_str(), taskname) == 0)) {
return true;
}
}
return false;
}
px4_task_t px4_getpid()
{
pthread_t pid = pthread_self();
px4_task_t ret = -1;
pthread_mutex_lock(&task_mutex);
for (int i = 0; i < PX4_MAX_TASKS; i++) {
if (taskmap[i].isused && taskmap[i].pid == pid) {
ret = i;
}
}
pthread_mutex_unlock(&task_mutex);
return ret;
}
const char *px4_get_taskname()
{
pthread_t pid = pthread_self();
const char *prog_name = "UnknownApp";
pthread_mutex_lock(&task_mutex);
for (int i = 0; i < PX4_MAX_TASKS; i++) {
if (taskmap[i].isused && taskmap[i].pid == pid) {
prog_name = taskmap[i].name.c_str();
}
}
pthread_mutex_unlock(&task_mutex);
return prog_name;
}
int px4_prctl(int option, const char *arg2, px4_task_t pid)
{
int rv;
switch (option) {
case PR_SET_NAME:
// set the threads name
#ifdef __PX4_DARWIN
rv = pthread_setname_np(arg2);
#else
rv = pthread_setname_np(pthread_self(), arg2);
#endif
break;
default:
rv = -1;
PX4_WARN("FAILED SETTING TASK NAME");
break;
}
return rv;
}

View File

@@ -0,0 +1,205 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file px4_sem.cpp
*
* PX4 Middleware Wrapper Linux Implementation
*/
#include <px4_defines.h>
#include <px4_middleware.h>
#include <px4_workqueue.h>
#include <stdint.h>
#include <stdio.h>
#include <pthread.h>
#include <errno.h>
#if defined(__PX4_DARWIN) || defined(__PX4_CYGWIN)
#include <px4_posix.h>
int px4_sem_init(px4_sem_t *s, int pshared, unsigned value)
{
// We do not used the process shared arg
(void)pshared;
s->value = value;
pthread_cond_init(&(s->wait), NULL);
pthread_mutex_init(&(s->lock), NULL);
return 0;
}
int px4_sem_setprotocol(px4_sem_t *s, int protocol)
{
return 0;
}
int px4_sem_wait(px4_sem_t *s)
{
int ret = pthread_mutex_lock(&(s->lock));
if (ret) {
return ret;
}
s->value--;
if (s->value < 0) {
ret = pthread_cond_wait(&(s->wait), &(s->lock));
} else {
ret = 0;
}
if (ret) {
PX4_WARN("px4_sem_wait failure");
}
int mret = pthread_mutex_unlock(&(s->lock));
return (ret) ? ret : mret;
}
int px4_sem_trywait(px4_sem_t *s)
{
int ret = pthread_mutex_lock(&(s->lock));
if (ret) {
return ret;
}
if (s->value <= 0) {
errno = EAGAIN;
ret = -1;
} else {
s->value--;
}
int mret = pthread_mutex_unlock(&(s->lock));
return (ret) ? ret : mret;
}
int px4_sem_timedwait(px4_sem_t *s, const struct timespec *abstime)
{
int ret = pthread_mutex_lock(&(s->lock));
if (ret) {
return ret;
}
s->value--;
errno = 0;
if (s->value < 0) {
ret = pthread_cond_timedwait(&(s->wait), &(s->lock), abstime);
} else {
ret = 0;
}
int err = ret;
if (err != 0 && err != ETIMEDOUT) {
setbuf(stdout, NULL);
setbuf(stderr, NULL);
const unsigned NAMELEN = 32;
char thread_name[NAMELEN] = {};
(void)pthread_getname_np(pthread_self(), thread_name, NAMELEN);
PX4_WARN("%s: px4_sem_timedwait failure: ret: %d, %s", thread_name, ret, strerror(err));
}
int mret = pthread_mutex_unlock(&(s->lock));
return (err) ? err : mret;
}
int px4_sem_post(px4_sem_t *s)
{
int ret = pthread_mutex_lock(&(s->lock));
if (ret) {
return ret;
}
s->value++;
if (s->value <= 0) {
ret = pthread_cond_signal(&(s->wait));
} else {
ret = 0;
}
if (ret) {
PX4_WARN("px4_sem_post failure");
}
int mret = pthread_mutex_unlock(&(s->lock));
// return the cond signal failure if present,
// else return the mutex status
return (ret) ? ret : mret;
}
int px4_sem_getvalue(px4_sem_t *s, int *sval)
{
int ret = pthread_mutex_lock(&(s->lock));
if (ret) {
PX4_WARN("px4_sem_getvalue failure");
}
if (ret) {
return ret;
}
*sval = s->value;
ret = pthread_mutex_unlock(&(s->lock));
return ret;
}
int px4_sem_destroy(px4_sem_t *s)
{
pthread_mutex_lock(&(s->lock));
pthread_cond_destroy(&(s->wait));
pthread_mutex_unlock(&(s->lock));
pthread_mutex_destroy(&(s->lock));
return 0;
}
#endif

View File

@@ -0,0 +1,131 @@
/****************************************************************************
*
* Copyright (c) 2015 Vijay Venkatraman. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_defines.h>
#include <px4_posix.h>
#include <string.h>
#include <stdbool.h>
#include <stdlib.h>
#include <fcntl.h>
#include <unistd.h>
#include <systemlib/err.h>
#include <errno.h>
#include <semaphore.h>
#include <sys/stat.h>
#include <drivers/drv_hrt.h>
#include <sys/mman.h>
#include <sys/ioctl.h>
#include "systemlib/param/param.h"
#include <shmem.h>
#include "px4muorb.h"
//#define SHMEM_DEBUG
void update_to_shmem(param_t param, union param_value_u value);
int update_from_shmem(param_t param, union param_value_u *value);
void update_index_from_shmem(void);
uint64_t update_from_shmem_prev_time = 0, update_from_shmem_current_time = 0;
extern unsigned char *adsp_changed_index;
struct param_wbuf_s {
union param_value_u val;
param_t param;
bool unsaved;
};
/*update value and param's change bit in shared memory*/
void update_to_shmem(param_t param, union param_value_u value)
{
if (px4muorb_param_update_to_shmem(param, (unsigned char *) &value,
sizeof(value))) {
PX4_ERR("krait update param %u failed", param);
}
}
void update_index_from_shmem(void)
{
if (!adsp_changed_index) {
PX4_ERR("%s no param buffer", __FUNCTION__);
return;
}
px4muorb_param_update_index_from_shmem(adsp_changed_index,
PARAM_BUFFER_SIZE);
}
static void update_value_from_shmem(param_t param, union param_value_u *value)
{
if (px4muorb_param_update_value_from_shmem(param, (unsigned char *) value,
sizeof(union param_value_u))) {
PX4_ERR("%s get param failed", __FUNCTION__);
}
}
int update_from_shmem(param_t param, union param_value_u *value)
{
unsigned int byte_changed, bit_changed;
unsigned int retval = 0;
if (!adsp_changed_index) {
PX4_ERR("%s no param buffer", __FUNCTION__);
return 0;
}
update_from_shmem_current_time = hrt_absolute_time();
if ((update_from_shmem_current_time - update_from_shmem_prev_time)
> 1000000) { //update every 1 second
update_from_shmem_prev_time = update_from_shmem_current_time;
update_index_from_shmem();
}
byte_changed = param / 8;
bit_changed = 1 << param % 8;
if (adsp_changed_index[byte_changed] & bit_changed) {
update_value_from_shmem(param, value);
adsp_changed_index[byte_changed] &= ~bit_changed; //clear the bit
retval = 1;
}
//else {PX4_INFO("no change to param %s", param_name(param));}
PX4_DEBUG("%s %d bit on adsp index[%d]",
(retval) ? "cleared" : "unchanged", bit_changed, byte_changed);
return retval;
}

View File

@@ -0,0 +1,53 @@
/****************************************************************************
*
* Copyright (C) 2015 Anton Matosov. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file sitl_runner_main.cpp
* Basic shell to execute px4 with specific model
*
* @author Anton Matosov <anton.matosov@gmail.com>
*/
#include <unistd.h>
#define __PX4_SITL_MAIN_OVERRIDE
#include "@SITL_RUNNER_MAIN_CPP@"
int main(int argc, const char **argv)
{
if (chdir("@SITL_RUNNER_WORKING_DIRECTORY@") != 0) {
PX4_ERR("Failed to change current directory to @SITL_RUNNER_WORKING_DIRECTORY@. error %i", errno);
return errno;
}
const char *argsOverride[] = {argv[0], "@SITL_RUNNER_SOURCE_DIR@", "@SITL_RUNNER_MODEL_FILE@"};
return SITL_MAIN(sizeof(argsOverride) / sizeof(argsOverride[0]), (char**)argsOverride);
}