PX4 / PX4-Autopilot

PX4 Autopilot Software
https://px4.io
BSD 3-Clause "New" or "Revised" License
8.49k stars 13.51k forks source link

FMU v1 Low Memory Issue (again?) #608

Closed pigeonhunter closed 10 years ago

pigeonhunter commented 10 years ago

Running px4fmu v1.7 + px4io 1.3

Free is reporting only about 6-10K of RAM available under the latest master with only the autostarted multicopter apps running. I'm also seeing the standard odd behavior in nsh, ie apps not found, indicative of a low memory situation.

nsh> free total used free largest Mem: 167136 156800 10336 6928

Here's what's running... Processes: 19 total, 2 running, 17 sleeping CPU usage: 66.08% tasks, 0.74% sched, 33.18% idle Uptime: 127.303s total, 42.796s idle

PID COMMAND CPU(ms) CPU(%) USED/STACK PRIO(BASE) STATE 0 Idle Task 42795 33.078 0/ 0 0 ( 0) READY 1 hpwork 4927 3.092 756/ 3992 192 (192) w:sig 2 lpwork 581 0.063 404/ 3992 50 ( 50) READY 3 init 1013 0.000 1228/ 4088 100 (100) w:sem 39 nshterm 12 0.000 908/ 2992 100 (100) w:sem 84 attitude_estimator_ekf 26825 21.023 11636/13992 250 (250) w:sem 41 commander 458 0.078 1708/ 2992 215 (215) w:sig 42 commander_low_prio 41 0.000 612/ 2984 50 ( 50) READY 44 px4io 5340 4.063 812/ 2040 240 (240) w:sem 49 mavlink 277 0.085 956/ 2040 100 (100) READY 50 mavlink_uart_rcv 111 0.000 764/ 2992 215 (215) w:sem 51 mavlink_orb_rcv 4252 3.058 1212/ 2040 250 (100) w:sem 62 sensors_task 16702 13.031 876/ 2040 250 (250) w:sem 92 top 657 1.046 1324/ 2992 100 (100) RUN
70 sdlog2 506 0.092 1796/ 2992 70 ( 70) w:sem 75 gps 473 0.070 892/ 2040 220 (220) w:sem 86 position_estimator_inav 14533 11.070 2068/ 4088 250 (250) w:sem 88 multirotor_att_control 6205 4.019 1452/ 2040 240 (240) w:sem 90 multirotor_pos_control 262 0.085 1764/ 4088 195 (195) w:sig

I can't be sure, of course, but the stack sizes seem a bit excessive compared to the used memory in some cases. Is there a free lint that can estimate what these aught to be?

Also att_estimator_ekf seems a bit on the massive size. It's all all those matrices I suppose. Perhaps a madgewick MARG implementation will help here, or Hyon's SO3. Currently att_estimator_so3 looks like:

117 attitude_estimator_so3 587 3.014 1136/13992 250 (250) w:sem

It also seems to be way overstacked, but that's easily fixed.

Getting back to the topic at hand... I haven't stepped through the startup yet, but here's the skinny from nm ...

arm-none-eabi-nm --print-size --size-sort ./Build/px4fmu-v1_default.build/firmware.elf | grep " [bBdD] "

20002fb4 00000001 b _ZL10should_arm 20000e54 00000001 b _ZL11bFilterInit 20000e2c 00000001 b _ZL14thread_running 20000ebc 00000001 b _ZL14thread_running 20000dd8 00000001 b _ZL14thread_running 20000de6 00000001 b _ZL14thread_running 20000a44 00000001 b _ZL18_home_position_set 20000046 00000001 d _ZL18main_state_changed 20000dd0 00000001 b _ZL18thread_should_exit 20000e55 00000001 b _ZL18thread_should_exit 20000de4 00000001 b _ZL18thread_should_exit 20000e98 00000001 b _ZL18thread_should_exit 20000045 00000001 d _ZL20arming_state_changed 20000ea0 00000001 b _ZL21commander_initialized 20000044 00000001 d _ZL24navigation_state_changed 20000de5 00000001 b _ZZ34attitude_estimator_ekf_thread_mainiPPcE17const_initialized 20000f54 00000001 b _ZZ34battery_remaining_estimate_voltageffE11initialized 20000004 00000001 d _ZZN6BlinkM3ledEvE16led_thread_ready 20000844 00000001 b _ZZN6BlinkM3ledEvE17topic_initialized 20000894 00000001 b _ZZN6BlinkM3ledEvE22detected_cells_blinked 200007d4 00000001 D fdlib_version 20002f25 00000001 b attached 2000280c 00000001 b chan 200014cc 00000001 b chan 20002ad8 00000001 b flag_system_armed 200036a8 00000001 b g_binitialized 2000005c 00000001 d gcs_link 200000c4 00000001 d gcs_link 20000f90 00000001 b gpio_led_started 2000106c 00000001 b initialized.15735 20002ffc 00000001 b initialized.5450 2000291c 00000001 b initialized.5945 200029b8 00000001 b initialized.5973 20002aba 00000001 b log_name_timestamp 20002acd 00000001 b log_on_start 20002acc 00000001 b log_when_armed 20002a90 00000001 b logging_enabled 20002aa8 00000001 b logwriter_should_exit 20002aa9 00000001 b main_thread_should_exit 200014cd 00000001 b mavlink_hil_enabled 20002810 00000001 b mavlink_link_mode 200014c0 00000001 b mavlink_link_mode 20002804 00000001 b mavlink_link_termination_allowed 200019cd 00000001 b mavlink_link_termination_allowed 200000b8 00000001 d mavlink_wpm_comp_id 200028a4 00000001 b motor_test_mode 20002f24 00000001 b started 200019cc 00000001 b thread_running 20000910 00000001 b thread_running 200007e0 00000001 b thread_running 200027f8 00000001 b thread_running 20002a44 00000001 b thread_running 20002ad9 00000001 b thread_running 20002a2c 00000001 b thread_running 20002a34 00000001 b thread_should_exit 20002a4c 00000001 b thread_should_exit 20000918 00000001 b thread_should_exit 20002811 00000001 b thread_should_exit 200007e8 00000001 b thread_should_exit 200028ac 00000001 b thread_should_exit 20001058 00000001 b thread_should_exit 20002a45 00000001 b verbose_mode 20002380 00000002 b counter.14705 200034b8 00000002 B g_lastpid 200036a0 00000002 b g_retchar 2000369c 00000002 b g_retchar 20000d1e 00000002 b latency_actual 20000cc8 00000002 b latency_baseline 20002ab8 00000002 b logwriter_pthread 20000d1c 00000002 B ppm_frame_length 2000280e 00000002 b receive_thread 200014b8 00000002 b receive_thread 2000105a 00000002 b uorb_receive_thread 20001e88 00000004 b _ZL10hil_frames 20000f40 00000004 b _ZL10mavlink_fd 20000eb8 00000004 b _ZL10status_pub 20000024 00000004 d _ZL11_sensor_sub 20000e9c 00000004 b _ZL11daemon_task 20000dd4 00000004 b _ZL11daemon_task 20000930 00000004 b _ZL11deamon_task 20000a3c 00000004 b _ZL11deamon_task 20001e4c 00000004 b _ZL11hil_counter 20000084 00000004 d _ZL11pub_hil_gps 2000007c 00000004 d _ZL11pub_hil_mag 20000040 00000004 d _ZL11takeoff_alt 20000028 00000004 d _ZL12_battery_sub 20000ea4 00000004 b _ZL12leds_counter 20000094 00000004 d _ZL12pub_hil_baro 20000088 00000004 d _ZL12pub_hil_gyro 2000002c 00000004 d _ZL13_airspeed_sub 200000a4 00000004 d _ZL13pub_hil_accel 20000a40 00000004 b _ZL14thread_running 20000934 00000004 b _ZL14thread_running 200000ac 00000004 d _ZL15pub_hil_battery 2000008c 00000004 d _ZL15pub_hil_sensors 20000ec8 00000004 b _ZL16control_mode_pub 20000098 00000004 d _ZL16pub_hil_airspeed 20000080 00000004 d _ZL16pub_hil_attitude 200000b0 00000004 d _ZL17pub_hil_local_pos 200000a8 00000004 d _ZL18pub_hil_global_pos 20000a38 00000004 b _ZL18thread_should_exit 2000092c 00000004 b _ZL18thread_should_exit 200000b4 00000004 d _ZL18vicon_position_pub 20000090 00000004 d _ZL20telemetry_status_pub 2000009c 00000004 d _ZL23offboard_control_sp_pub 20000de0 00000004 b _ZL27attitude_estimator_ekf_task 20000e4c 00000004 b _ZL27attitude_estimator_so3_task 2000003c 00000004 d _ZL2q0 20000e20 00000004 b _ZL2q1 20000e24 00000004 b _ZL2q2 20000e28 00000004 b _ZL2q3 20000e10 00000004 b _ZL3dq0 20000e60 00000004 b _ZL3dq1 20000e18 00000004 b _ZL3dq2 20000e68 00000004 b _ZL3dq3 20001dd0 00000004 b _ZL4lat0 20000f68 00000004 b _ZL4leds 20001c58 00000004 b _ZL4lon0 20000e58 00000004 b _ZL4q0q0 20000e5c 00000004 b _ZL4q0q1 20000e14 00000004 b _ZL4q0q2 20000e64 00000004 b _ZL4q0q3 20000e34 00000004 b _ZL4q1q1 20000e38 00000004 b _ZL4q1q2 20000e3c 00000004 b _ZL4q1q3 20000e30 00000004 b _ZL4q2q2 20000e1c 00000004 b _ZL4q2q3 20000e50 00000004 b _ZL4q3q3 20000f50 00000004 b _ZL6buzzer 200000a0 00000004 d _ZL7cmd_pub 20000f48 00000004 b _ZL7rgbleds 20000938 00000004 b _ZL8_esc_pub 20000030 00000004 d _ZL8_esc_sub 20000020 00000004 d _ZL8_gps_sub 20000078 00000004 d _ZL8flow_pub 20000034 00000004 d _ZL9_home_sub 20000f80 00000004 b _ZN10l1_control9g_controlE 20000f70 00000004 b _ZN11att_control9g_controlE 20000a5c 00000004 b _ZN12_GLOBAL__N_14gLEDE 20000be8 00000004 b _ZN12_GLOBALN_14g_mkE 20000d3c 00000004 b _ZN12_GLOBALN_15g_adcE 2000091c 00000004 b _ZN12_GLOBALN_15g_devE 20000d40 00000004 b _ZN12_GLOBALN_15g_devE 20002f10 00000004 b _ZN12_GLOBALN_15g_devE 20000bf8 00000004 b _ZN12_GLOBALN_15g_devE 20000bf4 00000004 b _ZN12_GLOBALN_15g_fmuE 20000924 00000004 b _ZN12_GLOBALN_15g_hilE 2000085c 00000004 b _ZN12_GLOBALN_18g_blinkmE 20000bfc 00000004 b _ZN12_GLOBALN_18g_rgbledE 2000090c 00000004 b _ZN12ets_airspeed5g_devE 20000a64 00000004 b _ZN13meas_airspeed5g_devE 20000920 00000004 b _ZN3gps5g_devE 20000a58 00000004 b _ZN6l3gd205g_devE 20000a60 00000004 b _ZN6mb12xx5g_devE 20000bf0 00000004 b _ZN6ms56115g_devE 20000928 00000004 b _ZN7hmc58835g_devE 20000bec 00000004 b _ZN7mpu60005g_devE 20002adc 00000004 b _ZN7sensors9g_sensorsE 20002a40 00000004 b _ZN9navigator11g_navigatorE 20000050 00000004 d _ZZ34battery_remaining_estimate_voltageffE10bat_v_full 2000004c 00000004 d _ZZ34battery_remaining_estimate_voltageffE11bat_n_cells 20000048 00000004 d _ZZ34battery_remaining_estimate_voltageffE11bat_v_empty 20000054 00000004 d _ZZ34battery_remaining_estimate_voltageffE12bat_capacity 20000f58 00000004 b _ZZ34battery_remaining_estimate_voltageffE12bat_v_full_h 20000f6c 00000004 b _ZZ34battery_remaining_estimate_voltageffE13bat_n_cells_h 20000f44 00000004 b _ZZ34battery_remaining_estimate_voltageffE13bat_v_empty_h 20000f4c 00000004 b _ZZ34battery_remaining_estimate_voltageffE14bat_capacity_h 20000f5c 00000004 b _ZZ34battery_remaining_estimate_voltageffE7counter 20001e00 00000004 b _ZZL14handle_messageP17mavlink_messageE6mc_pub 20001cf0 00000004 b _ZZL14handle_messageP17__mavlink_messageE6rc_pub 20000848 00000004 b _ZZN6BlinkM3ledEvE11t_led_blink 20000008 00000004 d _ZZN6BlinkM3ledEvE12led_interval 20000898 00000004 b _ZZN6BlinkM3ledEvE12num_of_cells 2000089c 00000004 b _ZZN6BlinkM3ledEvE19led_thread_runcount 20000850 00000004 b _ZZN6BlinkM3ledEvE21actuator_armed_sub_fd 20000884 00000004 b _ZZN6BlinkM3ledEvE21vehicle_status_sub_fd 20000890 00000004 b _ZZN6BlinkM3ledEvE22no_data_actuator_armed 20000854 00000004 b _ZZN6BlinkM3ledEvE22no_data_vehicle_status 20000858 00000004 b _ZZN6BlinkM3ledEvE23detected_cells_runcount 2000084c 00000004 b _ZZN6BlinkM3ledEvE27vehicle_control_mode_sub_fd 20000860 00000004 b _ZZN6BlinkM3ledEvE27vehicle_gps_position_sub_fd 20000888 00000004 b _ZZN6BlinkM3ledEvE28no_data_vehicle_control_mode 2000088c 00000004 b _ZZN6BlinkM3ledEvE28no_data_vehicle_gps_position 20000038 00000004 d _ZZN6MB12XX5startEvE3pub 2000001c 00000004 d _ZZN7HMC588317check_calibrationEvE3pub 20000000 00000004 d _ZZN8Airspeed5startEvE3pub 20000ddc 00000004 b _ZZN9KalmanNav10correctPosEvE7counter 200058b0 00000004 B __dso_handle 20001f74 00000004 b accel_counter.15524 200007ec 00000004 b ardrone_interface_task 200007e4 00000004 b ardrone_write 20002308 00000004 b attitude_counter 20002170 00000004 b baro_counter.15527 20000018 00000004 d battery_sub 200027fc 00000004 b baudrate 20001074 00000004 b baudrate 200000d0 00000004 d cmd_pub 20003840 00000004 B current_regs 20002a30 00000004 b deamon_task 20002a8c 00000004 b deamon_task 200000cc 00000004 d flow_pub 20000914 00000004 b frsky_task 20005ba4 00000004 B g_binfmts 20002ff8 00000004 B g_cdcacm 20003200 00000004 b g_irqerrno 20005b30 00000004 b g_msgalloc 20005b3c 00000004 b g_msgfreeirqalloc 200036a4 00000004 b g_optptr 200036c8 00000004 b g_randint1 200059c0 00000004 b g_sigactionalloc 200059cc 00000004 b g_sigpendingactionalloc 200059a8 00000004 b g_sigpendingirqactionalloc 200059a4 00000004 b g_sigpendingirqsignalalloc 200059ac 00000004 b g_sigpendingsignalalloc 20005994 00000004 B g_system_timer 20005998 00000004 B g_tickbias 20003690 00000004 B g_wdpool 2000006c 00000004 d global_position_set_triplet_pub.15702 20000068 00000004 d global_position_setpoint_pub.15701 20000010 00000004 d global_position_sub 2000237c 00000004 b gps_counter 20002378 00000004 b gyro_counter.15525 20002f1c 00000004 b i2c 200000ec 00000004 d last_amber.5680 200000e8 00000004 d last_blue.5679 20000cc0 00000004 b last_count.5964 20000074 00000004 d last_waypoint_index.15704 20002f70 00000004 b lasttime.6536 20000070 00000004 d local_position_setpoint_pub.15703 20002aa4 00000004 b log_bytes_written 20002a88 00000004 b log_msgs_skipped 20002abc 00000004 b log_msgs_written 20002130 00000004 b mag_counter.15526 200000d8 00000004 d mavlink_fd 20002a28 00000004 b mavlink_fd.6492 20001b18 00000004 b mavlink_param_queue_index 200014c4 00000004 b mavlink_task 20002800 00000004 b mavlink_task 200028a8 00000004 b mc_task 200028b4 00000004 b motor_skip_counter.5940 20002a24 00000004 b motor_skip_counter.5967 20002f28 00000004 b mtd_dev 20002f20 00000004 b n_partitions_current 2000230c 00000004 b nav_cap 20000d28 00000004 b new_channel_count.5942 20000cb0 00000004 b new_channel_holdoff.5943 200000d4 00000004 d offboard_control_sp_pub 200036ac 00000004 B optarg 2000015c 00000004 D optind 20000158 00000004 D optopt 20005b58 00000004 b p5s 200019c8 00000004 b param_component_id.15737 200014c8 00000004 b param_system_id.15736 20001070 00000004 b param_system_type.15738 200000dc 00000004 d param_topic 20002af0 00000004 b param_user_file 20002aec 00000004 b param_values 20002a48 00000004 b position_estimator_inav_task 20000cac 00000004 B ppm_decoded_channels 20000cb4 00000004 b ppm_edge_next 20000cc4 00000004 b ppm_pulse_next 20000840 00000004 b pub.5850 20002174 00000004 b rc_sub 20005ba0 00000004 b result.5608 20005b5c 00000004 b result_k.5609 20005b18 00000004 B root_inode 20000e00 00000004 b rtInfF 20000df4 00000004 b rtMinusInfF 20000df0 00000004 b rtNaNF 20002ae8 00000004 b s.4827 20000014 00000004 d sensor_sub 20001f70 00000004 b sensors_raw_counter 20002ac8 00000004 b sleep_delay 200008c0 00000004 b spi1 200008c4 00000004 b spi2 200008c8 00000004 b spi3 200020e8 00000004 b status_sub 200014bc 00000004 b total_counter.15680 200019d0 00000004 b uart 20002808 00000004 b uart 2000000c 00000004 d vehicle_status_sub 200000c8 00000004 d vicon_position_pub 20000058 00000004 d wpm 200028b0 00000004 b yaw_error.5946 200000bc 00000006 d mavlink_system 20000060 00000006 d mavlink_system 20000f60 00000008 b _ZL13blink_msg_end 20001e50 00000008 b _ZL13old_timestamp 20000ec0 00000008 b _ZL27last_print_mode_reject_time 20001f68 00000008 b _ZL4alt0 20000a48 00000008 b _ZL9_home_lat 20000a50 00000008 b _ZL9_home_lon 20000f78 00000008 b _ZZN24FixedwingAttitudeControl9task_mainEvE8last_run 20000f88 00000008 b _ZZN24FixedwingPositionControl9task_mainEvE8last_run 20002a38 00000008 b _ZZN9Navigator9task_mainEvE8last_run 20000cb8 00000008 b base_time.5963 20002f68 00000008 b basetime.6535 20000c00 00000008 b callout_queue 20000d50 00000008 b cos_phi_1 2000598c 00000008 B g_basetime 200007d8 00000008 d g_builtin_binfmt 20000144 00000008 D g_default_pthread_attr 20003398 00000008 B g_delayed_kufree 20005b34 00000008 b g_desalloc 20005b28 00000008 B g_desfree 200034cc 00000008 B g_inactivetasks 20005b48 00000008 B g_msgfree 20005b50 00000008 B g_msgfreeirq 20005b40 00000008 B g_msgqueues 20003390 00000008 B g_pendingtasks 200034bc 00000008 B g_readytorun 200059b0 00000008 B g_sigfreeaction 200059b8 00000008 B g_sigpendingaction 2000599c 00000008 B g_sigpendingirqaction 200059d0 00000008 B g_sigpendingirqsignal 200059c4 00000008 B g_sigpendingsignal 200033a0 00000008 B g_waitingformqnotempty 200033a8 00000008 B g_waitingformqnotfull 200033b0 00000008 B g_waitingforsemaphore 200034c4 00000008 B g_waitingforsignal 20003694 00000008 B g_wdactivelist 20003688 00000008 B g_wdfreelist 20002a70 00000008 b gps_time 20000d48 00000008 b lambda_0 20002938 00000008 b last_input.5938 20002a00 00000008 b last_input.5966 200028e8 00000008 b last_run.5937 20002958 00000008 b last_run.5964 20002310 00000008 b last_sensor_timestamp 200020f0 00000008 b last_sent_vfr 20002ac0 00000008 b logwriter_attr 20001b10 00000008 b loiter_start_time 200000e0 00000008 d partition_names_default 20002ae0 00000008 b perf_counters 20000d68 00000008 b phi_1 20000d20 00000008 B ppm_last_valid_decode 20000e08 00000008 b rtInf 20000df8 00000008 b rtMinusInf 20000de8 00000008 b rtNaN 20000d58 00000008 b scale 20000d60 00000008 b sin_phi_1 20002ad0 00000008 b start_time 20002f14 00000008 b test_args 20001e40 0000000c b _ZL6status 20000e40 0000000c b _ZL9gyro_bias 20000d7c 0000000c b _ZN4mathL5testAE 20000d70 0000000c b _ZN4mathL5testAE 20000d94 0000000c b _ZN4mathL5testBE 20000d88 0000000c b _ZN4mathL5testBE 20000dc4 0000000c b _ZN4mathL5testCE 20000da0 0000000c b _ZN4mathL5testDE 20000dac 0000000c b _ZN4mathL5testEE 20000db8 0000000c b _ZN4mathL5testFE 2000014c 0000000c D g_spawn_parmsem 20002aac 0000000c b logbuffer_cond 20002840 0000000c b status 20005b1c 0000000c b tree_sem 20000e88 00000010 b _ZL5armed 20000ea8 00000010 b _ZL6safety 200020d8 00000010 b airspeed 20002080 00000010 b armed 2000105c 00000010 b lb 20002a94 00000010 b lb 20002a78 00000010 b logbuffer_mutex 20001c30 00000010 b name_buf.14684 20000d2c 00000010 b ppm 20002fd8 00000010 b pwm_limit 20002f84 00000010 b r_page_servo_control_max 20002f74 00000010 b r_page_servo_control_min 20002fe8 00000010 b r_page_servo_disarmed 20002fb6 00000010 b r_page_servos 20002fc6 00000010 b servo_predicted 20000198 00000014 D stm32_i2c_ops 20000e70 00000018 b control_mode 200036cc 00000018 B g_work 20002920 00000018 b h.5944 200029bc 00000018 b h.5972 20001c40 00000018 b hil_battery_status 20002940 00000018 b p.5943 200036b0 00000018 b tm.4087 20000574 0000001a D g_daysbeforemonth 2000366c 0000001c B g_spawn_parms 20002a08 0000001c b p.5971 20002f94 00000020 b _ZL17actuator_controls 20000864 00000020 b _ZZN6BlinkM3ledEvE11t_led_color 20000a68 00000020 b addrTranslator 20003e44 00000020 b g_uart5rxfifo 20004264 00000020 b g_usart2rxfifo 20004284 00000020 b g_usart6rxfifo 20002a50 00000020 b log_dir 200008a0 00000020 b serial_dma_call.6453 20001cf4 00000024 b _ZL4vcmd 20000550 00000024 d g_spi1dev 2000052c 00000024 d g_spi3dev 200058b4 00000024 b g_sysdev 20000c08 00000024 b latency_counters 20002880 00000024 b vcmd 20001dd8 00000028 b _ZL14vicon_position 20002058 00000028 b actuators_0 20000ccc 00000028 B ppm_buffer 20000cf4 00000028 b ppm_temp_buffer 20002818 00000028 b vicon_position 200028f0 0000002c b pitch_controller.5941 200029d4 0000002c b pitch_rate_controller.5968 200028b8 0000002c b roll_controller.5942 20002960 0000002c b roll_rate_controller.5969 2000298c 0000002c b yaw_rate_controller.5970 20001e58 00000030 b _ZL19offboard_control_sp 20005920 00000030 b g_wrfile 200027c8 00000030 b m_mavlink_status.15440 200019d4 00000030 b m_mavlink_status.15727 20002850 00000030 b offboard_control_sp 200020f8 00000038 b global_pos 20001e08 00000038 b hil_global_pos 20002138 00000038 b rc_raw 200001ac 00000038 D stm32_i2c1_priv 20000160 00000038 D stm32_i2c2_priv 200001e4 00000038 D stm32_i2c3_priv 20002f2c 0000003c b g_at24c 20005950 0000003c b g_mmcsdslot 200008cc 00000040 b _ZN6deviceL11irq_entriesE 20005b60 00000040 b freelist 20000c6c 00000040 B ppm_edge_history 20000c2c 00000040 B ppm_pulse_history 200058d8 00000048 B g_volume 20001d18 00000048 b hil_local_pos 20002090 00000048 b local_pos 200007f0 00000050 b outputs.5849 200000f0 00000054 d sensors 20002318 00000060 b mavlink_subs 20000ed0 00000070 b _ZL6status 20001fe8 00000070 b att 20001d60 00000070 b hil_attitude 20001f78 00000070 b v_status 20000750 00000081 d g_bootcodeblob 20001c60 00000090 b hil_sensors 20000f98 000000c0 b gpio_led_data 20000468 000000c4 d g_uart5priv 200002e0 000000c4 d g_usart1priv 200003a4 000000c4 d g_usart2priv 2000021c 000000c4 d g_usart6priv 20001e90 000000d8 b hil_gps 20000940 000000f8 b _esc 200033b8 00000100 B g_pidhash 20001a04 00000107 b missionlib_msg_buf 20001b20 00000110 b tx_msg.14686 200059d8 00000140 b g_otgfsdev 200036e4 0000015c B g_mmheap 20000a88 00000160 b Motor 20003204 0000018c B g_irqvector 20002178 00000190 b rc 200034d4 00000198 b g_idletcb 20000590 000001c0 d g_dma 20003000 00000200 b g_iobuffer 200044a4 00000200 b g_uart5rxbuffer 20003a44 00000200 b g_uart5txbuffer 200042a4 00000200 b g_usart1rxbuffer 20003844 00000200 b g_usart1txbuffer 20003e64 00000200 b g_usart2rxbuffer 20004064 00000200 b g_usart2txbuffer 20003c44 00000200 b g_usart6rxbuffer 200046a4 00000200 b g_usart6txbuffer 20002af8 00000418 B system_load 20002388 00000440 b m_mavlink_buffer.15444 20001078 00000440 b m_mavlink_buffer.15731 200014d0 000004f8 b wpm_s 200048b0 00001000 b up_interruptstack

LorenzMeier commented 10 years ago

Hi!

Thanks for the pointers. We should indeed do a sweep on the stack sizes. I'd be happy to take pull requests if you can show the same documentation as here that a reduction is safe.

LorenzMeier commented 10 years ago

And if you do, please make sure to arm the vehicle with GPS reception, if possible.

pigeonhunter commented 10 years ago

I understand that safety is a major issue, and I'm concerned that only 6K free when armed and "flying" on the bench in manual with no GPS reception is cutting it close.

I'll do some research concerning safely estimating appropriate stack sizes. Reducing them should help some, but I'm not convinced they are the main cause of the memory issues i'm seeing. I only mentioned them because in some cases they are 2-3x the reported used memory (12x in one case), which seemed excessive. In total they add up to only ~62K.

I'm still planning on stepping through the startup to document the memory usage. That should hopefully help clear things up a bit. I'll keep you posted.

BTW the vehicle in this case is a mere quadrotor. I assume the issue would be worse with more actuators involved.

px4dev commented 10 years ago

Actuators are cheap; for the most part they are just mixer entries. What tends to hurt a lot are statically allocated data structures in applications that aren't being run - if you have three different filters and they aren't dynamically allocating their structures at runtime you are paying for all of them.

pigeonhunter commented 10 years ago

Nothing too exiting with the step-through. Each app consumed about what was expected. I stepped backwards by stopping apps instead of starting them in order and ended up with:

nsh> free total used free largest Mem: 167136 55024 112112 23328

nsh> ps PID PRI SCHD TYPE NP STATE NAME 0 0 FIFO TASK READY Idle Task() 1 192 FIFO KTHREAD WAITSIG hpwork() 2 50 FIFO KTHREAD READY lpwork() 3 100 FIFO TASK WAITSEM init() 39 100 FIFO TASK RUNNING nshterm(100068e0)

I can't really account for the used 55042 so I'll just call it overhead for now. Could there still be an issue with the build system?

Pending further enlightenment, I've embarked on a stack size estimation sweep. I just want to run my approach by you. I'm resorting to an hybrid experimental approach to estimating the sizes. First I review the application and attempt to identify the most stack intensive path. Then I run the system and induce the selected path(s), ie accelerometer calibration. I record the stack usage high-water-mark using "top". I then take this number and increase it by approximately 25% to account for missed paths and to leave some room for future code changes. I then increase this number to the nearest multiple of 8.

The result is the new stack size.

So far I've come up with

1024 for px4io 2088 for commander 1728 for commander_low_prio

Each have been tested in flight and so far everything is ok, and result in a savings of 3K.

IMHO, this approach should produce reasonably safe, yet not excessive stack sizes. As the issue stood, a freshly autostarted (4012) master branch px4fmu v1.7 + px4io v1.3 couldn't run the mag calibration routine without an out of memory error. I'm projecting a free memory increase of ~10-15 kB.

px4dev commented 10 years ago

On 27 Jan 2014, at 9:38 pm, pigeonhunter notifications@github.com wrote:

Nothing too exiting with the step-through. Each app consumed about what was expected. I stepped backwards by stopping apps instead of starting them in order

Apps don’t necessarily clean up correctly, so I’m not sure that’s a good idea. Perhaps a short sleep and then call ‘free’ between app starts?

and ended up with:

nsh> free total used free largest Mem: 167136 55024 112112 23328

nsh> ps PID PRI SCHD TYPE NP STATE NAME 0 0 FIFO TASK READY Idle Task() 1 192 FIFO KTHREAD WAITSIG hpwork() 2 50 FIFO KTHREAD READY lpwork() 3 100 FIFO TASK WAITSEM init() 39 100 FIFO TASK RUNNING nshterm(100068e0)

I can't really account for the used 55042 so I'll just call it overhead for now. Could there still be an issue with the build system?

Not sure what you’re referring to here. An issue with the build system isn’t going to call malloc; I would SWAG this as possibly being more likely to be leaks from applications, but it’s a hard call.

It might be educational to dump the actual heap allocation sizes; there’s a GDB macro for it, but we should probably teach ‘free’ how to do it as well.

Pending further enlightenment, I've embarked on a stack size estimation sweep. I just want to run my approach by you. I'm resorting to an hybrid experimental approach to estimating the sizes. First I review the application and attempt to identify the most stack intensive path. Then I run the system and induce the selected path(s), ie accelerometer calibration. I record the stack usage high-water-mark using "top". I then take this number and increase it by approximately 25% to account for missed paths and to leave some room for future code changes. I then increase this number to the nearest multiple of 8.

This sounds solid. 25% is a generous over-estimation.

pigeonhunter commented 10 years ago

Apps don’t necessarily clean up correctly, so I’m not sure that’s a good idea. Perhaps a short sleep and then call ‘free’ between app starts?

That was more work :-)

I can't really account for the used 55042 so I'll just call it overhead for now. Could there still be an issue with the build system?

Not sure what you’re referring to here. An issue with the build system isn’t going to call malloc; I would SWAG this as possibly being more likely to be leaks from applications, but it’s a hard call.

I recall that there was an earlier bug that caused ROMFS to be written to RAM. Perhaps a quick look?

It might be educational to dump the actual heap allocation sizes; there’s a GDB macro for it, but we should probably teach ‘free’ how to do it as well.

Something like gdb-heap would be very nice indeed.

25% is a generous over-estimation.

I thought so too. I decided on it to allow room for continued development without too much risk/hassle. We can always shave some off later, but there are diminishing returns.

And I there may be cases where I break that rule. Attitude_estimator_ekf for instance is already running with about that much overhead. It's very reliably using about ~11k of its ~14k stack with very little fluctuation. It might be a candidate for a closer shave, or retired.

px4dev commented 10 years ago

On 27 Jan 2014, at 10:35 pm, pigeonhunter notifications@github.com wrote:

Not sure what you’re referring to here. An issue with the build system isn’t going to call malloc; I would SWAG this as possibly being more likely to be leaks from applications, but it’s a hard call.

I recall that there was an earlier bug that caused ROMFS to be written to RAM. Perhaps a quick look?

Gotcha - that was in the data segment, not the heap.

It might be educational to dump the actual heap allocation sizes; there’s a GDB macro for it, but we should probably teach ‘free’ how to do it as well.

Something like gdb-heap would be very nice indeed.

I’ll take a poke at it; might be quick and easy.

LorenzMeier commented 10 years ago

Unfortunately I had to revert the merged pull request, as we hit corner cases and crashes in HIL. A few things to consider: printf() seems to require 500 - 1K stack, so a code path resulting in a printf() not always executed can be fatal. I plan to address this issue by mostly eliminating static RAM usage and trim obviously excessive stack sizes, but very carefully and one by one.

Your effort and contribution is really appreciated and I see the need for a cleanup. I just want to avoid in-flight crashes.

pigeonhunter commented 10 years ago

Oops... sorry about that. Normal flight was tested fairly extensively, but I have limited ability to test HIL mode. I'm running into problems getting HIL running w/ flightgear. :-(

BTW: I'm not the stack police. I just want to perform fairly standard user operations, like logging, sensor calibration, etc. with off-the-shelf autostart configurations.

@DrTon Can you id the thread that was overflowing? Maybe we can fix that one...

DrTon commented 10 years ago

First problem was "mavlink", but after reverting it I got few crashes in the middle of flight on beta and on master, so we decided with Lorenz to not play with it, and revert everything. It should be done again, but one-by-one, with enough gap (800-900bytes) and much more testing after each change. E.g. commander had extremly small gap after all calibrations, ~120 bytes.

pigeonhunter commented 10 years ago

I found two problems w/ mavlink. Both the main thread and the mavlink_rcv_uart thread overflowed in HIL mode. I agree that more testing is necessary.

julianoes commented 10 years ago

I think the current state is RAM-wise ok, right?

LorenzMeier commented 10 years ago

I think so - we just have to keep watching. But since a couple of our wing-wings are FMUv1, closing this now.