POSIX: Added PX4_ROOTFSDIR to file paths

Set a default path relative to current dir for the posix target.

Running make posixrun will create the required directoroes and then run
mainapp from its build location.

PX4_ROOTFSDIR is set to nothing for nuttx.

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
Mark Charlebois 2015-06-11 21:36:13 -07:00
parent 0c43803ec7
commit 4d1ae6269b
10 changed files with 25 additions and 14 deletions

View File

@ -132,7 +132,7 @@ static sem_t g_sys_state_mutex;
/* The data manager store file handle and file name */
static int g_fd = -1, g_task_fd = -1;
static const char *default_device_path = "/fs/microsd/dataman";
static const char *default_device_path = PX4_ROOTFSDIR"/fs/microsd/dataman";
static char *k_data_manager_device_path = NULL;
/* The data manager work queues */

View File

@ -571,7 +571,7 @@ MavlinkFTP::ErrorCode
MavlinkFTP::_workTruncateFile(PayloadHeader* payload)
{
char file[kMaxDataLength];
const char temp_file[] = "/fs/microsd/.trunc.tmp";
const char temp_file[] = PX4_ROOTFSDIR"/fs/microsd/.trunc.tmp";
strncpy(file, _data_as_cstring(payload), kMaxDataLength);
payload->size = 0;

View File

@ -389,7 +389,7 @@ protected:
} else if (write_err_count < write_err_threshold) {
/* string to hold the path to the log */
char log_file_name[32] = "";
char log_file_path[64] = "";
char log_file_path[70] = "";
timespec ts;
px4_clock_gettime(CLOCK_REALTIME, &ts);
@ -400,7 +400,7 @@ protected:
// XXX we do not want to interfere here with the SD log app
strftime(log_file_name, sizeof(log_file_name), "msgs_%Y_%m_%d_%H_%M_%S.txt", &tt);
snprintf(log_file_path, sizeof(log_file_path), "/fs/microsd/%s", log_file_name);
snprintf(log_file_path, sizeof(log_file_path), PX4_ROOTFSDIR"/fs/microsd/%s", log_file_name);
fp = fopen(log_file_path, "ab");
/* write first message */

View File

@ -49,8 +49,9 @@
#include <controllib/blocks.hpp>
#include <controllib/block/BlockParam.hpp>
#include <drivers/drv_hrt.h>
#include <px4_defines.h>
#define GEOFENCE_FILENAME "/fs/microsd/etc/geofence.txt"
#define GEOFENCE_FILENAME PX4_ROOTFSDIR"/fs/microsd/etc/geofence.txt"
class Geofence : public control::SuperBlock
{

View File

@ -189,7 +189,7 @@ int position_estimator_inav_main(int argc, char *argv[])
static void write_debug_log(const char *msg, float dt, float x_est[2], float y_est[2], float z_est[2], float x_est_prev[2], float y_est_prev[2], float z_est_prev[2], float acc[3], float corr_gps[3][2], float w_xy_gps_p, float w_xy_gps_v)
{
FILE *f = fopen("/fs/microsd/inav.log", "a");
FILE *f = fopen(PX4_ROOTFSDIR"/fs/microsd/inav.log", "a");
if (f) {
char *s = malloc(256);

View File

@ -179,7 +179,7 @@ static const int MIN_BYTES_TO_WRITE = 512;
static bool _extended_logging = false;
static bool _gpstime_only = false;
#define MOUNTPOINT "/fs/microsd"
#define MOUNTPOINT PX4_ROOTFSDIR"/fs/microsd"
static const char *mountpoint = MOUNTPOINT;
static const char *log_root = MOUNTPOINT "/log";
static int mavlink_fd = -1;

View File

@ -695,7 +695,7 @@ param_reset_excludes(const char *excludes[], int num_excludes)
param_notify_changes();
}
static const char *param_default_file = "/eeprom/parameters";
static const char *param_default_file = PX4_ROOTFSDIR"/eeprom/parameters";
static char *param_user_file = NULL;
int

View File

@ -104,8 +104,7 @@ int uORBTest::UnitTest::pubsublatency_main(void)
if (pubsubtest_print) {
char fname[32];
//sprintf(fname, "/fs/microsd/timings%u.txt", timingsgroup);
sprintf(fname, "/tmp/timings%u.txt", timingsgroup);
sprintf(fname, PX4_ROOTFSDIR"/fs/microsd/timings%u.txt", timingsgroup);
FILE *f = fopen(fname, "w");
if (f == NULL) {
warnx("Error opening file!\n");

View File

@ -65,9 +65,9 @@
#define NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN 4
#define UAVCAN_DEVICE_PATH "/dev/uavcan/esc"
#define UAVCAN_NODE_DB_PATH "/fs/microsd/uavcan.db"
#define UAVCAN_FIRMWARE_PATH "/fs/microsd/fw"
#define UAVCAN_LOG_FILE UAVCAN_NODE_DB_PATH"/trace.log"
#define UAVCAN_NODE_DB_PATH PX4_ROOTFSDIR"/fs/microsd/uavcan.db"
#define UAVCAN_FIRMWARE_PATH PX4_ROOTFSDIR"/fs/microsd/fw"
#define UAVCAN_LOG_FILE UAVCAN_NODE_DB_PATH"/trace.log"
// we add two to allow for actuator_direct and busevent
#define UAVCAN_NUM_POLL_FDS (NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN+2)

View File

@ -92,6 +92,8 @@ typedef param_t px4_param_t;
*/
#if defined(__PX4_NUTTX)
#define PX4_ROOTFSDIR
/* XXX this is a hack to resolve conflicts with NuttX headers */
#if !defined(__PX4_TESTS)
#define isspace(c) \
@ -136,6 +138,12 @@ __END_DECLS
#define px4_statfs_buf_f_bavail_t unsigned long
#if defined(__PX4_QURT)
#define PX4_ROOTFSDIR
#else
#define PX4_ROOTFSDIR "rootfs"
#endif
#endif
@ -198,6 +206,10 @@ __END_DECLS
#endif
#if defined(__PX4_QURT)
#define PX4_ROOTFSDIR
#define DEFAULT_PARAM_FILE "/fs/eeprom/parameters"
#define SIOCDEVPRIVATE 999999
// Missing math.h defines
@ -211,7 +223,6 @@ __END_DECLS
#define fminf(x, y) ((x) > (y) ? y : x)
#endif
#endif
/*