Browse Source

file paths: add PX4_STORAGEDIR & use it where appropriate

sbg
Beat Küng 7 years ago committed by Lorenz Meier
parent
commit
c0cac0594e
  1. 6
      src/modules/dataman/dataman.cpp
  2. 6
      src/modules/logger/logger.cpp
  3. 6
      src/modules/logger/logger.h
  4. 2
      src/modules/mavlink/mavlink_ftp.cpp
  5. 2
      src/modules/mavlink/mavlink_log_handler.cpp
  6. 2
      src/modules/mavlink/mavlink_receiver.cpp
  7. 4
      src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp
  8. 2
      src/modules/navigator/geofence.h
  9. 6
      src/modules/position_estimator_inav/position_estimator_inav_main.cpp
  10. 2
      src/modules/uORB/uORBManager.cpp
  11. 2
      src/modules/uORB/uORB_tests/uORBTest_UnitTest.cpp
  12. 5
      src/platforms/px4_defines.h
  13. 2
      src/systemcmds/sd_bench/sd_bench.c
  14. 18
      src/systemcmds/tests/test_file.c
  15. 6
      src/systemcmds/tests/test_file2.c
  16. 10
      src/systemcmds/tests/test_mount.c
  17. 2
      src/systemcmds/tests/test_parameters.cpp

6
src/modules/dataman/dataman.cpp

@ -246,11 +246,7 @@ static px4_sem_t g_sys_state_mutex_mission; @@ -246,11 +246,7 @@ static px4_sem_t g_sys_state_mutex_mission;
static px4_sem_t g_sys_state_mutex_fence;
/* The data manager store file handle and file name */
#ifdef __PX4_POSIX
static const char *default_device_path = PX4_ROOTFSDIR"/dataman";
#else
static const char *default_device_path = PX4_ROOTFSDIR"/fs/microsd/dataman";
#endif
static const char *default_device_path = PX4_STORAGEDIR "/dataman";
static char *k_data_manager_device_path = nullptr;
#if defined(FLASH_BASED_DATAMAN)

6
src/modules/logger/logger.cpp

@ -830,11 +830,7 @@ void Logger::run() @@ -830,11 +830,7 @@ void Logger::run()
orb_set_interval(log_message_sub, 20);
#if __PX4_POSIX
int ntopics = add_topics_from_file(PX4_ROOTFSDIR "/etc/logging/logger_topics.txt");
#else
int ntopics = add_topics_from_file(PX4_ROOTFSDIR "/fs/microsd/etc/logging/logger_topics.txt");
#endif
int ntopics = add_topics_from_file(PX4_STORAGEDIR "/etc/logging/logger_topics.txt");
if (ntopics > 0) {
PX4_INFO("logging %d topics from logger_topics.txt", ntopics);

6
src/modules/logger/logger.h

@ -313,11 +313,7 @@ private: @@ -313,11 +313,7 @@ private:
static constexpr size_t MAX_TOPICS_NUM = 64; /**< Maximum number of logged topics */
static constexpr unsigned MAX_NO_LOGFILE = 999; /**< Maximum number of log files */
#ifdef __PX4_POSIX
static constexpr const char *LOG_ROOT = PX4_ROOTFSDIR"/log";
#else
static constexpr const char *LOG_ROOT = PX4_ROOTFSDIR"/fs/microsd/log";
#endif
static constexpr const char *LOG_ROOT = PX4_STORAGEDIR "/log";
uint8_t *_msg_buffer{nullptr};
int _msg_buffer_len{0};

2
src/modules/mavlink/mavlink_ftp.cpp

@ -663,7 +663,7 @@ MavlinkFTP::_workTruncateFile(PayloadHeader *payload) @@ -663,7 +663,7 @@ MavlinkFTP::_workTruncateFile(PayloadHeader *payload)
// emulate truncate(_work_buffer1, payload->offset) by
// copying to temp and overwrite with O_TRUNC flag (NuttX does not support truncate()).
const char temp_file[] = PX4_ROOTFSDIR"/fs/microsd/.trunc.tmp";
const char temp_file[] = PX4_STORAGEDIR"/.trunc.tmp";
struct stat st;

2
src/modules/mavlink/mavlink_log_handler.cpp

@ -39,7 +39,7 @@ @@ -39,7 +39,7 @@
#include <sys/stat.h>
#include <time.h>
#define MOUNTPOINT PX4_ROOTFSDIR "/fs/microsd"
#define MOUNTPOINT PX4_STORAGEDIR
static const char *kLogRoot = MOUNTPOINT "/log";
static const char *kLogData = MOUNTPOINT "/logdata.txt";

2
src/modules/mavlink/mavlink_receiver.cpp

@ -443,7 +443,7 @@ void @@ -443,7 +443,7 @@ void
MavlinkReceiver::send_storage_information(int storage_id)
{
mavlink_storage_information_t storage_info{};
const char *microsd_dir = PX4_ROOTFSDIR"/fs/microsd";
const char *microsd_dir = PX4_STORAGEDIR;
if (storage_id == 0 || storage_id == 1) { // request is for all or the first storage
storage_info.storage_id = 1;

4
src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp

@ -55,8 +55,8 @@ const MavlinkFtpTest::DownloadTestCase MavlinkFtpTest::_rgDownloadTestCases[] = @@ -55,8 +55,8 @@ const MavlinkFtpTest::DownloadTestCase MavlinkFtpTest::_rgDownloadTestCases[] =
{ PX4_MAVLINK_TEST_DATA_DIR "/unit_test_data/mavlink_tests/test_240.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) + 1, false, false }, // Read take two packets
};
const char MavlinkFtpTest::_unittest_microsd_dir[] = PX4_ROOTFSDIR "/fs/microsd/ftp_unit_test_dir";
const char MavlinkFtpTest::_unittest_microsd_file[] = PX4_ROOTFSDIR "/fs/microsd/ftp_unit_test_dir/file";
const char MavlinkFtpTest::_unittest_microsd_dir[] = PX4_STORAGEDIR "/ftp_unit_test_dir";
const char MavlinkFtpTest::_unittest_microsd_file[] = PX4_STORAGEDIR "/ftp_unit_test_dir/file";
MavlinkFtpTest::MavlinkFtpTest() :
_ftp_server(nullptr),

2
src/modules/navigator/geofence.h

@ -52,7 +52,7 @@ @@ -52,7 +52,7 @@
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_air_data.h>
#define GEOFENCE_FILENAME PX4_ROOTFSDIR"/fs/microsd/etc/geofence.txt"
#define GEOFENCE_FILENAME PX4_STORAGEDIR"/etc/geofence.txt"
class Navigator;

6
src/modules/position_estimator_inav/position_estimator_inav_main.cpp

@ -191,11 +191,7 @@ static void write_debug_log(const char *msg, float dt, float x_est[2], float y_e @@ -191,11 +191,7 @@ static void write_debug_log(const char *msg, float dt, float x_est[2], float y_e
float acc[3], float corr_gps[3][2], float w_xy_gps_p, float w_xy_gps_v, float corr_mocap[3][1], float w_mocap_p,
float corr_vision[3][2], float w_xy_vision_p, float w_z_vision_p, float w_xy_vision_v)
{
#ifdef __PX4_POSIX
FILE *f = fopen(PX4_ROOTFSDIR"/inav.log", "a");
#else
FILE *f = fopen(PX4_ROOTFSDIR"/fs/microsd/inav.log", "a");
#endif
FILE *f = fopen(PX4_STORAGEDIR"/inav.log", "a");
if (f) {
char *s = malloc(256);

2
src/modules/uORB/uORBManager.cpp

@ -65,7 +65,7 @@ bool uORB::Manager::initialize() @@ -65,7 +65,7 @@ bool uORB::Manager::initialize()
uORB::Manager::Manager()
{
#ifdef ORB_USE_PUBLISHER_RULES
const char *file_name = "./rootfs/orb_publisher.rules";
const char *file_name = PX4_STORAGEDIR"/orb_publisher.rules";
int ret = readPublisherRulesFromFile(file_name, _publisher_rule);
if (ret == PX4_OK) {

2
src/modules/uORB/uORB_tests/uORBTest_UnitTest.cpp

@ -139,7 +139,7 @@ int uORBTest::UnitTest::pubsublatency_main() @@ -139,7 +139,7 @@ int uORBTest::UnitTest::pubsublatency_main()
if (pubsubtest_print) {
char fname[32];
sprintf(fname, PX4_ROOTFSDIR"/fs/microsd/timings%u.txt", timingsgroup);
sprintf(fname, PX4_STORAGEDIR"/uorb_timings%u.txt", timingsgroup);
FILE *f = fopen(fname, "w");
if (f == nullptr) {

5
src/platforms/px4_defines.h

@ -110,7 +110,8 @@ typedef param_t px4_param_t; @@ -110,7 +110,8 @@ typedef param_t px4_param_t;
* NuttX specific defines.
****************************************************************************/
#define PX4_ROOTFSDIR "."
#define PX4_ROOTFSDIR ""
#define PX4_STORAGEDIR PX4_ROOTFSDIR "/fs/microsd"
#define _PX4_IOC(x,y) _IOC(x,y)
// mode for open with O_CREAT
@ -200,6 +201,8 @@ __END_DECLS @@ -200,6 +201,8 @@ __END_DECLS
# endif
#endif // __PX4_QURT
#define PX4_STORAGEDIR PX4_ROOTFSDIR
#endif // __PX4_POSIX
#if defined(__PX4_ROS) || defined(__PX4_POSIX)

2
src/systemcmds/sd_bench/sd_bench.c

@ -64,7 +64,7 @@ static inline unsigned int time_fsync(int fd); @@ -64,7 +64,7 @@ static inline unsigned int time_fsync(int fd);
__EXPORT int sd_bench_main(int argc, char *argv[]);
static const char *BENCHMARK_FILE = PX4_ROOTFSDIR"/fs/microsd/benchmark.tmp";
static const char *BENCHMARK_FILE = PX4_STORAGEDIR"/benchmark.tmp";
static int num_runs; ///< number of runs
static int run_duration; ///< duration of a single run [ms]

18
src/systemcmds/tests/test_file.c

@ -98,7 +98,7 @@ test_file(int argc, char *argv[]) @@ -98,7 +98,7 @@ test_file(int argc, char *argv[])
/* check if microSD card is mounted */
struct stat buffer;
if (stat(PX4_ROOTFSDIR "/fs/microsd/", &buffer)) {
if (stat(PX4_STORAGEDIR "/", &buffer)) {
warnx("no microSD card mounted, aborting file test");
return 1;
}
@ -126,7 +126,7 @@ test_file(int argc, char *argv[]) @@ -126,7 +126,7 @@ test_file(int argc, char *argv[])
uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
hrt_abstime start, end;
int fd = px4_open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
int fd = px4_open(PX4_STORAGEDIR "/testfile", O_TRUNC | O_WRONLY | O_CREAT);
warnx("testing unaligned writes - please wait..");
@ -158,7 +158,7 @@ test_file(int argc, char *argv[]) @@ -158,7 +158,7 @@ test_file(int argc, char *argv[])
warnx("write took %" PRIu64 " us", (end - start));
px4_close(fd);
fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_RDONLY);
fd = open(PX4_STORAGEDIR "/testfile", O_RDONLY);
/* read back data for validation */
for (unsigned i = 0; i < iterations; i++) {
@ -196,8 +196,8 @@ test_file(int argc, char *argv[]) @@ -196,8 +196,8 @@ test_file(int argc, char *argv[])
*/
close(fd);
int ret = unlink(PX4_ROOTFSDIR "/fs/microsd/testfile");
fd = px4_open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
int ret = unlink(PX4_STORAGEDIR "/testfile");
fd = px4_open(PX4_STORAGEDIR "/testfile", O_TRUNC | O_WRONLY | O_CREAT);
warnx("testing aligned writes - please wait.. (CTRL^C to abort)");
@ -220,7 +220,7 @@ test_file(int argc, char *argv[]) @@ -220,7 +220,7 @@ test_file(int argc, char *argv[])
warnx("reading data aligned..");
px4_close(fd);
fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_RDONLY);
fd = open(PX4_STORAGEDIR "/testfile", O_RDONLY);
bool align_read_ok = true;
@ -257,7 +257,7 @@ test_file(int argc, char *argv[]) @@ -257,7 +257,7 @@ test_file(int argc, char *argv[])
warnx("reading data unaligned..");
close(fd);
fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_RDONLY);
fd = open(PX4_STORAGEDIR "/testfile", O_RDONLY);
bool unalign_read_ok = true;
int unalign_read_err_count = 0;
@ -298,7 +298,7 @@ test_file(int argc, char *argv[]) @@ -298,7 +298,7 @@ test_file(int argc, char *argv[])
}
ret = unlink(PX4_ROOTFSDIR "/fs/microsd/testfile");
ret = unlink(PX4_STORAGEDIR "/testfile");
close(fd);
if (ret) {
@ -311,7 +311,7 @@ test_file(int argc, char *argv[]) @@ -311,7 +311,7 @@ test_file(int argc, char *argv[])
/* list directory */
DIR *d;
struct dirent *dir;
d = opendir(PX4_ROOTFSDIR "/fs/microsd");
d = opendir(PX4_STORAGEDIR);
if (d) {

6
src/systemcmds/tests/test_file2.c

@ -54,11 +54,7 @@ @@ -54,11 +54,7 @@
#define FLAG_FSYNC 1
#define FLAG_LSEEK 2
#ifdef __PX4_POSIX
#define LOG_PATH PX4_ROOTFSDIR "/log/"
#else
#define LOG_PATH PX4_ROOTFSDIR "/fs/microsd/"
#endif
#define LOG_PATH PX4_STORAGEDIR
/*
return a predictable value for any file offset to allow detection of corruption

10
src/systemcmds/tests/test_mount.c

@ -70,7 +70,7 @@ test_mount(int argc, char *argv[]) @@ -70,7 +70,7 @@ test_mount(int argc, char *argv[])
/* check if microSD card is mounted */
struct stat buffer;
if (stat(PX4_ROOTFSDIR "/fs/microsd/", &buffer)) {
if (stat(PX4_STORAGEDIR "/", &buffer)) {
PX4_ERR("no microSD card mounted, aborting file test");
return 1;
}
@ -78,7 +78,7 @@ test_mount(int argc, char *argv[]) @@ -78,7 +78,7 @@ test_mount(int argc, char *argv[])
/* list directory */
DIR *d;
struct dirent *dir;
d = opendir(PX4_ROOTFSDIR "/fs/microsd");
d = opendir(PX4_STORAGEDIR);
if (d) {
@ -202,7 +202,7 @@ test_mount(int argc, char *argv[]) @@ -202,7 +202,7 @@ test_mount(int argc, char *argv[])
uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
int fd = px4_open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
int fd = px4_open(PX4_STORAGEDIR "/testfile", O_TRUNC | O_WRONLY | O_CREAT);
for (unsigned i = 0; i < iterations; i++) {
@ -239,7 +239,7 @@ test_mount(int argc, char *argv[]) @@ -239,7 +239,7 @@ test_mount(int argc, char *argv[])
usleep(200000);
px4_close(fd);
fd = px4_open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_RDONLY);
fd = px4_open(PX4_STORAGEDIR "/testfile", O_RDONLY);
/* read back data for validation */
for (unsigned i = 0; i < iterations; i++) {
@ -268,7 +268,7 @@ test_mount(int argc, char *argv[]) @@ -268,7 +268,7 @@ test_mount(int argc, char *argv[])
}
int ret = unlink(PX4_ROOTFSDIR "/fs/microsd/testfile");
int ret = unlink(PX4_STORAGEDIR "/testfile");
px4_close(fd);
if (ret) {

2
src/systemcmds/tests/test_parameters.cpp

@ -312,7 +312,7 @@ bool ParameterTest::exportImportAll() @@ -312,7 +312,7 @@ bool ParameterTest::exportImportAll()
static constexpr float MAGIC_FLOAT_VAL = 0.217828f;
// backup current parameters
const char *param_file_name = PX4_ROOTFSDIR "/fs/microsd/param_backup";
const char *param_file_name = PX4_STORAGEDIR "/param_backup";
int fd = open(param_file_name, O_WRONLY | O_CREAT, PX4_O_MODE_666);
if (fd < 0) {

Loading…
Cancel
Save