dronecodeのコーディングルールを拝見いたしました。
あまりにもざっくりしていることもあり、保守性や品質まではいき渡っていなさそうと感じています。
そこで、日本には、組み込み系ソフトについて、コーディングルールというのを事細かく定義してるものがあります。
例えば、
・MISRAとか
・IPAの「組込みソフトウェア開発向けコーディング作法ガイド[C++言語版]」や
・凡ミスによる障害の回避ルール
これらのルールをベースにArduCopterのコードの品質を上げていきたい。
また、その過程で、不安なコードがあれば、不安を軽減していきたい。
その情報や修正案などのアップしたいと思い、このディスカッションを立ち上げました。
何卒、よろしくおねがいいたします。
Replies
今日、採用いただきました。
これで、Navioで、PX4Flowが利用できると思うのですが。
いかがでしょう。
murata,katsutoshi said:
Navio2 を長時間稼働させてログを取得していました。
ファイルファイズが2Gを超えたら、新しいファイルを作成しません。
確か電源に接続されたままホバリングさせて基地局にするシステムがあったと思います。
こういう使い方をする場合、ログファイルを新規作成する必要あると思っています。
励ましありがとうございます。とても元気付けられます。
情報ありがとうございます。
Jiro Hattori said:
頑張っていますね。
ご存じのようにPixhawk本体とpx4flowは、既にDisconの風情です。
Pixhawk2と並行してSolo用のOptical Flow Sensor(px4flowの改良品)が、開発中なようなので、ネタをお知らせします。
詳細は、”Optical flow on Solo” http://discuss.ardupilot.org/t/optical-flow-on-solo/8756 です。
CANBUSになるのかなぁ?
Navio2 で PX4Flow が使えないということで調査を進めています。
平均値「i2c_integral_frame」の値が変化しないという現象があります。
これは、PX4Flowのダブルバッファを切り替えるために、最終レジスタまで行ったかどうかをsizeofで構造体のサイズと比較して切り替えています。
この構造体のサイズが、AP_OpticalFlow_Linux.h と i2c_frame.h で異なっています。
1レジスタ分がLinux側が少ない、もしくは PX4Flow 側が1レジスタ分多いということが原因でした。
PX4Flow側の定義をHPに合わせると、多数のFCに影響があるため、Linux側を修正することにしました。
PACKED を取るとWORDバウンダリ(さらに2バイト多くなります)となって解消しません。
そこで、1バイト分のパディング変数を追加することで対応しました。
対応結果:
Debug Information:
f_integral=10 00 FB FF EB FF 00 00 04 00 00 00 E4 97 01 00 E8 94 05 00 00 00 D8 0E C3 00
PX4FLOW id:0 qual:195 FlowRateX:-0.00 Y:-0.02 BodyRateX:0.00 y:0.00
===
AP_OpticalFlow_Linux.h
typedef struct PACKED {
uint16_t frame_count_since_last_readout;
int16_t pixel_flow_x_integral;
int16_t pixel_flow_y_integral;
int16_t gyro_x_rate_integral;
int16_t gyro_y_rate_integral;
int16_t gyro_z_rate_integral;
uint32_t integration_timespan;
uint32_t sonar_timestamp;
uint16_t ground_distance;
int16_t gyro_temperature;
uint8_t qual;
uint8_t padding_not_used; ★追加パディング変数
} i2c_integral_frame;
PX4Flow の i2c_frame.h
Pixhawk 単体でWifi接続したいと思って、Wifi TCP I2C SPIで検索しましたところ、「Wi-Fiモジュール ESP-WROOM-02」というモジュールがヒットしました。
さらに、ardupilotで検索しましたら、すでに実証実験されておられ、WifiでMission Plannerと接続できたとの記事でした。
早速、楽天市場でヒットした店舗へ注文しました。
先人に感謝です。
http://diydrones.com/group/japan-arducopter-group/forum/topics/esp8...
Navio2で意図的にアクティブのlogファイルを削除しました。
この削除による異常検出しないようです。
murata,katsutoshi said:
PX4Flow がハングしただけで、本体がパニックしてしまいます。
PX4Flowはオプションだから、ハングしても無視すればよいのに。
pi@navio:~/work/ardupilot/build/navio2-debug/bin $ sudo ./arducopter-hexa -A u:192.168.0.15:14550
Raspberry Pi 2/3 with BCM2709!
PANIC: AP_Baro::read unsuccessful for more than 500ms in AP_Baro::calibrate [2]
===
// calibrate the barometer. This must be called at least once before
// the altitude() or climb_rate() interfaces can be used
void AP_Baro::calibrate()
{
// reset the altitude offset when we calibrate. The altitude
// offset is supposed to be for within a flight
_alt_offset.set_and_save(0);
// start by assuming all sensors are calibrated (for healthy() test)
for (uint8_t i=0; i<_num_sensors; i++) {
sensors[i].calibrated = true;
sensors[i].alt_ok = true;
}
// let the barometer settle for a full second after startup
// the MS5611 reads quite a long way off for the first second,
// leading to about 1m of error if we don't wait
for (uint8_t i = 0; i < 10; i++) {
uint32_t tstart = AP_HAL::millis();
do {
update();
if (AP_HAL::millis() - tstart > 500) {
AP_HAL::panic("PANIC: AP_Baro::read unsuccessful "
"for more than 500ms in AP_Baro::calibrate [2]\r\n"); ★ここでパニックている。
}
hal.scheduler->delay(10);
} while (!healthy());
hal.scheduler->delay(100);
}
// now average over 5 values for the ground pressure and
// temperature settings
float sum_pressure[BARO_MAX_INSTANCES] = {0};
float sum_temperature[BARO_MAX_INSTANCES] = {0};
uint8_t count[BARO_MAX_INSTANCES] = {0};
const uint8_t num_samples = 5;
for (uint8_t c = 0; c < num_samples; c++) {
uint32_t tstart = AP_HAL::millis();
do {
update();
if (AP_HAL::millis() - tstart > 500) {
AP_HAL::panic("PANIC: AP_Baro::read unsuccessful "
"for more than 500ms in AP_Baro::calibrate [3]\r\n");
}
} while (!healthy());
for (uint8_t i=0; i<_num_sensors; i++) {
if (healthy(i)) {
sum_pressure[i] += sensors[i].pressure;
sum_temperature[i] += sensors[i].temperature;
count[i] += 1;
}
}
hal.scheduler->delay(100);
}
for (uint8_t i=0; i<_num_sensors; i++) {
if (count[i] == 0) {
sensors[i].calibrated = false;
} else {
sensors[i].ground_pressure.set_and_save(sum_pressure[i] / count[i]);
sensors[i].ground_temperature.set_and_save(sum_temperature[i] / count[i]);
}
}
// panic if all sensors are not calibrated
for (uint8_t i=0; i<_num_sensors; i++) {
if (sensors[i].calibrated) {
return;
}
}
AP_HAL::panic("AP_Baro: all sensors uncalibrated");
}
PX4Flow へのアクセスでreadできない場合があるようです。
murata,katsutoshi said: