Browse Source

Merge branch 'master' into seatbelt_multirotor

sbg
Anton Babushkin 12 years ago
parent
commit
95d324f061
  1. 157
      src/drivers/ets_airspeed/ets_airspeed.cpp
  2. 13
      src/drivers/hott_telemetry/messages.c
  3. 2
      src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
  4. 19
      src/modules/sdlog2/sdlog2.c
  5. 9
      src/modules/sdlog2/sdlog2_messages.h

157
src/drivers/ets_airspeed/ets_airspeed.cpp

@ -37,7 +37,7 @@
* *
* Driver for the Eagle Tree Airspeed V3 connected via I2C. * Driver for the Eagle Tree Airspeed V3 connected via I2C.
*/ */
#include <nuttx/config.h> #include <nuttx/config.h>
#include <drivers/device/i2c.h> #include <drivers/device/i2c.h>
@ -77,13 +77,13 @@
#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION #define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION
/* I2C bus address */ /* 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 */ /* 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 #define MIN_ACCURATE_DIFF_PRES_PA 12
@ -105,38 +105,38 @@ class ETSAirspeed : public device::I2C
public: public:
ETSAirspeed(int bus, int address = I2C_ADDRESS); ETSAirspeed(int bus, int address = I2C_ADDRESS);
virtual ~ETSAirspeed(); virtual ~ETSAirspeed();
virtual int init(); virtual int init();
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen); 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 ioctl(struct file *filp, int cmd, unsigned long arg);
/** /**
* Diagnostics - print some basic information about the driver. * Diagnostics - print some basic information about the driver.
*/ */
void print_info(); void print_info();
protected: protected:
virtual int probe(); virtual int probe();
private: private:
work_s _work; work_s _work;
unsigned _num_reports; unsigned _num_reports;
volatile unsigned _next_report; volatile unsigned _next_report;
volatile unsigned _oldest_report; volatile unsigned _oldest_report;
differential_pressure_s *_reports; differential_pressure_s *_reports;
bool _sensor_ok; bool _sensor_ok;
int _measure_ticks; int _measure_ticks;
bool _collect_phase; bool _collect_phase;
int _diff_pres_offset; int _diff_pres_offset;
orb_advert_t _airspeed_pub; orb_advert_t _airspeed_pub;
perf_counter_t _sample_perf; perf_counter_t _sample_perf;
perf_counter_t _comms_errors; perf_counter_t _comms_errors;
perf_counter_t _buffer_overflows; perf_counter_t _buffer_overflows;
/** /**
* Test whether the device supported by the driver is present at a * Test whether the device supported by the driver is present at a
* specific address. * specific address.
@ -144,28 +144,28 @@ private:
* @param address The I2C bus address to probe. * @param address The I2C bus address to probe.
* @return True if the device is present. * @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. * Initialise the automatic measurement state machine and start it.
* *
* @note This function is called at open and error time. It might make sense * @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. * to make it more aggressive about resetting the bus in case of errors.
*/ */
void start(); void start();
/** /**
* Stop the automatic measurement state machine. * Stop the automatic measurement state machine.
*/ */
void stop(); void stop();
/** /**
* Perform a poll cycle; collect from the previous measurement * Perform a poll cycle; collect from the previous measurement
* and start a new one. * and start a new one.
*/ */
void cycle(); void cycle();
int measure(); int measure();
int collect(); int collect();
/** /**
* Static trampoline from the workq context; because we don't have a * 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. * @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 */ /* helper macro for handling report buffer indices */
@ -203,7 +203,7 @@ ETSAirspeed::ETSAirspeed(int bus, int address) :
{ {
// enable debug() calls // enable debug() calls
_debug_enabled = true; _debug_enabled = true;
// work_cancel in the dtor will explode if we don't do this... // work_cancel in the dtor will explode if we don't do this...
memset(&_work, 0, sizeof(_work)); memset(&_work, 0, sizeof(_work));
} }
@ -230,6 +230,7 @@ ETSAirspeed::init()
/* allocate basic report buffers */ /* allocate basic report buffers */
_num_reports = 2; _num_reports = 2;
_reports = new struct differential_pressure_s[_num_reports]; _reports = new struct differential_pressure_s[_num_reports];
for (unsigned i = 0; i < _num_reports; i++) for (unsigned i = 0; i < _num_reports; i++)
_reports[i].max_differential_pressure_pa = 0; _reports[i].max_differential_pressure_pa = 0;
@ -351,11 +352,11 @@ ETSAirspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
case SENSORIOCGQUEUEDEPTH: case SENSORIOCGQUEUEDEPTH:
return _num_reports - 1; return _num_reports - 1;
case SENSORIOCRESET: case SENSORIOCRESET:
/* XXX implement this */ /* XXX implement this */
return -EINVAL; return -EINVAL;
default: default:
/* give it to the superclass */ /* give it to the superclass */
return I2C::ioctl(filp, cmd, arg); return I2C::ioctl(filp, cmd, arg);
@ -432,14 +433,14 @@ ETSAirspeed::measure()
uint8_t cmd = READ_CMD; uint8_t cmd = READ_CMD;
ret = transfer(&cmd, 1, nullptr, 0); ret = transfer(&cmd, 1, nullptr, 0);
if (OK != ret) if (OK != ret) {
{
perf_count(_comms_errors); perf_count(_comms_errors);
log("i2c::transfer returned %d", ret); log("i2c::transfer returned %d", ret);
return ret; return ret;
} }
ret = OK; ret = OK;
return ret; return ret;
} }
@ -447,30 +448,31 @@ int
ETSAirspeed::collect() ETSAirspeed::collect()
{ {
int ret = -EIO; int ret = -EIO;
/* read from the sensor */ /* read from the sensor */
uint8_t val[2] = {0, 0}; uint8_t val[2] = {0, 0};
perf_begin(_sample_perf); perf_begin(_sample_perf);
ret = transfer(nullptr, 0, &val[0], 2); ret = transfer(nullptr, 0, &val[0], 2);
if (ret < 0) { if (ret < 0) {
log("error reading from sensor: %d", ret); log("error reading from sensor: %d", ret);
return ret; return ret;
} }
uint16_t diff_pres_pa = val[1] << 8 | val[0]; uint16_t diff_pres_pa = val[1] << 8 | val[0];
param_get(param_find("SENS_DPRES_OFF"), &_diff_pres_offset); 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; diff_pres_pa = 0;
} else { } 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].timestamp = hrt_absolute_time();
_reports[_next_report].differential_pressure_pa = diff_pres_pa; _reports[_next_report].differential_pressure_pa = diff_pres_pa;
@ -498,7 +500,7 @@ ETSAirspeed::collect()
ret = OK; ret = OK;
perf_end(_sample_perf); perf_end(_sample_perf);
return ret; return ret;
} }
@ -511,17 +513,19 @@ ETSAirspeed::start()
/* schedule a cycle to start things */ /* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&ETSAirspeed::cycle_trampoline, this, 1); work_queue(HPWORK, &_work, (worker_t)&ETSAirspeed::cycle_trampoline, this, 1);
/* notify about state change */ /* notify about state change */
struct subsystem_info_s info = { struct subsystem_info_s info = {
true, true,
true, true,
true, true,
SUBSYSTEM_TYPE_DIFFPRESSURE}; SUBSYSTEM_TYPE_DIFFPRESSURE
};
static orb_advert_t pub = -1; static orb_advert_t pub = -1;
if (pub > 0) { if (pub > 0) {
orb_publish(ORB_ID(subsystem_info), pub, &info); orb_publish(ORB_ID(subsystem_info), pub, &info);
} else { } else {
pub = orb_advertise(ORB_ID(subsystem_info), &info); pub = orb_advertise(ORB_ID(subsystem_info), &info);
} }
@ -653,8 +657,7 @@ start(int i2c_bus)
fail: fail:
if (g_dev != nullptr) if (g_dev != nullptr) {
{
delete g_dev; delete g_dev;
g_dev = nullptr; g_dev = nullptr;
} }
@ -668,15 +671,14 @@ fail:
void void
stop() stop()
{ {
if (g_dev != nullptr) if (g_dev != nullptr) {
{
delete g_dev; delete g_dev;
g_dev = nullptr; g_dev = nullptr;
}
else } else {
{
errx(1, "driver not running"); errx(1, "driver not running");
} }
exit(0); exit(0);
} }
@ -773,10 +775,10 @@ info()
} // namespace } // namespace
static void static void
ets_airspeed_usage() 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, "options:\n");
fprintf(stderr, "\t-b --bus i2cbus (%d)\n", PX4_I2C_BUS_DEFAULT); fprintf(stderr, "\t-b --bus i2cbus (%d)\n", PX4_I2C_BUS_DEFAULT);
fprintf(stderr, "command:\n"); fprintf(stderr, "command:\n");
@ -789,6 +791,7 @@ ets_airspeed_main(int argc, char *argv[])
int i2c_bus = PX4_I2C_BUS_DEFAULT; int i2c_bus = PX4_I2C_BUS_DEFAULT;
int i; int i;
for (i = 1; i < argc; i++) { for (i = 1; i < argc; i++) {
if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) { if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) {
if (argc > i + 1) { if (argc > i + 1) {
@ -802,12 +805,12 @@ ets_airspeed_main(int argc, char *argv[])
*/ */
if (!strcmp(argv[1], "start")) if (!strcmp(argv[1], "start"))
ets_airspeed::start(i2c_bus); ets_airspeed::start(i2c_bus);
/* /*
* Stop the driver * Stop the driver
*/ */
if (!strcmp(argv[1], "stop")) if (!strcmp(argv[1], "stop"))
ets_airspeed::stop(); ets_airspeed::stop();
/* /*
* Test the driver/device. * Test the driver/device.

13
src/drivers/hott_telemetry/messages.c

@ -44,6 +44,7 @@
#include <string.h> #include <string.h>
#include <systemlib/geo/geo.h> #include <systemlib/geo/geo.h>
#include <unistd.h> #include <unistd.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/battery_status.h> #include <uORB/topics/battery_status.h>
#include <uORB/topics/home_position.h> #include <uORB/topics/home_position.h>
#include <uORB/topics/sensor_combined.h> #include <uORB/topics/sensor_combined.h>
@ -56,6 +57,7 @@ static int battery_sub = -1;
static int gps_sub = -1; static int gps_sub = -1;
static int home_sub = -1; static int home_sub = -1;
static int sensor_sub = -1; static int sensor_sub = -1;
static int airspeed_sub = -1;
static bool home_position_set = false; static bool home_position_set = false;
static double home_lat = 0.0d; static double home_lat = 0.0d;
@ -68,6 +70,7 @@ messages_init(void)
gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
home_sub = orb_subscribe(ORB_ID(home_position)); home_sub = orb_subscribe(ORB_ID(home_position));
sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
airspeed_sub = orb_subscribe(ORB_ID(airspeed));
} }
void void
@ -100,6 +103,16 @@ build_eam_response(uint8_t *buffer, size_t *size)
msg.altitude_L = (uint8_t)alt & 0xff; msg.altitude_L = (uint8_t)alt & 0xff;
msg.altitude_H = (uint8_t)(alt >> 8) & 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; msg.stop = STOP_BYTE;
memcpy(buffer, &msg, *size); memcpy(buffer, &msg, *size);
} }

2
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", attitude_estimator_ekf_task = task_spawn("attitude_estimator_ekf",
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5, SCHED_PRIORITY_MAX - 5,
12400, 14000,
attitude_estimator_ekf_thread_main, attitude_estimator_ekf_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL); (argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0); exit(0);

19
src/modules/sdlog2/sdlog2.c

@ -241,7 +241,7 @@ int sdlog2_main(int argc, char *argv[])
deamon_task = task_spawn("sdlog2", deamon_task = task_spawn("sdlog2",
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT - 30, SCHED_PRIORITY_DEFAULT - 30,
2048, 3000,
sdlog2_thread_main, sdlog2_thread_main,
(const char **)argv); (const char **)argv);
exit(0); exit(0);
@ -661,6 +661,7 @@ int sdlog2_thread_main(int argc, char *argv[])
int vicon_pos_sub; int vicon_pos_sub;
int flow_sub; int flow_sub;
int rc_sub; int rc_sub;
int airspeed_sub;
} subs; } subs;
/* log message buffer: header + body */ /* log message buffer: header + body */
@ -681,6 +682,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_RC_s log_RC; struct log_RC_s log_RC;
struct log_OUT0_s log_OUT0; struct log_OUT0_s log_OUT0;
struct log_ARSP_s log_ARSP; struct log_ARSP_s log_ARSP;
struct log_AIRS_s log_AIRS;
} body; } body;
} log_msg = { } log_msg = {
LOG_PACKET_HEADER_INIT(0) LOG_PACKET_HEADER_INIT(0)
@ -784,6 +786,12 @@ int sdlog2_thread_main(int argc, char *argv[])
fds[fdsc_count].events = POLLIN; fds[fdsc_count].events = POLLIN;
fdsc_count++; 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, /* WARNING: If you get the error message below,
* then the number of registered messages (fdsc) * then the number of registered messages (fdsc)
* differs from the number of messages in the above list. * differs from the number of messages in the above list.
@ -1069,6 +1077,15 @@ int sdlog2_thread_main(int argc, char *argv[])
LOGBUFFER_WRITE_AND_COUNT(RC); 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);
}
/* signal the other thread new data, but not yet unlock */ /* signal the other thread new data, but not yet unlock */
if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) { if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) {
#ifdef SDLOG2_DEBUG #ifdef SDLOG2_DEBUG

9
src/modules/sdlog2/sdlog2_messages.h

@ -178,6 +178,13 @@ struct log_ARSP_s {
float pitch_rate_sp; float pitch_rate_sp;
float yaw_rate_sp; float yaw_rate_sp;
}; };
/* --- AIRS - AIRSPEED --- */
#define LOG_AIRS_MSG 13
struct log_AIRS_s {
float indicated_airspeed;
float true_airspeed;
};
#pragma pack(pop) #pragma pack(pop)
/* construct list of all message formats */ /* construct list of all message formats */
@ -195,7 +202,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(STAT, "BBBBBfffB", "State,FlightMode,CtlMode,SASMode,Armed,BatV,BatC,BatRem,BatWarn"), LOG_FORMAT(STAT, "BBBBBfffB", "State,FlightMode,CtlMode,SASMode,Armed,BatV,BatC,BatRem,BatWarn"),
LOG_FORMAT(RC, "ffffffff", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7"), 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(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"), LOG_FORMAT(AIRS, "ff", "IndSpeed,TrueSpeed"),
}; };
static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s); static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s);

Loading…
Cancel
Save