From 95236c379a3b0a551f5ac26387356ecad0a82d60 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 13 Jun 2013 06:51:09 +0400 Subject: [PATCH 01/13] sdlog2: ARSP (attitude rates setpoint) message added, attitude rates added to ATT message --- src/modules/sdlog2/sdlog2.c | 25 ++++++++++++++++++++++++- src/modules/sdlog2/sdlog2_messages.h | 14 +++++++++++++- 2 files changed, 37 insertions(+), 2 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index a14bd6f80e..ca6ab59346 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -64,6 +64,7 @@ #include #include #include +#include #include #include #include @@ -612,7 +613,7 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */ /* number of messages */ - const ssize_t fdsc = 15; + const ssize_t fdsc = 16; /* Sanity check variable and index */ ssize_t fdsc_count = 0; /* file descriptors to wait for */ @@ -627,6 +628,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; @@ -648,6 +650,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; @@ -677,6 +680,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct log_STAT_s log_STAT; struct log_RC_s log_RC; struct log_OUT0_s log_OUT0; + struct log_ARSP_s log_ARSP; } body; } log_msg = { LOG_PACKET_HEADER_INIT(0) @@ -720,6 +724,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; @@ -953,6 +963,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); } @@ -966,6 +979,16 @@ int sdlog2_thread_main(int argc, char *argv[]) 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); diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 40763ee1e0..48322e0b6e 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 --- */ @@ -167,13 +170,21 @@ struct log_RC_s { struct log_OUT0_s { float output[8]; }; + +/* --- ARSP - ATTITUDE RATE SET POINT --- */ +#define LOG_ARSP_MSG 13 +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(ATT, "ffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate"), LOG_FORMAT(ATSP, "fff", "RollSP,PitchSP,YawSP"), LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"), LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"), @@ -184,6 +195,7 @@ static const struct log_format_s log_formats[] = { 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(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"), + LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"), }; static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s); From 12ac41802e663e5d9328c294df4117269764ef2a Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sat, 15 Jun 2013 22:58:14 +0200 Subject: [PATCH 02/13] Log airspeed. --- src/modules/sdlog2/sdlog2.c | 17 +++++++++++++++++ src/modules/sdlog2/sdlog2_messages.h | 8 ++++++++ 2 files changed, 25 insertions(+) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index a14bd6f80e..b79a07b976 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -658,6 +658,7 @@ int sdlog2_thread_main(int argc, char *argv[]) int vicon_pos_sub; int flow_sub; int rc_sub; + int airspeed_sub; } subs; /* log message buffer: header + body */ @@ -677,6 +678,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct log_STAT_s log_STAT; struct log_RC_s log_RC; struct log_OUT0_s log_OUT0; + struct log_AIRS_s log_AIRS; } body; } log_msg = { LOG_PACKET_HEADER_INIT(0) @@ -774,6 +776,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. @@ -1046,6 +1054,15 @@ 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); + } + /* signal the other thread new data, but not yet unlock */ if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) { #ifdef SDLOG2_DEBUG diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 40763ee1e0..c71f3b7e85 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -167,6 +167,13 @@ 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; +}; #pragma pack(pop) /* construct list of all message formats */ @@ -184,6 +191,7 @@ static const struct log_format_s log_formats[] = { 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(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"), + LOG_FORMAT(AIRS, "ff", "IndSpeed,TrueSpeed"), }; static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s); From 4253c16b3f3eeb9ed05d2b80c8ce9531a11ffad3 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sat, 15 Jun 2013 23:24:57 +0200 Subject: [PATCH 03/13] Increase array size. --- src/modules/sdlog2/sdlog2.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index b79a07b976..fee20cea40 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -612,7 +612,7 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */ /* number of messages */ - const ssize_t fdsc = 15; + const ssize_t fdsc = 16; /* Sanity check variable and index */ ssize_t fdsc_count = 0; /* file descriptors to wait for */ From 138ce117ab0a9b95f473f34ce8644fa6456b32a6 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 16 Jun 2013 17:20:07 +0400 Subject: [PATCH 04/13] ATSP.ThrustSP added --- src/modules/sdlog2/sdlog2.c | 1 + src/modules/sdlog2/sdlog2_messages.h | 3 ++- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index ca6ab59346..f67cfad879 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -976,6 +976,7 @@ 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); } diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 48322e0b6e..fc5687988c 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -71,6 +71,7 @@ struct log_ATSP_s { float roll_sp; float pitch_sp; float yaw_sp; + float thrust_sp; }; /* --- IMU - IMU SENSORS --- */ @@ -185,7 +186,7 @@ struct log_ARSP_s { static const struct log_format_s log_formats[] = { LOG_FORMAT(TIME, "Q", "StartTime"), LOG_FORMAT(ATT, "ffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate"), - LOG_FORMAT(ATSP, "fff", "RollSP,PitchSP,YawSP"), + 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"), From dadac932da6fe2e45cfc6ed135beed9e6adff1b0 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sun, 16 Jun 2013 20:44:11 +0200 Subject: [PATCH 05/13] Report airspeed over HoTT telemetry --- src/drivers/hott_telemetry/messages.c | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/src/drivers/hott_telemetry/messages.c b/src/drivers/hott_telemetry/messages.c index 369070f8c4..d2634ef41a 100644 --- a/src/drivers/hott_telemetry/messages.c +++ b/src/drivers/hott_telemetry/messages.c @@ -44,6 +44,7 @@ #include #include #include +#include #include #include #include @@ -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); } From 1fc3c8f7234b281a570f578b4600dcd75b06346b Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sun, 16 Jun 2013 20:52:15 +0200 Subject: [PATCH 06/13] Fix usage help and cleanup formatting --- src/drivers/ets_airspeed/ets_airspeed.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index e50395e479..b1d9a1cb93 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -80,7 +80,7 @@ #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. @@ -470,7 +470,7 @@ ETSAirspeed::collect() 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; @@ -597,7 +597,7 @@ ETSAirspeed::print_info() perf_print_counter(_buffer_overflows); printf("poll interval: %u ticks\n", _measure_ticks); printf("report queue: %u (%u/%u @ %p)\n", - _num_reports, _oldest_report, _next_report, _reports); + _num_reports, _oldest_report, _next_report, _reports); } /** @@ -776,7 +776,7 @@ info() 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"); From 7a99de9d304dd56246917ab2966970b7c6fa4214 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sun, 16 Jun 2013 21:07:42 +0200 Subject: [PATCH 07/13] More formatting cleanups --- src/drivers/ets_airspeed/ets_airspeed.cpp | 135 +++++++++++----------- 1 file changed, 69 insertions(+), 66 deletions(-) diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index b1d9a1cb93..adabc15252 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 #include @@ -81,9 +81,9 @@ /* Register address */ #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); - + /** * Diagnostics - print some basic information about the driver. */ void print_info(); - + protected: virtual int probe(); private: - work_s _work; - unsigned _num_reports; - volatile unsigned _next_report; - volatile unsigned _oldest_report; + 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; + 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; - 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,27 +448,28 @@ 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. @@ -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); } @@ -597,7 +601,7 @@ ETSAirspeed::print_info() perf_print_counter(_buffer_overflows); printf("poll interval: %u ticks\n", _measure_ticks); printf("report queue: %u (%u/%u @ %p)\n", - _num_reports, _oldest_report, _next_report, _reports); + _num_reports, _oldest_report, _next_report, _reports); } /** @@ -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,8 +775,8 @@ info() } // namespace -static void -ets_airspeed_usage() +static void +ets_airspeed_usage() { fprintf(stderr, "usage: ets_airspeed command [options]\n"); fprintf(stderr, "options:\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. From 24cb66c8330ecc2c04c541a92322ba7339d49b87 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sun, 16 Jun 2013 21:17:07 +0200 Subject: [PATCH 08/13] And yet more formatting cleanups --- src/drivers/ets_airspeed/ets_airspeed.cpp | 52 +++++++++++------------ 1 file changed, 26 insertions(+), 26 deletions(-) diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index adabc15252..c39da98d70 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -77,10 +77,10 @@ #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. @@ -106,35 +106,35 @@ public: ETSAirspeed(int bus, int address = I2C_ADDRESS); virtual ~ETSAirspeed(); - virtual int init(); + 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 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; + 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; + orb_advert_t _airspeed_pub; - perf_counter_t _sample_perf; - perf_counter_t _comms_errors; - perf_counter_t _buffer_overflows; + perf_counter_t _sample_perf; + perf_counter_t _comms_errors; + perf_counter_t _buffer_overflows; /** @@ -152,20 +152,20 @@ private: * @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,7 +173,7 @@ private: * * @param arg Instance pointer for the driver that is polling. */ - static void cycle_trampoline(void *arg); + static void cycle_trampoline(void *arg); }; From badaa5e4a23561834ff4badbe3a62fbf3d3e02aa Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 17 Jun 2013 09:57:34 +0200 Subject: [PATCH 09/13] Fixed too low stack sizes --- .../attitude_estimator_ekf/attitude_estimator_ekf_main.cpp | 2 +- src/modules/sdlog2/sdlog2.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) 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 8e18c3c9a7..16d5ad6262 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/sdlog2.c b/src/modules/sdlog2/sdlog2.c index fee20cea40..8c0788ae62 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -240,7 +240,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); From d9f30858c88f6613808d1781ce06058e88e40fa9 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Jun 2013 14:46:18 +0400 Subject: [PATCH 10/13] sdlog2 messages ID fix --- src/modules/sdlog2/sdlog2_messages.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index efb999a509..7f7bf60535 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -180,7 +180,7 @@ struct log_AIRS_s { }; /* --- ARSP - ATTITUDE RATE SET POINT --- */ -#define LOG_ARSP_MSG 13 +#define LOG_ARSP_MSG 14 struct log_ARSP_s { float roll_rate_sp; float pitch_rate_sp; From a11895ac43b4e345ebd04d9999f386bc1408b98e Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Jun 2013 16:06:35 +0400 Subject: [PATCH 11/13] Critical bug fixed, cleanup --- src/modules/sdlog2/logbuffer.c | 2 +- src/modules/sdlog2/sdlog2.c | 80 +++++++++++++++------------------- 2 files changed, 35 insertions(+), 47 deletions(-) diff --git a/src/modules/sdlog2/logbuffer.c b/src/modules/sdlog2/logbuffer.c index 8aaafaf316..2e1e4fd4da 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 178986f610..6715b57f5e 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -114,35 +114,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. @@ -172,17 +171,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); @@ -196,12 +195,12 @@ static void handle_status(struct vehicle_status_s *cmd); /** * 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) @@ -286,22 +285,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) { @@ -403,6 +386,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); @@ -419,7 +407,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) { @@ -432,14 +420,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); @@ -608,12 +596,9 @@ 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 = 16; + const ssize_t fdsc = 17; /* Sanity check variable and index */ ssize_t fdsc_count = 0; /* file descriptors to wait for */ @@ -901,7 +886,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; @@ -1087,10 +1072,13 @@ int sdlog2_thread_main(int argc, char *argv[]) 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); From 447fc5e291b110b0fa1e55c7ace294968c28c5ef Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 18 Jun 2013 10:31:24 +0400 Subject: [PATCH 12/13] sdlog2 bugs fixed --- src/modules/sdlog2/sdlog2.c | 50 ++++++++++++++++++++++++------------- 1 file changed, 33 insertions(+), 17 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 6715b57f5e..c543fb1b4c 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -103,7 +103,7 @@ //#define SDLOG2_DEBUG -static bool thread_should_exit = false; /**< Deamon exit flag */ +static bool main_thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ static int deamon_task; /**< Handle of deamon task / thread */ static bool logwriter_should_exit = false; /**< Logwriter thread exit flag */ @@ -236,7 +236,7 @@ int sdlog2_main(int argc, char *argv[]) exit(0); } - thread_should_exit = false; + main_thread_should_exit = false; deamon_task = task_spawn("sdlog2", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT - 30, @@ -251,7 +251,7 @@ int sdlog2_main(int argc, char *argv[]) printf("\tsdlog2 is not started\n"); } - thread_should_exit = true; + main_thread_should_exit = true; exit(0); } @@ -330,10 +330,10 @@ int open_logfile() fd = open(path_buf, O_CREAT | O_WRONLY | O_DSYNC); if (fd == 0) { - errx(1, "opening %s failed.", path_buf); + warn("opening %s failed", path_buf); } - warnx("logging to: %s", path_buf); + warnx("logging to: %s.", path_buf); mavlink_log_info(mavlink_fd, "[sdlog2] log: %s", path_buf); return fd; @@ -341,7 +341,7 @@ int open_logfile() if (file_number > MAX_NO_LOGFILE) { /* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */ - warn("all %d possible files exist already", MAX_NO_LOGFILE); + warnx("all %d possible files exist already.", MAX_NO_LOGFILE); return -1; } @@ -367,8 +367,7 @@ static void *logwriter_thread(void *arg) bool should_wait = false; bool is_part = false; - while (!thread_should_exit && !logwriter_should_exit) { - + while (true) { /* make sure threads are synchronized */ pthread_mutex_lock(&logbuffer_mutex); @@ -378,7 +377,7 @@ static void *logwriter_thread(void *arg) } /* only wait if no data is available to process */ - if (should_wait) { + if (should_wait && !logwriter_should_exit) { /* blocking wait for new data at this line */ pthread_cond_wait(&logbuffer_cond, &logbuffer_mutex); } @@ -411,7 +410,7 @@ static void *logwriter_thread(void *arg) #endif if (n < 0) { - thread_should_exit = true; + main_thread_should_exit = true; err(1, "error writing log file"); } @@ -421,6 +420,16 @@ static void *logwriter_thread(void *arg) } else { n = 0; +#ifdef SDLOG2_DEBUG + printf("no data available, main_thread_should_exit=%i, logwriter_should_exit=%i\n", (int)main_thread_should_exit, (int)logwriter_should_exit); +#endif + /* exit only with empty buffer */ + if (main_thread_should_exit || logwriter_should_exit) { +#ifdef SDLOG2_DEBUG + printf("break logwriter thread\n"); +#endif + break; + } should_wait = true; } @@ -433,6 +442,10 @@ static void *logwriter_thread(void *arg) fsync(log_file); close(log_file); +#ifdef SDLOG2_DEBUG + printf("logwriter thread exit\n"); +#endif + return OK; } @@ -459,10 +472,9 @@ void sdlog2_start_log() pthread_attr_setstacksize(&receiveloop_attr, 2048); logwriter_should_exit = false; - pthread_t thread; /* start log buffer emptying thread */ - if (0 != pthread_create(&thread, &receiveloop_attr, logwriter_thread, &lb)) { + if (0 != pthread_create(&logwriter_pthread, &receiveloop_attr, logwriter_thread, &lb)) { errx(1, "error creating logwriter thread"); } @@ -476,16 +488,20 @@ void sdlog2_stop_log() mavlink_log_info(mavlink_fd, "[sdlog2] stop logging"); logging_enabled = false; - logwriter_should_exit = true; /* wake up write thread one last time */ pthread_mutex_lock(&logbuffer_mutex); + logwriter_should_exit = true; pthread_cond_signal(&logbuffer_cond); /* unlock, now the writer thread may return */ pthread_mutex_unlock(&logbuffer_mutex); /* wait for write thread to return */ - (void)pthread_join(logwriter_pthread, NULL); + int ret; + if ((ret = pthread_join(logwriter_pthread, NULL)) != 0) { + warnx("error joining logwriter thread: %i", ret); + } + logwriter_pthread = 0; sdlog2_status(); } @@ -506,7 +522,7 @@ void write_formats(int fd) for (i = 0; i < log_formats_num; i++) { log_format_packet.body = log_formats[i]; - write(fd, &log_format_packet, sizeof(log_format_packet)); + log_bytes_written += write(fd, &log_format_packet, sizeof(log_format_packet)); } fsync(fd); @@ -809,7 +825,7 @@ int sdlog2_thread_main(int argc, char *argv[]) if (log_on_start) sdlog2_start_log(); - while (!thread_should_exit) { + while (!main_thread_should_exit) { /* decide use usleep() or blocking poll() */ bool use_sleep = sleep_delay > 0 && logging_enabled; @@ -819,7 +835,7 @@ int sdlog2_thread_main(int argc, char *argv[]) /* handle the poll result */ if (poll_ret < 0) { warnx("ERROR: poll error, stop logging."); - thread_should_exit = true; + main_thread_should_exit = true; } else if (poll_ret > 0) { From 4254bbfe6df9b17ece3b72d51dd93921fe55be52 Mon Sep 17 00:00:00 2001 From: samuezih Date: Tue, 18 Jun 2013 10:45:08 +0200 Subject: [PATCH 13/13] Add PX4IOAR PX4FLOW example startup script --- .../init.d/rc.PX4IOAR_PX4FLOW_example | 94 +++++++++++++++++++ 1 file changed, 94 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d/rc.PX4IOAR_PX4FLOW_example diff --git a/ROMFS/px4fmu_common/init.d/rc.PX4IOAR_PX4FLOW_example b/ROMFS/px4fmu_common/init.d/rc.PX4IOAR_PX4FLOW_example new file mode 100644 index 0000000000..e7173f6e6e --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/rc.PX4IOAR_PX4FLOW_example @@ -0,0 +1,94 @@ +#!nsh +# +# Flight startup script for PX4FMU on PX4IOAR carrier board. +# + +# Disable the USB interface +set USB no + +# Disable autostarting other apps +set MODE ardrone + +echo "[init] doing PX4IOAR startup..." + +# +# Start the ORB +# +uorb start + +# +# Load microSD params +# +echo "[init] loading microSD params" +param select /fs/microsd/params +if [ -f /fs/microsd/params ] +then + param load /fs/microsd/params +fi + +# +# Force some key parameters to sane values +# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor +# see https://pixhawk.ethz.ch/mavlink/ +# +param set MAV_TYPE 2 + +# +# Configure PX4FMU for operation with PX4IOAR +# +fmu mode_gpio_serial + +# +# Start the sensors. +# +sh /etc/init.d/rc.sensors + +# +# Start MAVLink and MAVLink Onboard (Flow Sensor) +# +mavlink start -d /dev/ttyS0 -b 57600 +mavlink_onboard start -d /dev/ttyS3 -b 115200 +usleep 5000 + +# +# Start the commander. +# +commander start + +# +# Start the attitude estimator +# +attitude_estimator_ekf start + +# +# Start the position estimator +# +flow_position_estimator start + +# +# Fire up the multi rotor attitude controller +# +multirotor_att_control start + +# +# Fire up the flow position controller +# +flow_position_control start + +# +# Fire up the flow speed controller +# +flow_speed_control start + +# +# Fire up the AR.Drone interface. +# +ardrone_interface start -d /dev/ttyS1 + +# +# startup is done; we don't want the shell because we +# use the same UART for telemetry +# +echo "[init] startup done" + +exit