이충섭

fix : collectGps function move check_gps to ekf2

...@@ -55,7 +55,6 @@ ...@@ -55,7 +55,6 @@
55 #define MASK_GPS_VDRIFT (1<<6) 55 #define MASK_GPS_VDRIFT (1<<6)
56 #define MASK_GPS_HSPD (1<<7) 56 #define MASK_GPS_HSPD (1<<7)
57 #define MASK_GPS_VSPD (1<<8) 57 #define MASK_GPS_VSPD (1<<8)
58 -static int hold=0;
59 bool Ekf::collect_gps(const gps_message &gps) 58 bool Ekf::collect_gps(const gps_message &gps)
60 { 59 {
61 // Run GPS checks always 60 // Run GPS checks always
...@@ -141,18 +140,6 @@ bool Ekf::collect_gps(const gps_message &gps) ...@@ -141,18 +140,6 @@ bool Ekf::collect_gps(const gps_message &gps)
141 } 140 }
142 141
143 // start collecting GPS if there is a 3D fix and the NED origin has been set 142 // start collecting GPS if there is a 3D fix and the NED origin has been set
144 - if(hold != int(gps.time_usec/1000000))
145 - {
146 - hold=int(gps.time_usec/1000000);
147 - if(hold%2==0)
148 - {
149 - std::cout <<"----------------------current--------------------------"<<std::endl;
150 - std :: cout << "time : "<<gps.time_usec/1000000<<std::endl;
151 - std :: cout << "lat : " <<gps.lat <<std::endl;
152 - std :: cout << "lon : " <<gps.lon <<std::endl;
153 - std :: cout << "alt : " <<gps.alt <<std::endl;
154 - }
155 - }
156 // print GPS data every 1 seocnds 143 // print GPS data every 1 seocnds
157 return _NED_origin_initialised && (gps.fix_type >= 3); 144 return _NED_origin_initialised && (gps.fix_type >= 3);
158 } 145 }
......
...@@ -32,7 +32,7 @@ ...@@ -32,7 +32,7 @@
32 ****************************************************************************/ 32 ****************************************************************************/
33 33
34 #include "EKF2.hpp" 34 #include "EKF2.hpp"
35 - 35 +#include <iostream>
36 using namespace time_literals; 36 using namespace time_literals;
37 using math::constrain; 37 using math::constrain;
38 using matrix::Eulerf; 38 using matrix::Eulerf;
...@@ -44,7 +44,7 @@ static px4::atomic<EKF2 *> _objects[EKF2_MAX_INSTANCES] {}; ...@@ -44,7 +44,7 @@ static px4::atomic<EKF2 *> _objects[EKF2_MAX_INSTANCES] {};
44 #if !defined(CONSTRAINED_FLASH) 44 #if !defined(CONSTRAINED_FLASH)
45 static px4::atomic<EKF2Selector *> _ekf2_selector {nullptr}; 45 static px4::atomic<EKF2Selector *> _ekf2_selector {nullptr};
46 #endif // !CONSTRAINED_FLASH 46 #endif // !CONSTRAINED_FLASH
47 - 47 +static int hold=0;
48 EKF2::EKF2(bool multi_mode, const px4::wq_config_t &config, bool replay_mode): 48 EKF2::EKF2(bool multi_mode, const px4::wq_config_t &config, bool replay_mode):
49 ModuleParams(nullptr), 49 ModuleParams(nullptr),
50 ScheduledWorkItem(MODULE_NAME, config), 50 ScheduledWorkItem(MODULE_NAME, config),
...@@ -169,6 +169,8 @@ EKF2::~EKF2() ...@@ -169,6 +169,8 @@ EKF2::~EKF2()
169 { 169 {
170 perf_free(_ecl_ekf_update_perf); 170 perf_free(_ecl_ekf_update_perf);
171 perf_free(_ecl_ekf_update_full_perf); 171 perf_free(_ecl_ekf_update_full_perf);
172 + perf_free(_imu_missed_perf);
173 + perf_free(_mag_missed_perf);
172 } 174 }
173 175
174 bool EKF2::multi_init(int imu, int mag) 176 bool EKF2::multi_init(int imu, int mag)
...@@ -193,17 +195,18 @@ bool EKF2::multi_init(int imu, int mag) ...@@ -193,17 +195,18 @@ bool EKF2::multi_init(int imu, int mag)
193 _estimator_visual_odometry_aligned_pub.advertised(); 195 _estimator_visual_odometry_aligned_pub.advertised();
194 _yaw_est_pub.advertise(); 196 _yaw_est_pub.advertise();
195 197
196 - _vehicle_imu_sub.ChangeInstance(imu); 198 + bool changed_instance = _vehicle_imu_sub.ChangeInstance(imu) && _magnetometer_sub.ChangeInstance(mag);
197 - _magnetometer_sub.ChangeInstance(mag);
198 199
199 const int status_instance = _estimator_states_pub.get_instance(); 200 const int status_instance = _estimator_states_pub.get_instance();
200 201
201 - if ((status_instance >= 0) 202 + if ((status_instance >= 0) && changed_instance
202 && (_attitude_pub.get_instance() == status_instance) 203 && (_attitude_pub.get_instance() == status_instance)
203 && (_local_position_pub.get_instance() == status_instance) 204 && (_local_position_pub.get_instance() == status_instance)
204 && (_global_position_pub.get_instance() == status_instance)) { 205 && (_global_position_pub.get_instance() == status_instance)) {
205 206
206 _instance = status_instance; 207 _instance = status_instance;
208 +
209 + ScheduleNow();
207 return true; 210 return true;
208 } 211 }
209 212
...@@ -219,6 +222,12 @@ int EKF2::print_status() ...@@ -219,6 +222,12 @@ int EKF2::print_status()
219 _ekf.local_position_is_valid(), _ekf.global_position_is_valid()); 222 _ekf.local_position_is_valid(), _ekf.global_position_is_valid());
220 perf_print_counter(_ecl_ekf_update_perf); 223 perf_print_counter(_ecl_ekf_update_perf);
221 perf_print_counter(_ecl_ekf_update_full_perf); 224 perf_print_counter(_ecl_ekf_update_full_perf);
225 + perf_print_counter(_imu_missed_perf);
226 +
227 + if (_device_id_mag != 0) {
228 + perf_print_counter(_mag_missed_perf);
229 + }
230 +
222 return 0; 231 return 0;
223 } 232 }
224 233
...@@ -298,8 +307,9 @@ void EKF2::Run() ...@@ -298,8 +307,9 @@ void EKF2::Run()
298 imu_updated = _vehicle_imu_sub.update(&imu); 307 imu_updated = _vehicle_imu_sub.update(&imu);
299 308
300 if (imu_updated && (_vehicle_imu_sub.get_last_generation() != last_generation + 1)) { 309 if (imu_updated && (_vehicle_imu_sub.get_last_generation() != last_generation + 1)) {
301 - PX4_ERR("%d - vehicle_imu lost, generation %d -> %d", _instance, last_generation, 310 + perf_count(_imu_missed_perf);
302 - _vehicle_imu_sub.get_last_generation()); 311 + PX4_DEBUG("%d - vehicle_imu lost, generation %d -> %d", _instance, last_generation,
312 + _vehicle_imu_sub.get_last_generation());
303 } 313 }
304 314
305 imu_sample_new.time_us = imu.timestamp_sample; 315 imu_sample_new.time_us = imu.timestamp_sample;
...@@ -1498,7 +1508,18 @@ void EKF2::UpdateGpsSample(ekf2_timestamps_s &ekf2_timestamps) ...@@ -1498,7 +1508,18 @@ void EKF2::UpdateGpsSample(ekf2_timestamps_s &ekf2_timestamps)
1498 + vehicle_gps_position.vdop * vehicle_gps_position.vdop), 1508 + vehicle_gps_position.vdop * vehicle_gps_position.vdop),
1499 }; 1509 };
1500 _ekf.setGpsData(gps_msg); 1510 _ekf.setGpsData(gps_msg);
1501 - 1511 + if(hold != int(gps_msg.time_usec/1000000))
1512 + {
1513 + hold=int(gps_msg.time_usec/1000000);
1514 + if(hold%2==0)
1515 + {
1516 + std::cout <<"----------------------current--------------------------"<<std::endl;
1517 + std :: cout << "time : "<<gps_msg.time_usec/1000000<<std::endl;
1518 + std :: cout << "lat : " <<gps_msg.lat <<std::endl;
1519 + std :: cout << "lon : " <<gps_msg.lon <<std::endl;
1520 + std :: cout << "alt : " <<gps_msg.alt <<std::endl;
1521 + }
1522 + }
1502 _gps_time_usec = gps_msg.time_usec; 1523 _gps_time_usec = gps_msg.time_usec;
1503 _gps_alttitude_ellipsoid = vehicle_gps_position.alt_ellipsoid; 1524 _gps_alttitude_ellipsoid = vehicle_gps_position.alt_ellipsoid;
1504 } 1525 }
...@@ -1513,8 +1534,9 @@ void EKF2::UpdateMagSample(ekf2_timestamps_s &ekf2_timestamps) ...@@ -1513,8 +1534,9 @@ void EKF2::UpdateMagSample(ekf2_timestamps_s &ekf2_timestamps)
1513 if (_magnetometer_sub.update(&magnetometer)) { 1534 if (_magnetometer_sub.update(&magnetometer)) {
1514 1535
1515 if (_magnetometer_sub.get_last_generation() != last_generation + 1) { 1536 if (_magnetometer_sub.get_last_generation() != last_generation + 1) {
1516 - PX4_ERR("%d - vehicle_magnetometer lost, generation %d -> %d", _instance, last_generation, 1537 + perf_count(_mag_missed_perf);
1517 - _magnetometer_sub.get_last_generation()); 1538 + PX4_DEBUG("%d - vehicle_magnetometer lost, generation %d -> %d", _instance, last_generation,
1539 + _magnetometer_sub.get_last_generation());
1518 } 1540 }
1519 1541
1520 bool reset = false; 1542 bool reset = false;
...@@ -1738,7 +1760,8 @@ int EKF2::task_spawn(int argc, char *argv[]) ...@@ -1738,7 +1760,8 @@ int EKF2::task_spawn(int argc, char *argv[])
1738 1760
1739 while ((multi_instances_allocated < multi_instances) 1761 while ((multi_instances_allocated < multi_instances)
1740 && (vehicle_status_sub.get().arming_state != vehicle_status_s::ARMING_STATE_ARMED) 1762 && (vehicle_status_sub.get().arming_state != vehicle_status_s::ARMING_STATE_ARMED)
1741 - && (hrt_elapsed_time(&time_started) < 30_s)) { 1763 + && ((hrt_elapsed_time(&time_started) < 30_s)
1764 + || (vehicle_status_sub.get().hil_state == vehicle_status_s::HIL_STATE_ON))) {
1742 1765
1743 vehicle_status_sub.update(); 1766 vehicle_status_sub.update();
1744 1767
...@@ -1763,16 +1786,21 @@ int EKF2::task_spawn(int argc, char *argv[]) ...@@ -1763,16 +1786,21 @@ int EKF2::task_spawn(int argc, char *argv[])
1763 1786
1764 if ((actual_instance >= 0) && (_objects[actual_instance].load() == nullptr)) { 1787 if ((actual_instance >= 0) && (_objects[actual_instance].load() == nullptr)) {
1765 _objects[actual_instance].store(ekf2_inst); 1788 _objects[actual_instance].store(ekf2_inst);
1766 - ekf2_inst->ScheduleNow();
1767 success = true; 1789 success = true;
1768 multi_instances_allocated++; 1790 multi_instances_allocated++;
1769 ekf2_instance_created[imu][mag] = true; 1791 ekf2_instance_created[imu][mag] = true;
1770 1792
1793 + if (actual_instance == 0) {
1794 + // force selector to run immediately if first instance started
1795 + _ekf2_selector.load()->ScheduleNow();
1796 + }
1797 +
1771 PX4_INFO("starting instance %d, IMU:%d (%d), MAG:%d (%d)", actual_instance, 1798 PX4_INFO("starting instance %d, IMU:%d (%d), MAG:%d (%d)", actual_instance,
1772 imu, vehicle_imu_sub.get().accel_device_id, 1799 imu, vehicle_imu_sub.get().accel_device_id,
1773 mag, vehicle_mag_sub.get().device_id); 1800 mag, vehicle_mag_sub.get().device_id);
1774 1801
1775 - _ekf2_selector.load()->ScheduleNow(); 1802 + // sleep briefly before starting more instances
1803 + px4_usleep(10000);
1776 1804
1777 } else { 1805 } else {
1778 PX4_ERR("instance numbering problem instance: %d", actual_instance); 1806 PX4_ERR("instance numbering problem instance: %d", actual_instance);
......