aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2013-06-17 14:45:20 +0200
committerJulian Oes <julian@oes.ch>2013-06-17 14:45:20 +0200
commit7bb78a4f9b7d6a4d4468c93154c3f3524e8ff929 (patch)
treef239492841e34551fb2bf467b61f1c88359f1108 /src
parentbca60b98bdc1bfe5a377946d8c50d8f5c54514d9 (diff)
parenta11895ac43b4e345ebd04d9999f386bc1408b98e (diff)
downloadpx4-firmware-7bb78a4f9b7d6a4d4468c93154c3f3524e8ff929.tar.gz
px4-firmware-7bb78a4f9b7d6a4d4468c93154c3f3524e8ff929.tar.bz2
px4-firmware-7bb78a4f9b7d6a4d4468c93154c3f3524e8ff929.zip
Merge remote-tracking branch 'drton/sdlog2' into new_state_machine
Conflicts: src/modules/sdlog2/sdlog2.c
Diffstat (limited to 'src')
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp157
-rw-r--r--src/drivers/hott_telemetry/messages.c13
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp2
-rw-r--r--src/modules/sdlog2/logbuffer.c2
-rw-r--r--src/modules/sdlog2/sdlog2.c121
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h25
6 files changed, 193 insertions, 127 deletions
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index e50395e47..c39da98d7 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -37,7 +37,7 @@
*
* Driver for the Eagle Tree Airspeed V3 connected via I2C.
*/
-
+
#include <nuttx/config.h>
#include <drivers/device/i2c.h>
@@ -77,13 +77,13 @@
#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION
/* I2C bus address */
-#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */
+#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */
/* Register address */
-#define READ_CMD 0x07 /* Read the data */
-
+#define READ_CMD 0x07 /* Read the data */
+
/**
- * The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h.
+ * The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h.
*/
#define MIN_ACCURATE_DIFF_PRES_PA 12
@@ -105,38 +105,38 @@ class ETSAirspeed : public device::I2C
public:
ETSAirspeed(int bus, int address = I2C_ADDRESS);
virtual ~ETSAirspeed();
-
- virtual int init();
-
- virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
- virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
-
+
+ virtual int init();
+
+ virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
/**
* Diagnostics - print some basic information about the driver.
*/
- void print_info();
-
+ void print_info();
+
protected:
- virtual int probe();
+ virtual int probe();
private:
- work_s _work;
- unsigned _num_reports;
- volatile unsigned _next_report;
- volatile unsigned _oldest_report;
- differential_pressure_s *_reports;
- bool _sensor_ok;
- int _measure_ticks;
- bool _collect_phase;
- int _diff_pres_offset;
-
- orb_advert_t _airspeed_pub;
-
- perf_counter_t _sample_perf;
- perf_counter_t _comms_errors;
- perf_counter_t _buffer_overflows;
-
-
+ work_s _work;
+ unsigned _num_reports;
+ volatile unsigned _next_report;
+ volatile unsigned _oldest_report;
+ differential_pressure_s *_reports;
+ bool _sensor_ok;
+ int _measure_ticks;
+ bool _collect_phase;
+ int _diff_pres_offset;
+
+ orb_advert_t _airspeed_pub;
+
+ perf_counter_t _sample_perf;
+ perf_counter_t _comms_errors;
+ perf_counter_t _buffer_overflows;
+
+
/**
* Test whether the device supported by the driver is present at a
* specific address.
@@ -144,28 +144,28 @@ private:
* @param address The I2C bus address to probe.
* @return True if the device is present.
*/
- int probe_address(uint8_t address);
-
+ int probe_address(uint8_t address);
+
/**
* Initialise the automatic measurement state machine and start it.
*
* @note This function is called at open and error time. It might make sense
* to make it more aggressive about resetting the bus in case of errors.
*/
- void start();
-
+ void start();
+
/**
* Stop the automatic measurement state machine.
*/
- void stop();
-
+ void stop();
+
/**
* Perform a poll cycle; collect from the previous measurement
* and start a new one.
*/
- void cycle();
- int measure();
- int collect();
+ void cycle();
+ int measure();
+ int collect();
/**
* Static trampoline from the workq context; because we don't have a
@@ -173,9 +173,9 @@ private:
*
* @param arg Instance pointer for the driver that is polling.
*/
- static void cycle_trampoline(void *arg);
-
-
+ static void cycle_trampoline(void *arg);
+
+
};
/* helper macro for handling report buffer indices */
@@ -203,7 +203,7 @@ ETSAirspeed::ETSAirspeed(int bus, int address) :
{
// enable debug() calls
_debug_enabled = true;
-
+
// work_cancel in the dtor will explode if we don't do this...
memset(&_work, 0, sizeof(_work));
}
@@ -230,6 +230,7 @@ ETSAirspeed::init()
/* allocate basic report buffers */
_num_reports = 2;
_reports = new struct differential_pressure_s[_num_reports];
+
for (unsigned i = 0; i < _num_reports; i++)
_reports[i].max_differential_pressure_pa = 0;
@@ -351,11 +352,11 @@ ETSAirspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
case SENSORIOCGQUEUEDEPTH:
return _num_reports - 1;
-
+
case SENSORIOCRESET:
/* XXX implement this */
return -EINVAL;
-
+
default:
/* give it to the superclass */
return I2C::ioctl(filp, cmd, arg);
@@ -432,14 +433,14 @@ ETSAirspeed::measure()
uint8_t cmd = READ_CMD;
ret = transfer(&cmd, 1, nullptr, 0);
- if (OK != ret)
- {
+ if (OK != ret) {
perf_count(_comms_errors);
log("i2c::transfer returned %d", ret);
return ret;
}
+
ret = OK;
-
+
return ret;
}
@@ -447,30 +448,31 @@ int
ETSAirspeed::collect()
{
int ret = -EIO;
-
+
/* read from the sensor */
uint8_t val[2] = {0, 0};
-
+
perf_begin(_sample_perf);
-
+
ret = transfer(nullptr, 0, &val[0], 2);
-
+
if (ret < 0) {
log("error reading from sensor: %d", ret);
return ret;
}
-
+
uint16_t diff_pres_pa = val[1] << 8 | val[0];
param_get(param_find("SENS_DPRES_OFF"), &_diff_pres_offset);
-
- if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
+
+ if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
diff_pres_pa = 0;
+
} else {
- diff_pres_pa -= _diff_pres_offset;
+ diff_pres_pa -= _diff_pres_offset;
}
- // XXX we may want to smooth out the readings to remove noise.
+ // XXX we may want to smooth out the readings to remove noise.
_reports[_next_report].timestamp = hrt_absolute_time();
_reports[_next_report].differential_pressure_pa = diff_pres_pa;
@@ -498,7 +500,7 @@ ETSAirspeed::collect()
ret = OK;
perf_end(_sample_perf);
-
+
return ret;
}
@@ -511,17 +513,19 @@ ETSAirspeed::start()
/* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&ETSAirspeed::cycle_trampoline, this, 1);
-
+
/* notify about state change */
struct subsystem_info_s info = {
true,
true,
true,
- SUBSYSTEM_TYPE_DIFFPRESSURE};
+ SUBSYSTEM_TYPE_DIFFPRESSURE
+ };
static orb_advert_t pub = -1;
if (pub > 0) {
orb_publish(ORB_ID(subsystem_info), pub, &info);
+
} else {
pub = orb_advertise(ORB_ID(subsystem_info), &info);
}
@@ -653,8 +657,7 @@ start(int i2c_bus)
fail:
- if (g_dev != nullptr)
- {
+ if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
}
@@ -668,15 +671,14 @@ fail:
void
stop()
{
- if (g_dev != nullptr)
- {
+ if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
- }
- else
- {
+
+ } else {
errx(1, "driver not running");
}
+
exit(0);
}
@@ -773,10 +775,10 @@ info()
} // namespace
-static void
-ets_airspeed_usage()
+static void
+ets_airspeed_usage()
{
- fprintf(stderr, "usage: ets_airspeed [options] command\n");
+ fprintf(stderr, "usage: ets_airspeed command [options]\n");
fprintf(stderr, "options:\n");
fprintf(stderr, "\t-b --bus i2cbus (%d)\n", PX4_I2C_BUS_DEFAULT);
fprintf(stderr, "command:\n");
@@ -789,6 +791,7 @@ ets_airspeed_main(int argc, char *argv[])
int i2c_bus = PX4_I2C_BUS_DEFAULT;
int i;
+
for (i = 1; i < argc; i++) {
if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) {
if (argc > i + 1) {
@@ -802,12 +805,12 @@ ets_airspeed_main(int argc, char *argv[])
*/
if (!strcmp(argv[1], "start"))
ets_airspeed::start(i2c_bus);
-
- /*
- * Stop the driver
- */
- if (!strcmp(argv[1], "stop"))
- ets_airspeed::stop();
+
+ /*
+ * Stop the driver
+ */
+ if (!strcmp(argv[1], "stop"))
+ ets_airspeed::stop();
/*
* Test the driver/device.
diff --git a/src/drivers/hott_telemetry/messages.c b/src/drivers/hott_telemetry/messages.c
index 369070f8c..d2634ef41 100644
--- a/src/drivers/hott_telemetry/messages.c
+++ b/src/drivers/hott_telemetry/messages.c
@@ -44,6 +44,7 @@
#include <string.h>
#include <systemlib/geo/geo.h>
#include <unistd.h>
+#include <uORB/topics/airspeed.h>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/home_position.h>
#include <uORB/topics/sensor_combined.h>
@@ -56,6 +57,7 @@ static int battery_sub = -1;
static int gps_sub = -1;
static int home_sub = -1;
static int sensor_sub = -1;
+static int airspeed_sub = -1;
static bool home_position_set = false;
static double home_lat = 0.0d;
@@ -68,6 +70,7 @@ messages_init(void)
gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
home_sub = orb_subscribe(ORB_ID(home_position));
sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
+ airspeed_sub = orb_subscribe(ORB_ID(airspeed));
}
void
@@ -100,6 +103,16 @@ build_eam_response(uint8_t *buffer, size_t *size)
msg.altitude_L = (uint8_t)alt & 0xff;
msg.altitude_H = (uint8_t)(alt >> 8) & 0xff;
+ /* get a local copy of the airspeed data */
+ struct airspeed_s airspeed;
+ memset(&airspeed, 0, sizeof(airspeed));
+ orb_copy(ORB_ID(airspeed), airspeed_sub, &airspeed);
+
+ uint16_t speed = (uint16_t)(airspeed.indicated_airspeed_m_s);
+ msg.speed_L = (uint8_t)speed & 0xff;
+ msg.speed_H = (uint8_t)(speed >> 8) & 0xff;
+
+
msg.stop = STOP_BYTE;
memcpy(buffer, &msg, *size);
}
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
index 8e18c3c9a..16d5ad626 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -126,7 +126,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
attitude_estimator_ekf_task = task_spawn("attitude_estimator_ekf",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 12400,
+ 14000,
attitude_estimator_ekf_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
diff --git a/src/modules/sdlog2/logbuffer.c b/src/modules/sdlog2/logbuffer.c
index 8aaafaf31..2e1e4fd4d 100644
--- a/src/modules/sdlog2/logbuffer.c
+++ b/src/modules/sdlog2/logbuffer.c
@@ -121,7 +121,7 @@ int logbuffer_get_ptr(struct logbuffer_s *lb, void **ptr, bool *is_part)
} else {
// read pointer is after write pointer, read bytes from read_ptr to end of the buffer
n = lb->size - lb->read_ptr;
- *is_part = true;
+ *is_part = lb->write_ptr > 0;
}
*ptr = &(lb->data[lb->read_ptr]);
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 5a3478665..885155e0d 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -65,6 +65,7 @@
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_controls_effective.h>
@@ -115,35 +116,34 @@ static const int MAX_WRITE_CHUNK = 512;
static const int MIN_BYTES_TO_WRITE = 512;
static const char *mountpoint = "/fs/microsd";
-int log_file = -1;
-int mavlink_fd = -1;
+static int mavlink_fd = -1;
struct logbuffer_s lb;
/* mutex / condition to synchronize threads */
-pthread_mutex_t logbuffer_mutex;
-pthread_cond_t logbuffer_cond;
+static pthread_mutex_t logbuffer_mutex;
+static pthread_cond_t logbuffer_cond;
-char folder_path[64];
+static char folder_path[64];
/* statistics counters */
-unsigned long log_bytes_written = 0;
-uint64_t start_time = 0;
-unsigned long log_msgs_written = 0;
-unsigned long log_msgs_skipped = 0;
+static unsigned long log_bytes_written = 0;
+static uint64_t start_time = 0;
+static unsigned long log_msgs_written = 0;
+static unsigned long log_msgs_skipped = 0;
/* current state of logging */
-bool logging_enabled = false;
+static bool logging_enabled = false;
/* enable logging on start (-e option) */
-bool log_on_start = false;
+static bool log_on_start = false;
/* enable logging when armed (-a option) */
-bool log_when_armed = false;
+static bool log_when_armed = false;
/* delay = 1 / rate (rate defined by -r option) */
-useconds_t sleep_delay = 0;
+static useconds_t sleep_delay = 0;
/* helper flag to track system state changes */
-bool flag_system_armed = false;
+static bool flag_system_armed = false;
-pthread_t logwriter_pthread = 0;
+static pthread_t logwriter_pthread = 0;
/**
* Log buffer writing thread. Open and close file here.
@@ -173,17 +173,17 @@ static void sdlog2_status(void);
/**
* Start logging: create new file and start log writer thread.
*/
-void sdlog2_start_log();
+static void sdlog2_start_log(void);
/**
* Stop logging: stop log writer thread and close log file.
*/
-void sdlog2_stop_log();
+static void sdlog2_stop_log(void);
/**
* Write a header to log file: list of message formats.
*/
-void write_formats(int fd);
+static void write_formats(int fd);
static bool file_exist(const char *filename);
@@ -197,12 +197,12 @@ static void handle_status(struct actuator_safety_s *safety);
/**
* Create folder for current logging session. Store folder name in 'log_folder'.
*/
-static int create_logfolder();
+static int create_logfolder(void);
/**
* Select first free log file name and open it.
*/
-static int open_logfile();
+static int open_logfile(void);
static void
sdlog2_usage(const char *reason)
@@ -242,7 +242,7 @@ int sdlog2_main(int argc, char *argv[])
deamon_task = task_spawn("sdlog2",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT - 30,
- 2048,
+ 3000,
sdlog2_thread_main,
(const char **)argv);
exit(0);
@@ -287,22 +287,6 @@ int create_logfolder()
if (mkdir_ret == 0) {
/* folder does not exist, success */
-
- /* copy parser script file */
- // TODO
- /*
- char mfile_out[100];
- sprintf(mfile_out, "%s/session%04u/run_to_plot_data.m", mountpoint, foldernumber);
- int ret = file_copy(mfile_in, mfile_out);
-
- if (!ret) {
- warnx("copied m file to %s", mfile_out);
-
- } else {
- warnx("failed copying m file from %s to\n %s", mfile_in, mfile_out);
- }
- */
-
break;
} else if (mkdir_ret == -1) {
@@ -404,6 +388,11 @@ static void *logwriter_thread(void *arg)
/* only get pointer to thread-safe data, do heavy I/O a few lines down */
int available = logbuffer_get_ptr(logbuf, &read_ptr, &is_part);
+#ifdef SDLOG2_DEBUG
+ int rp = logbuf->read_ptr;
+ int wp = logbuf->write_ptr;
+#endif
+
/* continue */
pthread_mutex_unlock(&logbuffer_mutex);
@@ -420,7 +409,7 @@ static void *logwriter_thread(void *arg)
should_wait = (n == available) && !is_part;
#ifdef SDLOG2_DEBUG
- printf("%i wrote: %i of %i, is_part=%i, should_wait=%i", poll_count, n, available, (int)is_part, (int)should_wait);
+ printf("write %i %i of %i rp=%i wp=%i, is_part=%i, should_wait=%i\n", log_bytes_written, n, available, rp, wp, (int)is_part, (int)should_wait);
#endif
if (n < 0) {
@@ -433,14 +422,14 @@ static void *logwriter_thread(void *arg)
}
} else {
+ n = 0;
should_wait = true;
}
- if (poll_count % 10 == 0) {
+ if (++poll_count == 10) {
fsync(log_file);
+ poll_count = 0;
}
-
- poll_count++;
}
fsync(log_file);
@@ -609,9 +598,6 @@ int sdlog2_thread_main(int argc, char *argv[])
errx(1, "can't allocate log buffer, exiting.");
}
- /* file descriptors to wait for */
- struct pollfd fds_control[2];
-
/* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */
/* number of messages */
const ssize_t fdsc = 17;
@@ -633,6 +619,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct sensor_combined_s sensor;
struct vehicle_attitude_s att;
struct vehicle_attitude_setpoint_s att_sp;
+ struct vehicle_rates_setpoint_s rates_sp;
struct actuator_outputs_s act_outputs;
struct actuator_controls_s act_controls;
struct actuator_controls_effective_s act_controls_effective;
@@ -656,6 +643,7 @@ int sdlog2_thread_main(int argc, char *argv[])
int sensor_sub;
int att_sub;
int att_sp_sub;
+ int rates_sp_sub;
int act_outputs_sub;
int act_controls_sub;
int act_controls_effective_sub;
@@ -667,6 +655,7 @@ int sdlog2_thread_main(int argc, char *argv[])
int control_debug_sub;
int flow_sub;
int rc_sub;
+ int airspeed_sub;
} subs;
/* log message buffer: header + body */
@@ -687,6 +676,8 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_CTRL_s log_CTRL;
struct log_RC_s log_RC;
struct log_OUT0_s log_OUT0;
+ struct log_AIRS_s log_AIRS;
+ struct log_ARSP_s log_ARSP;
} body;
} log_msg = {
LOG_PACKET_HEADER_INIT(0)
@@ -736,6 +727,12 @@ int sdlog2_thread_main(int argc, char *argv[])
fds[fdsc_count].events = POLLIN;
fdsc_count++;
+ /* --- RATES SETPOINT --- */
+ subs.rates_sp_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint));
+ fds[fdsc_count].fd = subs.rates_sp_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
/* --- ACTUATOR OUTPUTS --- */
subs.act_outputs_sub = orb_subscribe(ORB_ID_VEHICLE_CONTROLS);
fds[fdsc_count].fd = subs.act_outputs_sub;
@@ -796,6 +793,12 @@ int sdlog2_thread_main(int argc, char *argv[])
fds[fdsc_count].events = POLLIN;
fdsc_count++;
+ /* --- AIRSPEED --- */
+ subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed));
+ fds[fdsc_count].fd = subs.airspeed_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
/* WARNING: If you get the error message below,
* then the number of registered messages (fdsc)
* differs from the number of messages in the above list.
@@ -921,7 +924,7 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_GPS.epv = buf.gps_pos.epv_m;
log_msg.body.log_GPS.lat = buf.gps_pos.lat;
log_msg.body.log_GPS.lon = buf.gps_pos.lon;
- log_msg.body.log_GPS.alt = buf.gps_pos.alt * 0.001;
+ log_msg.body.log_GPS.alt = buf.gps_pos.alt * 0.001f;
log_msg.body.log_GPS.vel_n = buf.gps_pos.vel_n_m_s;
log_msg.body.log_GPS.vel_e = buf.gps_pos.vel_e_m_s;
log_msg.body.log_GPS.vel_d = buf.gps_pos.vel_d_m_s;
@@ -991,6 +994,9 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_ATT.roll = buf.att.roll;
log_msg.body.log_ATT.pitch = buf.att.pitch;
log_msg.body.log_ATT.yaw = buf.att.yaw;
+ log_msg.body.log_ATT.roll_rate = buf.att.rollspeed;
+ log_msg.body.log_ATT.pitch_rate = buf.att.pitchspeed;
+ log_msg.body.log_ATT.yaw_rate = buf.att.yawspeed;
LOGBUFFER_WRITE_AND_COUNT(ATT);
}
@@ -1001,9 +1007,20 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_ATSP.roll_sp = buf.att_sp.roll_body;
log_msg.body.log_ATSP.pitch_sp = buf.att_sp.pitch_body;
log_msg.body.log_ATSP.yaw_sp = buf.att_sp.yaw_body;
+ log_msg.body.log_ATSP.thrust_sp = buf.att_sp.thrust;
LOGBUFFER_WRITE_AND_COUNT(ATSP);
}
+ /* --- RATES SETPOINT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_rates_setpoint), subs.rates_sp_sub, &buf.rates_sp);
+ log_msg.msg_type = LOG_ARSP_MSG;
+ log_msg.body.log_ARSP.roll_rate_sp = buf.rates_sp.roll;
+ log_msg.body.log_ARSP.pitch_rate_sp = buf.rates_sp.pitch;
+ log_msg.body.log_ARSP.yaw_rate_sp = buf.rates_sp.yaw;
+ LOGBUFFER_WRITE_AND_COUNT(ARSP);
+ }
+
/* --- ACTUATOR OUTPUTS --- */
if (fds[ifds++].revents & POLLIN) {
orb_copy(ORB_ID(actuator_outputs_0), subs.act_outputs_sub, &buf.act_outputs);
@@ -1105,10 +1122,22 @@ int sdlog2_thread_main(int argc, char *argv[])
LOGBUFFER_WRITE_AND_COUNT(RC);
}
+ /* --- AIRSPEED --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(airspeed), subs.airspeed_sub, &buf.airspeed);
+ log_msg.msg_type = LOG_AIRS_MSG;
+ log_msg.body.log_AIRS.indicated_airspeed = buf.airspeed.indicated_airspeed_m_s;
+ log_msg.body.log_AIRS.true_airspeed = buf.airspeed.true_airspeed_m_s;
+ LOGBUFFER_WRITE_AND_COUNT(AIRS);
+ }
+
+#ifdef SDLOG2_DEBUG
+ printf("fill rp=%i wp=%i count=%i\n", lb.read_ptr, lb.write_ptr, logbuffer_count(&lb));
+#endif
/* signal the other thread new data, but not yet unlock */
if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) {
#ifdef SDLOG2_DEBUG
- printf("signal %i", logbuffer_count(&lb));
+ printf("signal rp=%i wp=%i count=%i\n", lb.read_ptr, lb.write_ptr, logbuffer_count(&lb));
#endif
/* only request write if several packets can be written at once */
pthread_cond_signal(&logbuffer_cond);
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 98a64ef21..a83a72514 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -60,6 +60,9 @@ struct log_ATT_s {
float roll;
float pitch;
float yaw;
+ float roll_rate;
+ float pitch_rate;
+ float yaw_rate;
};
/* --- ATSP - ATTITUDE SET POINT --- */
@@ -68,6 +71,7 @@ struct log_ATSP_s {
float roll_sp;
float pitch_sp;
float yaw_sp;
+ float thrust_sp;
};
/* --- IMU - IMU SENSORS --- */
@@ -184,14 +188,29 @@ struct log_RC_s {
struct log_OUT0_s {
float output[8];
};
+
+/* --- AIRS - AIRSPEED --- */
+#define LOG_AIRS_MSG 13
+struct log_AIRS_s {
+ float indicated_airspeed;
+ float true_airspeed;
+};
+
+/* --- ARSP - ATTITUDE RATE SET POINT --- */
+#define LOG_ARSP_MSG 14
+struct log_ARSP_s {
+ float roll_rate_sp;
+ float pitch_rate_sp;
+ float yaw_rate_sp;
+};
#pragma pack(pop)
/* construct list of all message formats */
static const struct log_format_s log_formats[] = {
LOG_FORMAT(TIME, "Q", "StartTime"),
- LOG_FORMAT(ATT, "fff", "Roll,Pitch,Yaw"),
- LOG_FORMAT(ATSP, "fff", "RollSP,PitchSP,YawSP"),
+ LOG_FORMAT(ATT, "ffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate"),
+ LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"),
LOG_FORMAT(LPOS, "fffffffLLf", "X,Y,Z,VX,VY,VZ,Heading,HomeLat,HomeLon,HomeAlt"),
@@ -202,6 +221,8 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(CTRL, "ffffffffffff", "RP,RI,RD,RRP,RRI,RRD,PP,PI,PD,PRP,PRI,PRD"),
LOG_FORMAT(RC, "ffffffff", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7"),
LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
+ LOG_FORMAT(AIRS, "ff", "IndSpeed,TrueSpeed"),
+ LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
};
static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s);