diff --git a/Makefile b/Makefile index 7d0fc725..a23f5047 100644 --- a/Makefile +++ b/Makefile @@ -46,9 +46,10 @@ INCLUDE_CENTRAL := -Imenu -Iosd -I../menu -I../osd -Icode/r_central/menu -Icode/ FOLDER_BASE=code/base FOLDER_COMMON=code/common FOLDER_RADIO=code/radio +FOLDER_UTILS=code/utils FOLDER_START=code/r_start -FOLDER_UTILS=code/r_utils +FOLDER_RUTILS=code/r_utils FOLDER_I2C=code/r_i2c FOLDER_VEHICLE=code/r_vehicle FOLDER_STATION=code/r_station @@ -82,6 +83,12 @@ $(FOLDER_START)/%.o: $(FOLDER_START)/%.c $(FOLDER_START)/%.o: $(FOLDER_START)/%.cpp $(CXX) $(_CFLAGS) -c -o $@ $< +$(FOLDER_RUTILS)/%.o: $(FOLDER_RUTILS)/%.c + $(CC) $(_CFLAGS) -c -o $@ $< + +$(FOLDER_RUTILS)/%.o: $(FOLDER_RUTILS)/%.cpp + $(CXX) $(_CFLAGS) -c -o $@ $< + $(FOLDER_UTILS)/%.o: $(FOLDER_UTILS)/%.c $(CC) $(_CFLAGS) -c -o $@ $< @@ -158,30 +165,31 @@ drmutil.o: code/r_tests/drmutil.c $(CC) $(_CFLAGS) $(CFLAGS_RENDERER) -c -o $@ $< MODULE_MINIMUM_BASE := $(FOLDER_BASE)/base.o $(FOLDER_BASE)/config.o $(FOLDER_BASE)/gpio.o $(FOLDER_BASE)/hardware_i2c.o $(FOLDER_BASE)/hardware_radio_sik.o $(FOLDER_BASE)/hardware_radio_serial.o $(FOLDER_BASE)/hardware_serial.o $(FOLDER_BASE)/hardware.o $(FOLDER_BASE)/hardware_radio.o $(FOLDER_BASE)/hardware_radio_txpower.o $(FOLDER_BASE)/hw_procs.o -MODULE_MINIMUM_RADIO := $(FOLDER_COMMON)/radio_stats.o $(FOLDER_RADIO)/radio_duplicate_det.o $(FOLDER_RADIO)/radio_rx.o $(FOLDER_RADIO)/radio_tx.o $(FOLDER_RADIO)/radiolink.o $(FOLDER_RADIO)/radiopackets_rc.o $(FOLDER_RADIO)/radiopackets_short.o $(FOLDER_RADIO)/radiopackets_wfbohd.o $(FOLDER_RADIO)/radiopackets2.o $(FOLDER_RADIO)/radiopacketsqueue.o $(FOLDER_RADIO)/radiotap.o +MODULE_MINIMUM_RADIO := $(FOLDER_COMMON)/radio_stats.o $(FOLDER_RADIO)/radio_duplicate_det.o $(FOLDER_RADIO)/radio_rx.o $(FOLDER_RADIO)/radio_tx.o $(FOLDER_RADIO)/radiolink.o $(FOLDER_RADIO)/radiopackets_rc.o $(FOLDER_RADIO)/radiopackets_short.o $(FOLDER_RADIO)/radiopackets_wfbohd.o $(FOLDER_RADIO)/radiopackets2.o $(FOLDER_RADIO)/radiopacketsqueue.o $(FOLDER_RADIO)/radiotap.o $(FOLDER_BASE)/tx_powers.o MODULE_MINIMUM_COMMON := $(FOLDER_COMMON)/string_utils.o MODULE_BASE := $(FOLDER_BASE)/base.o $(FOLDER_BASE)/shared_mem.o $(FOLDER_BASE)/config.o $(FOLDER_BASE)/hardware.o $(FOLDER_BASE)/hardware_camera.o $(FOLDER_BASE)/hardware_files.o $(FOLDER_BASE)/hw_procs.o $(FOLDER_BASE)/utils.o $(FOLDER_BASE)/encr.o $(FOLDER_BASE)/hardware_i2c.o $(FOLDER_BASE)/alarms.o $(FOLDER_BASE)/hardware_radio.o $(FOLDER_BASE)/hardware_radio_serial.o $(FOLDER_BASE)/hardware_serial.o $(FOLDER_BASE)/hardware_radio_sik.o $(FOLDER_BASE)/hardware_radio_txpower.o $(FOLDER_BASE)/ruby_ipc.o $(FOLDER_BASE)/commands.o $(FOLDER_BASE)/hardware_files.o -MODULE_BASE2 := $(FOLDER_BASE)/gpio.o $(FOLDER_BASE)/ctrl_settings.o $(FOLDER_BASE)/controller_utils.o $(FOLDER_BASE)/controller_rt_info.o $(FOLDER_BASE)/vehicle_rt_info.o $(FOLDER_BASE)/ctrl_preferences.o $(FOLDER_BASE)/ctrl_interfaces.o +MODULE_BASE2 := $(FOLDER_BASE)/gpio.o $(FOLDER_BASE)/ctrl_settings.o $(FOLDER_UTILS)/utils_controller.o $(FOLDER_BASE)/controller_rt_info.o $(FOLDER_BASE)/vehicle_rt_info.o $(FOLDER_BASE)/ctrl_preferences.o $(FOLDER_BASE)/ctrl_interfaces.o MODULE_COMMON := $(FOLDER_COMMON)/string_utils.o $(FOLDER_COMMON)/relay_utils.o MODULE_MODELS := $(FOLDER_BASE)/models.o $(FOLDER_BASE)/models_list.o MODULE_RADIO := $(FOLDER_COMMON)/radio_stats.o $(FOLDER_RADIO)/fec.o $(FOLDER_RADIO)/radio_duplicate_det.o $(FOLDER_RADIO)/radio_rx.o $(FOLDER_RADIO)/radio_tx.o $(FOLDER_RADIO)/radiolink.o $(FOLDER_RADIO)/radiopackets_rc.o $(FOLDER_RADIO)/radiopackets_short.o $(FOLDER_RADIO)/radiopackets2.o $(FOLDER_RADIO)/radiopacketsqueue.o $(FOLDER_RADIO)/radiotap.o -MODULE_VEHICLE := $(FOLDER_VEHICLE)/shared_vars.o $(FOLDER_VEHICLE)/timers.o $(FOLDER_VEHICLE)/adaptive_video.o $(FOLDER_VEHICLE)/utils_vehicle.o $(FOLDER_VEHICLE)/launchers_vehicle.o $(FOLDER_BASE)/vehicle_rt_info.o +MODULE_VEHICLE := $(FOLDER_VEHICLE)/shared_vars.o $(FOLDER_VEHICLE)/timers.o $(FOLDER_VEHICLE)/adaptive_video.o $(FOLDER_UTILS)/utils_vehicle.o $(FOLDER_VEHICLE)/launchers_vehicle.o $(FOLDER_BASE)/vehicle_rt_info.o MODULE_STATION := $(FOLDER_STATION)/shared_vars.o $(FOLDER_STATION)/shared_vars_state.o $(FOLDER_STATION)/timers.o $(FOLDER_STATION)/adaptive_video.o CENTRAL_MENU_ITEMS_ALL := $(FOLDER_CENTRAL_MENU)/menu_items.o $(FOLDER_CENTRAL_MENU)/menu_item_select_base.o $(FOLDER_CENTRAL_MENU)/menu_item_select.o $(FOLDER_CENTRAL_MENU)/menu_item_slider.o $(FOLDER_CENTRAL_MENU)/menu_item_range.o $(FOLDER_CENTRAL_MENU)/menu_item_edit.o $(FOLDER_CENTRAL_MENU)/menu_item_section.o $(FOLDER_CENTRAL_MENU)/menu_item_text.o $(FOLDER_CENTRAL_MENU)/menu_item_legend.o $(FOLDER_CENTRAL_MENU)/menu_item_checkbox.o $(FOLDER_CENTRAL_MENU)/menu_item_radio.o -CENTRAL_MENU_ALL1 := $(FOLDER_CENTRAL_MENU)/menu.o $(FOLDER_CENTRAL_MENU)/menu_objects.o $(FOLDER_CENTRAL_MENU)/menu_preferences_buttons.o $(FOLDER_CENTRAL_MENU)/menu_root.o $(FOLDER_CENTRAL_MENU)/menu_search.o $(FOLDER_CENTRAL_MENU)/menu_spectator.o $(FOLDER_CENTRAL_MENU)/menu_vehicles.o $(FOLDER_CENTRAL_MENU)/menu_vehicle.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_general.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_expert.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_video.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_video_bidir.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_camera.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_osd.o $(FOLDER_CENTRAL_MENU)/menu_confirmation.o $(FOLDER_CENTRAL_MENU)/menu_storage.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_telemetry.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_video_encodings.o $(FOLDER_CENTRAL_MENU)/menu_text.o $(FOLDER_CENTRAL_MENU)/menu_tx_power.o $(FOLDER_CENTRAL_MENU)/menu_tx_power_8812eu.o $(FOLDER_CENTRAL_MENU)/menu_calibrate_hdmi.o +CENTRAL_MENU_ALL1 := $(FOLDER_CENTRAL_MENU)/menu.o $(FOLDER_CENTRAL_MENU)/menu_objects.o $(FOLDER_CENTRAL_MENU)/menu_preferences_buttons.o $(FOLDER_CENTRAL_MENU)/menu_root.o $(FOLDER_CENTRAL_MENU)/menu_search.o $(FOLDER_CENTRAL_MENU)/menu_spectator.o $(FOLDER_CENTRAL_MENU)/menu_vehicles.o $(FOLDER_CENTRAL_MENU)/menu_vehicle.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_general.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_expert.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_video.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_video_bidir.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_camera.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_osd.o $(FOLDER_CENTRAL_MENU)/menu_confirmation.o $(FOLDER_CENTRAL_MENU)/menu_storage.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_telemetry.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_video_encodings.o $(FOLDER_CENTRAL_MENU)/menu_text.o $(FOLDER_CENTRAL_MENU)/menu_tx_raw_power.o $(FOLDER_CENTRAL_MENU)/menu_calibrate_hdmi.o CENTRAL_MENU_ALL2 := $(FOLDER_CENTRAL_MENU)/menu_vehicle_relay.o $(FOLDER_CENTRAL_MENU)/menu_controller.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_alarms.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_camera_gains.o $(FOLDER_CENTRAL_MENU)/menu_controller_peripherals.o $(FOLDER_CENTRAL_MENU)/menu_controller_expert.o $(FOLDER_CENTRAL_MENU)/menu_system.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_osd_instruments.o $(FOLDER_CENTRAL_MENU)/menu_preferences_ui.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_video_profile.o $(FOLDER_CENTRAL_MENU)/menu_confirmation_import.o $(FOLDER_CENTRAL_MENU)/menu_system_alarms.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_selector.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_osd_widgets.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_osd_widget.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_dev.o $(FOLDER_CENTRAL_MENU)/menu_controller_dev.o $(FOLDER_CENTRAL_MENU)/menu_controller_dev_stats.o -CENTRAL_MENU_ALL3 := $(FOLDER_CENTRAL_MENU)/menu_vehicle_management.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_import.o $(FOLDER_CENTRAL_MENU)/menu_switch_vehicle.o $(FOLDER_CENTRAL_MENU)/menu_controller_joystick.o $(FOLDER_CENTRAL_MENU)/menu_system_all_params.o $(FOLDER_CENTRAL_MENU)/menu_color_picker.o $(FOLDER_CENTRAL_MENU)/menu_controller_video.o $(FOLDER_CENTRAL_MENU)/menu_controller_telemetry.o $(FOLDER_CENTRAL_MENU)/menu_update_vehicle.o $(FOLDER_CENTRAL_MENU)/menu_device_i2c.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_osd_stats.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_audio.o $(FOLDER_CENTRAL_MENU)/menu_channels_select.o $(FOLDER_CENTRAL_MENU)/menu_tx_power_max.o $(FOLDER_CENTRAL_MENU)/menu_system_dev_logs.o $(FOLDER_CENTRAL_MENU)/menu_item_vehicle.o $(FOLDER_CENTRAL_MENU)/menu_radio_config.o $(FOLDER_CENTRAL_MENU)/menu_preferences.o -CENTRAL_MENU_ALL4 := $(FOLDER_CENTRAL_MENU)/menu_vehicle_data_link.o $(FOLDER_CENTRAL_MENU)/menu_controller_network.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_osd_plugins.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_instruments_general.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_osd_elements.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_osd_plugin.o $(FOLDER_CENTRAL_MENU)/menu_controller_plugins.o $(FOLDER_CENTRAL_MENU)/menu_controller_encryption.o $(FOLDER_CENTRAL_MENU)/menu_search_connect.o $(FOLDER_CENTRAL_MENU)/menu_system_hardware.o $(FOLDER_CENTRAL_MENU)/menu_confirmation_hdmi.o $(FOLDER_CENTRAL_MENU)/menu_controller_recording.o $(FOLDER_CENTRAL_MENU)/menu_system_video_profiles.o $(FOLDER_CENTRAL_MENU)/menu_info_booster.o $(FOLDER_CENTRAL_MENU)/menu_controller_radio_interface.o $(FOLDER_CENTRAL_MENU)/menu_negociate_radio.o +CENTRAL_MENU_ALL3 := $(FOLDER_CENTRAL_MENU)/menu_vehicle_management.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_import.o $(FOLDER_CENTRAL_MENU)/menu_switch_vehicle.o $(FOLDER_CENTRAL_MENU)/menu_controller_joystick.o $(FOLDER_CENTRAL_MENU)/menu_system_all_params.o $(FOLDER_CENTRAL_MENU)/menu_color_picker.o $(FOLDER_CENTRAL_MENU)/menu_controller_video.o $(FOLDER_CENTRAL_MENU)/menu_controller_telemetry.o $(FOLDER_CENTRAL_MENU)/menu_update_vehicle.o $(FOLDER_CENTRAL_MENU)/menu_device_i2c.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_osd_stats.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_audio.o $(FOLDER_CENTRAL_MENU)/menu_channels_select.o $(FOLDER_CENTRAL_MENU)/menu_system_dev_logs.o $(FOLDER_CENTRAL_MENU)/menu_item_vehicle.o $(FOLDER_CENTRAL_MENU)/menu_radio_config.o $(FOLDER_CENTRAL_MENU)/menu_preferences.o +CENTRAL_MENU_ALL4 := $(FOLDER_CENTRAL_MENU)/menu_vehicle_data_link.o $(FOLDER_CENTRAL_MENU)/menu_controller_network.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_osd_plugins.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_instruments_general.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_osd_elements.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_osd_plugin.o $(FOLDER_CENTRAL_MENU)/menu_controller_plugins.o $(FOLDER_CENTRAL_MENU)/menu_controller_encryption.o $(FOLDER_CENTRAL_MENU)/menu_search_connect.o $(FOLDER_CENTRAL_MENU)/menu_system_hardware.o $(FOLDER_CENTRAL_MENU)/menu_confirmation_hdmi.o $(FOLDER_CENTRAL_MENU)/menu_controller_recording.o $(FOLDER_CENTRAL_MENU)/menu_system_video_profiles.o $(FOLDER_CENTRAL_MENU)/menu_info_booster.o $(FOLDER_CENTRAL_MENU)/menu_controller_radio_interface.o $(FOLDER_CENTRAL_MENU)/menu_negociate_radio.o $(FOLDER_CENTRAL_MENU)/menu_about.o CENTRAL_MENU_ALL5 := $(FOLDER_CENTRAL_MENU)/menu_system_dev_stats.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_radio_link.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_radio_interface.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_management_plugins.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_peripherals.o $(FOLDER_CENTRAL_MENU)/menu_confirmation_delete_logs.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_radio.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_cpu_oipc.o $(FOLDER_CENTRAL_MENU)/menu_confirmation_vehicle_board.o +CENTRAL_MENU_ALL6 := $(FOLDER_CENTRAL_MENU)/menu_controller_radio.o CENTRAL_MENU_RC := $(FOLDER_CENTRAL_MENU)/menu_vehicle_rc.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_rc_failsafe.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_rc_channels.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_rc_expo.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_rc_camera.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_rc_input.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_functions.o CENTRAL_MENU_RADIO := $(FOLDER_CENTRAL_MENU)/menu_controller_radio_interface_sik.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_radio_link_sik.o $(FOLDER_CENTRAL_MENU)/menu_diagnose_radio_link.o $(FOLDER_CENTRAL_MENU)/menu_vehicle_radio_link_elrs.o CENTRAL_POPUP_ALL := $(FOLDER_CENTRAL)/popup.o $(FOLDER_CENTRAL)/popup_log.o $(FOLDER_CENTRAL)/popup_commands.o $(FOLDER_CENTRAL)/popup_camera_params.o CENTRAL_RENDER_ALL := $(FOLDER_CENTRAL)/colors.o $(FOLDER_CENTRAL)/render_commands.o $(FOLDER_CENTRAL)/render_joysticks.o $(FOLDER_CENTRAL)/process_router_messages.o CENTRAL_OSD_ALL := $(FOLDER_CENTRAL_OSD)/osd_common.o $(FOLDER_CENTRAL_OSD)/osd.o $(FOLDER_CENTRAL_OSD)/osd_stats.o $(FOLDER_CENTRAL_OSD)/osd_debug_stats.o $(FOLDER_CENTRAL_OSD)/osd_ahi.o $(FOLDER_CENTRAL_OSD)/osd_lean.o $(FOLDER_CENTRAL_OSD)/osd_warnings.o $(FOLDER_CENTRAL_OSD)/osd_gauges.o $(FOLDER_CENTRAL_OSD)/osd_plugins.o $(FOLDER_CENTRAL_OSD)/osd_stats_dev.o $(FOLDER_CENTRAL_OSD)/osd_stats_video_bitrate.o $(FOLDER_CENTRAL_OSD)/osd_links.o $(FOLDER_CENTRAL_OSD)/osd_stats_radio.o $(FOLDER_CENTRAL_OSD)/osd_widgets.o $(FOLDER_CENTRAL_OSD)/osd_widgets_builtin.o $(FOLDER_BASE)/vehicle_rt_info.o -CENTRAL_ALL := $(FOLDER_CENTRAL)/notifications.o $(FOLDER_CENTRAL)/launchers_controller.o $(FOLDER_CENTRAL)/local_stats.o $(FOLDER_CENTRAL)/rx_scope.o $(FOLDER_CENTRAL)/forward_watch.o $(FOLDER_CENTRAL)/timers.o $(FOLDER_CENTRAL)/ui_alarms.o $(FOLDER_CENTRAL)/media.o $(FOLDER_CENTRAL)/pairing.o $(FOLDER_CENTRAL)/link_watch.o $(FOLDER_CENTRAL)/warnings.o $(FOLDER_CENTRAL)/handle_commands.o $(FOLDER_CENTRAL)/events.o $(FOLDER_CENTRAL)/shared_vars_ipc.o $(FOLDER_CENTRAL)/shared_vars_state.o $(FOLDER_CENTRAL)/shared_vars_osd.o $(FOLDER_CENTRAL)/fonts.o $(FOLDER_CENTRAL)/keyboard.o $(FOLDER_CENTRAL)/quickactions.o $(FOLDER_CENTRAL)/shared_vars.o $(FOLDER_BASE)/camera_utils.o $(FOLDER_CENTRAL)/parse_msp.o $(FOLDER_BASE)/hardware_files.o -CENTRAL_RADIO := $(FOLDER_RADIO)/radiopackets2.o $(FOLDER_RADIO)/radiopackets_short.o $(FOLDER_RADIO)/radiotap.o +CENTRAL_ALL := $(FOLDER_CENTRAL)/notifications.o $(FOLDER_CENTRAL)/launchers_controller.o $(FOLDER_CENTRAL)/local_stats.o $(FOLDER_CENTRAL)/rx_scope.o $(FOLDER_CENTRAL)/forward_watch.o $(FOLDER_CENTRAL)/timers.o $(FOLDER_CENTRAL)/ui_alarms.o $(FOLDER_CENTRAL)/media.o $(FOLDER_CENTRAL)/pairing.o $(FOLDER_CENTRAL)/link_watch.o $(FOLDER_CENTRAL)/warnings.o $(FOLDER_CENTRAL)/handle_commands.o $(FOLDER_CENTRAL)/events.o $(FOLDER_CENTRAL)/shared_vars_ipc.o $(FOLDER_CENTRAL)/shared_vars_state.o $(FOLDER_CENTRAL)/shared_vars_osd.o $(FOLDER_CENTRAL)/fonts.o $(FOLDER_CENTRAL)/keyboard.o $(FOLDER_CENTRAL)/quickactions.o $(FOLDER_CENTRAL)/shared_vars.o $(FOLDER_BASE)/camera_utils.o $(FOLDER_CENTRAL)/parse_msp.o $(FOLDER_BASE)/hardware_files.o $(FOLDER_COMMON)/strings_table.o +CENTRAL_RADIO := $(FOLDER_RADIO)/radiopackets2.o $(FOLDER_RADIO)/radiopackets_short.o $(FOLDER_RADIO)/radiotap.o $(FOLDER_BASE)/tx_powers.o all: vehicle station ruby_i2c ruby_plugins ruby_central tests @@ -193,7 +201,7 @@ else station: ruby_start ruby_utils ruby_controller ruby_rt_station ruby_tx_rc ruby_rx_telemetry endif -ruby_central: $(FOLDER_CENTRAL)/ruby_central.o $(MODULE_BASE) $(MODULE_MODELS) $(MODULE_COMMON) $(MODULE_BASE2) $(CENTRAL_MENU_ITEMS_ALL) $(CENTRAL_MENU_ALL1) $(CENTRAL_RENDER_CODE) $(CENTRAL_MENU_ALL2) $(CENTRAL_MENU_ALL3) $(CENTRAL_MENU_ALL4) $(CENTRAL_MENU_ALL5) $(CENTRAL_MENU_RC) $(CENTRAL_MENU_RADIO) $(CENTRAL_POPUP_ALL) $(CENTRAL_RENDER_ALL) $(CENTRAL_OSD_ALL) $(CENTRAL_ALL) $(CENTRAL_RADIO) $(FOLDER_BASE)/shared_mem_controller_only.o $(FOLDER_BASE)/hdmi.o $(FOLDER_COMMON)/favorites.o $(FOLDER_BASE)/plugins_settings.o \ +ruby_central: $(FOLDER_CENTRAL)/ruby_central.o $(MODULE_BASE) $(MODULE_MODELS) $(MODULE_COMMON) $(MODULE_BASE2) $(CENTRAL_MENU_ITEMS_ALL) $(CENTRAL_MENU_ALL1) $(CENTRAL_RENDER_CODE) $(CENTRAL_MENU_ALL2) $(CENTRAL_MENU_ALL3) $(CENTRAL_MENU_ALL4) $(CENTRAL_MENU_ALL5) $(CENTRAL_MENU_ALL6) $(CENTRAL_MENU_RC) $(CENTRAL_MENU_RADIO) $(CENTRAL_POPUP_ALL) $(CENTRAL_RENDER_ALL) $(CENTRAL_OSD_ALL) $(CENTRAL_ALL) $(CENTRAL_RADIO) $(FOLDER_BASE)/shared_mem_controller_only.o $(FOLDER_BASE)/hdmi.o $(FOLDER_COMMON)/favorites.o $(FOLDER_BASE)/plugins_settings.o \ $(FOLDER_BASE)/core_plugins_settings.o $(FOLDER_BASE)/hardware_files.o $(FOLDER_COMMON)/models_connect_frequencies.o $(FOLDER_BASE)/shared_mem_i2c.o $(FOLDER_BASE)/video_capture_res.o $(CXX) $(_CFLAGS) $(CFLAGS_RENDERER) -export-dynamic -o $@ $^ $(_LDFLAGS) -ldl $(LDFLAGS_CENTRAL) $(LDFLAGS_CENTRAL2) $(LDFLAGS_RENDERER) @@ -201,32 +209,32 @@ ruby_central: $(FOLDER_CENTRAL)/ruby_central.o $(MODULE_BASE) $(MODULE_MODELS) $ ruby_utils: ruby_logger ruby_initdhcp ruby_sik_config ruby_alive ruby_video_proc ruby_update ruby_update_worker ruby_start: $(FOLDER_START)/ruby_start.o $(FOLDER_START)/r_start_vehicle.o $(FOLDER_START)/r_test.o $(FOLDER_START)/r_initradio.o $(FOLDER_START)/first_boot.o \ - $(FOLDER_VEHICLE)/ruby_rx_commands.o $(FOLDER_BASE)/parser_h264.o $(FOLDER_BASE)/camera_utils.o $(FOLDER_VEHICLE)/video_source_csi.o $(FOLDER_VEHICLE)/ruby_rx_rc.o $(FOLDER_VEHICLE)/process_upload.o $(FOLDER_BASE)/commands.o $(FOLDER_BASE)/vehicle_settings.o $(FOLDER_BASE)/hardware_radio_txpower.o $(FOLDER_RADIO)/radiopackets2.o $(FOLDER_BASE)/ctrl_preferences.o $(FOLDER_BASE)/ctrl_interfaces.o $(FOLDER_VEHICLE)/hw_config_check.o $(MODULE_MINIMUM_BASE) $(MODULE_MODELS) $(MODULE_MINIMUM_COMMON) $(FOLDER_BASE)/ruby_ipc.o $(FOLDER_BASE)/ctrl_settings.o $(FOLDER_BASE)/controller_utils.o $(FOLDER_BASE)/utils.o $(FOLDER_BASE)/shared_mem.o $(FOLDER_VEHICLE)/launchers_vehicle.o $(FOLDER_VEHICLE)/shared_vars.o $(FOLDER_VEHICLE)/timers.o $(FOLDER_VEHICLE)/utils_vehicle.o $(FOLDER_BASE)/encr.o \ - $(FOLDER_BASE)/core_plugins_settings.o $(FOLDER_BASE)/hardware_camera.o $(FOLDER_BASE)/hardware_files.o + $(FOLDER_VEHICLE)/ruby_rx_commands.o $(FOLDER_BASE)/parser_h264.o $(FOLDER_BASE)/camera_utils.o $(FOLDER_VEHICLE)/video_source_csi.o $(FOLDER_VEHICLE)/ruby_rx_rc.o $(FOLDER_VEHICLE)/process_upload.o $(FOLDER_BASE)/commands.o $(FOLDER_BASE)/vehicle_settings.o $(FOLDER_BASE)/hardware_radio_txpower.o $(FOLDER_RADIO)/radiopackets2.o $(FOLDER_BASE)/ctrl_preferences.o $(FOLDER_BASE)/ctrl_interfaces.o $(FOLDER_VEHICLE)/hw_config_check.o $(MODULE_MINIMUM_BASE) $(MODULE_MODELS) $(MODULE_MINIMUM_COMMON) $(FOLDER_BASE)/ruby_ipc.o $(FOLDER_BASE)/ctrl_settings.o $(FOLDER_UTILS)/utils_controller.o $(FOLDER_BASE)/utils.o $(FOLDER_BASE)/shared_mem.o $(FOLDER_VEHICLE)/launchers_vehicle.o $(FOLDER_VEHICLE)/shared_vars.o $(FOLDER_VEHICLE)/timers.o $(FOLDER_UTILS)/utils_vehicle.o $(FOLDER_BASE)/encr.o \ + $(FOLDER_BASE)/core_plugins_settings.o $(FOLDER_BASE)/hardware_camera.o $(FOLDER_BASE)/hardware_files.o $(FOLDER_BASE)/tx_powers.o $(CXX) $(_CFLAGS) -o $@ $^ $(_LDFLAGS) -ldl ruby_i2c: $(FOLDER_I2C)/ruby_i2c.o $(MODULE_BASE) $(MODULE_MODELS) $(MODULE_COMMON) $(MODULE_BASE2) $(FOLDER_BASE)/shared_mem_i2c.o $(CXX) $(_CFLAGS) -o $@ $^ $(_LDFLAGS) -ruby_logger: $(FOLDER_UTILS)/ruby_logger.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_MODELS) $(MODULE_COMMON) +ruby_logger: $(FOLDER_RUTILS)/ruby_logger.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_MODELS) $(MODULE_COMMON) $(CXX) $(_CFLAGS) -o $@ $^ $(_LDFLAGS) -ruby_initdhcp: $(FOLDER_UTILS)/ruby_initdhcp.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_MODELS) $(MODULE_COMMON) +ruby_initdhcp: $(FOLDER_RUTILS)/ruby_initdhcp.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_MODELS) $(MODULE_COMMON) $(CXX) $(_CFLAGS) -o $@ $^ $(_LDFLAGS) -ruby_sik_config: $(FOLDER_UTILS)/ruby_sik_config.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_MODELS) $(MODULE_COMMON) +ruby_sik_config: $(FOLDER_RUTILS)/ruby_sik_config.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_MODELS) $(MODULE_COMMON) $(CXX) $(_CFLAGS) -o $@ $^ $(_LDFLAGS) -ldl -ruby_alive: $(FOLDER_UTILS)/ruby_alive.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_MODELS) $(MODULE_COMMON) +ruby_alive: $(FOLDER_RUTILS)/ruby_alive.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_MODELS) $(MODULE_COMMON) $(CXX) $(_CFLAGS) -o $@ $^ $(_LDFLAGS) -ruby_video_proc: $(FOLDER_UTILS)/ruby_video_proc.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_MODELS) $(MODULE_COMMON) +ruby_video_proc: $(FOLDER_RUTILS)/ruby_video_proc.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_MODELS) $(MODULE_COMMON) $(CXX) $(_CFLAGS) -o $@ $^ $(_LDFLAGS) -ruby_update: $(FOLDER_UTILS)/ruby_update.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_MODELS) $(MODULE_COMMON) $(FOLDER_BASE)/vehicle_settings.o +ruby_update: $(FOLDER_RUTILS)/ruby_update.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_MODELS) $(MODULE_COMMON) $(FOLDER_BASE)/vehicle_settings.o $(CXX) $(_CFLAGS) -o $@ $^ $(_LDFLAGS) -ruby_update_worker: $(FOLDER_UTILS)/ruby_update_worker.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_MODELS) $(MODULE_COMMON) +ruby_update_worker: $(FOLDER_RUTILS)/ruby_update_worker.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_MODELS) $(MODULE_COMMON) $(CXX) $(_CFLAGS) -o $@ $^ $(_LDFLAGS) ruby_tx_telemetry: $(FOLDER_VEHICLE)/ruby_tx_telemetry.o $(FOLDER_VEHICLE)/telemetry.o $(FOLDER_VEHICLE)/telemetry_ltm.o $(FOLDER_VEHICLE)/telemetry_mavlink.o $(FOLDER_VEHICLE)/telemetry_msp.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_COMMON) $(MODULE_RADIO) $(MODULE_MODELS) $(MODULE_VEHICLE) $(FOLDER_BASE)/parse_fc_telemetry.o $(FOLDER_BASE)/parse_fc_telemetry_ltm.o $(FOLDER_BASE)/vehicle_settings.o @@ -246,7 +254,7 @@ ruby_tx_rc: $(FOLDER_STATION)/ruby_tx_rc.o $(MODULE_BASE) $(MODULE_BASE2) $(MODU $(CXX) $(_CFLAGS) -o $@ $^ $(_LDFLAGS) ruby_rt_station: $(FOLDER_STATION)/ruby_rt_station.o $(MODULE_BASE) $(MODULE_BASE2) $(MODULE_COMMON) $(MODULE_RADIO) $(MODULE_MODELS) $(MODULE_STATION) $(FOLDER_STATION)/links_utils.o $(FOLDER_STATION)/packets_utils.o $(FOLDER_STATION)/process_local_packets.o $(FOLDER_STATION)/process_radio_in_packets.o $(FOLDER_STATION)/processor_rx_audio.o $(FOLDER_STATION)/processor_rx_video.o $(FOLDER_STATION)/video_rx_buffers.o $(FOLDER_STATION)/radio_links.o $(FOLDER_STATION)/relay_rx.o $(FOLDER_STATION)/test_link_params.o $(FOLDER_STATION)/process_video_packets.o $(FOLDER_STATION)/rx_video_output.o $(FOLDER_STATION)/rx_video_recording.o $(FOLDER_BASE)/shared_mem_controller_only.o $(FOLDER_COMMON)/models_connect_frequencies.o $(FOLDER_BASE)/parse_fc_telemetry.o $(FOLDER_BASE)/parse_fc_telemetry_ltm.o $(FOLDER_STATION)/radio_links_sik.o $(FOLDER_BASE)/radio_utils.o $(FOLDER_BASE)/core_plugins_settings.o $(FOLDER_BASE)/camera_utils.o \ - $(FOLDER_BASE)/parser_h264.o + $(FOLDER_BASE)/parser_h264.o $(FOLDER_BASE)/tx_powers.o $(CXX) $(_CFLAGS) -o $@ $^ $(_LDFLAGS) -ldl ruby_plugins: ruby_plugin_osd_ahi ruby_plugin_gauge_speed ruby_plugin_gauge_altitude ruby_plugin_gauge_ahi ruby_plugin_gauge_heading @@ -328,8 +336,8 @@ clean: ruby_central $(FOLDER_CENTRAL)/ruby_central test_log $(FOLDER_TESTS)/test_log ruby_plugin* \ $(FOLDER_VEHICLE)/ruby_tx_telemetry $(FOLDER_VEHICLE)/ruby_rt_vehicle \ $(FOLDER_STATION)/ruby_controller $(FOLDER_STATION)/ruby_rt_station $(FOLDER_STATION)/ruby_tx_rc $(FOLDER_STATION)/ruby_rx_telemetry \ - $(FOLDER_START)/ruby_start $(FOLDER_I2C)/ruby_i2c $(FOLDER_UTILS)/ruby_logger $(FOLDER_UTILS)/ruby_initdhcp $(FOLDER_UTILS)/ruby_sik_config $(FOLDER_UTILS)/ruby_alive $(FOLDER_UTILS)/ruby_video_proc $(FOLDER_UTILS)/ruby_update $(FOLDER_UTILS)/ruby_update_worker \ - $(FOLDER_BASE)/*.o $(FOLDER_COMMON)/*.o $(FOLDER_RADIO)/*.o $(FOLDER_START)/*.o $(FOLDER_UTILS)/*.o $(FOLDER_VEHICLE)/*.o $(FOLDER_STATION)/*.o \ + $(FOLDER_START)/ruby_start $(FOLDER_I2C)/ruby_i2c $(FOLDER_RUTILS)/ruby_logger $(FOLDER_RUTILS)/ruby_initdhcp $(FOLDER_RUTILS)/ruby_sik_config $(FOLDER_RUTILS)/ruby_alive $(FOLDER_RUTILS)/ruby_video_proc $(FOLDER_RUTILS)/ruby_update $(FOLDER_RUTILS)/ruby_update_worker \ + $(FOLDER_BASE)/*.o $(FOLDER_COMMON)/*.o $(FOLDER_RADIO)/*.o $(FOLDER_START)/*.o $(FOLDER_RUTILS)/*.o $(FOLDER_UTILS)/*.o $(FOLDER_VEHICLE)/*.o $(FOLDER_STATION)/*.o \ $(FOLDER_CENTRAL)/*.o $(FOLDER_CENTRAL_MENU)/*.o $(FOLDER_CENTRAL_OSD)/*.o $(FOLDER_CENTRAL_RENDERER)/*.o \ $(FOLDER_PLUGINS_OSD)/*.o code/public/utils/*.o code/r_player/*.o $(FOLDER_TESTS)/*.o \ code/r_i2c/*.o @@ -339,8 +347,8 @@ cleanstation: test_* ruby_controller ruby_rt_station ruby_tx_rc ruby_rx_telemetry \ test_log $(FOLDER_TESTS)/test_log ruby_plugin* \ $(FOLDER_STATION)/ruby_controller $(FOLDER_STATION)/ruby_rt_station $(FOLDER_STATION)/ruby_tx_rc $(FOLDER_STATION)/ruby_rx_telemetry \ - $(FOLDER_START)/ruby_start $(FOLDER_I2C)/ruby_i2c $(FOLDER_UTILS)/ruby_logger $(FOLDER_UTILS)/ruby_initdhcp $(FOLDER_UTILS)/ruby_sik_config $(FOLDER_UTILS)/ruby_alive $(FOLDER_UTILS)/ruby_video_proc $(FOLDER_UTILS)/ruby_update $(FOLDER_UTILS)/ruby_update_worker \ + $(FOLDER_START)/ruby_start $(FOLDER_I2C)/ruby_i2c $(FOLDER_RUTILS)/ruby_logger $(FOLDER_RUTILS)/ruby_initdhcp $(FOLDER_RUTILS)/ruby_sik_config $(FOLDER_RUTILS)/ruby_alive $(FOLDER_RUTILS)/ruby_video_proc $(FOLDER_RUTILS)/ruby_update $(FOLDER_RUTILS)/ruby_update_worker \ $(FOLDER_CENTRAL)/*.o $(FOLDER_CENTRAL_MENU)/*.o $(FOLDER_CENTRAL_OSD)/*.o $(FOLDER_CENTRAL_RENDERER)/*.o \ - $(FOLDER_BASE)/*.o $(FOLDER_COMMON)/*.o $(FOLDER_RADIO)/*.o $(FOLDER_START)/*.o $(FOLDER_UTILS)/*.o $(FOLDER_STATION)/*.o \ + $(FOLDER_BASE)/*.o $(FOLDER_COMMON)/*.o $(FOLDER_RADIO)/*.o $(FOLDER_START)/*.o $(FOLDER_RUTILS)/*.o $(FOLDER_UTILS)/*.o $(FOLDER_STATION)/*.o \ $(FOLDER_TESTS)/*.o $(FOLDER_PLUGINS_OSD)/*.o \ code/r_i2c/*.o code/r_utils/*.o code/r_player/*.o diff --git a/code/base/base.h b/code/base/base.h index 1fd17517..6b5f4015 100644 --- a/code/base/base.h +++ b/code/base/base.h @@ -29,10 +29,10 @@ typedef u32 __le32; #define LOGGER_MESSAGE_QUEUE_ID 123 #define SYSTEM_NAME "Ruby" -// dword: BB.BB.MM.mm (BB.BB: build number, MM: major ver, mm: minor ver) +// dword[3...0]: BB.BB.MM.mm (BB.BB: build number (highest bytes), MM: major ver, mm: minor ver (lowest byte)) #define SYSTEM_SW_VERSION_MAJOR 10 -#define SYSTEM_SW_VERSION_MINOR 0 -#define SYSTEM_SW_BUILD_NUMBER 245 +#define SYSTEM_SW_VERSION_MINOR 10 +#define SYSTEM_SW_BUILD_NUMBER 252 #if __BYTE_ORDER == __LITTLE_ENDIAN #define le16_to_cpu(x) (x) diff --git a/code/base/commands.cpp b/code/base/commands.cpp index a0c254e8..fa9f6e08 100644 --- a/code/base/commands.cpp +++ b/code/base/commands.cpp @@ -50,7 +50,8 @@ const char* commands_get_description(u8 command_type) case COMMAND_ID_SET_RADIO_CARD_MODEL: strcpy(szCommandDesc, "Set_Radio_Card_Model"); break; case COMMAND_ID_SET_MODEL_FLAGS: strcpy(szCommandDesc, "Set_Model_Flags"); break; case COMMAND_ID_SET_SIK_PACKET_SIZE: strcpy(szCommandDesc, "Set_SiK_Packet_Size"); break; - case COMMAND_ID_RESET_RADIO_LINK: strcpy(szCommandDesc, "Reset_Radio_Link"); break; + case COMMAND_ID_RESET_RADIO_LINK: strcpy(szCommandDesc, "Reset_Radio_Link"); break; + case COMMAND_ID_SET_AUTO_TX_POWERS: strcpy(szCommandDesc, "SetAutoTxPowers"); break; case COMMAND_ID_GET_USB_INFO: strcpy(szCommandDesc, "Get_USB_Info"); break; case COMMAND_ID_SET_RADIO_LINK_CAPABILITIES: strcpy(szCommandDesc, "Set_Radio_Link_Capabilities"); break; case COMMAND_ID_GET_USB_INFO2: strcpy(szCommandDesc, "Get_USB_Info2"); break; @@ -86,8 +87,6 @@ const char* commands_get_description(u8 command_type) case COMMAND_ID_SET_NICE_VALUE_TELEMETRY: strcpy(szCommandDesc, "Set_NiceValueTelemetry"); break; case COMMAND_ID_SET_NICE_VALUES: strcpy(szCommandDesc, "Set_NiceValues"); break; case COMMAND_ID_SET_IONICE_VALUES: strcpy(szCommandDesc, "Set_IONiceValues"); break; - case COMMAND_ID_SET_RADIO_SLOTTIME: strcpy(szCommandDesc, "Set_Radio_Slottime"); break; - case COMMAND_ID_SET_RADIO_THRESH62: strcpy(szCommandDesc, "Set_Radio_Thresh62"); break; case COMMAND_ID_SET_ENABLE_DHCP: strcpy(szCommandDesc, "Set_Enable_DHCP"); break; case COMMAND_ID_SET_ALL_PARAMS: strcpy(szCommandDesc, "Set_All_Params"); break; case COMMAND_ID_GET_ALL_PARAMS_ZIP: strcpy(szCommandDesc, "Get_All_Params_Zip"); break; diff --git a/code/base/commands.h b/code/base/commands.h index 8b9943ce..117bc6a0 100644 --- a/code/base/commands.h +++ b/code/base/commands.h @@ -8,11 +8,8 @@ #define COMMAND_ID_SET_VEHICLE_NAME 3 #define COMMAND_ID_SET_TX_POWERS 4 -// 8 bytes: 0...5: u8 RTL8812AU, u8 RTL8812EU, u8 Atheros, u8 maxRTL8812AU, u8 maxRTL8812EU, u8 maxAtheros, -// 6: u8 radio card index, -// 7: u8 power, if 0 -> not set -// First 8 bytes can be 0xFF or 0x00 for no changes in those params -// Byte 9,10,11 (if present, optional): 0x81 then tx power Sik, then 0x81 +// byte 0: count interfaces +// N-bytes: power for each card (raw power values) // deprecated starting in 8.3, using now test link functionality to change frequency for 2.4/5.8ghz. still using this command for 433/868 bands #define COMMAND_ID_SET_RADIO_LINK_FREQUENCY 5 @@ -34,10 +31,16 @@ #define COMMAND_ID_SET_RADIO_LINK_FLAGS_CONFIRMATION 8 // param is radio link id -#define COMMAND_ID_SET_RADIO_SLOTTIME 9 -#define COMMAND_ID_SET_RADIO_THRESH62 10 +#define COMMAND_ID_SET_AUTO_TX_POWERS 9 +// param: byte 0: auto adjust vehicle power +// param: byte 1: auto adjust controller power + +// Deprecated in 10.1 +//#define COMMAND_ID_SET_RADIO_THRESH62 10 + #define COMMAND_ID_SET_RADIO_CARD_MODEL 11 -// param: low byte: card index, second byte: card model +// param: low byte: card index, second byte: card model (if 0xFF, then autodetect it again) +// response has the new card model in command_response_param #define COMMAND_ID_SET_MODEL_FLAGS 12 // param u32 new model flags diff --git a/code/base/config.c b/code/base/config.c index 0f1ecae2..d0d7fbfa 100644 --- a/code/base/config.c +++ b/code/base/config.c @@ -67,45 +67,46 @@ int getChannels25Count() { return sizeof(channels25)/sizeof(channels25[0]); } u32* getChannels58() { return channels58; } int getChannels58Count() { return sizeof(channels58)/sizeof(channels58[0]); } -int _getChannelsAndCount(u32 nBand, u32** channels) +int _getChannelsAndCount(u32 nBand, u32** ppuChannels) { - if( channels == NULL ) + if (ppuChannels == NULL) return -1; - switch ( nBand ) { + switch ( nBand ) + { case RADIO_HW_SUPPORTED_BAND_433: - *channels = getChannels433(); + *ppuChannels = getChannels433(); return getChannels433Count(); case RADIO_HW_SUPPORTED_BAND_868: - *channels = getChannels868(); + *ppuChannels = getChannels868(); return getChannels868Count(); case RADIO_HW_SUPPORTED_BAND_915: - *channels = getChannels915(); + *ppuChannels = getChannels915(); return getChannels915Count(); case RADIO_HW_SUPPORTED_BAND_23: - *channels = getChannels23(); + *ppuChannels = getChannels23(); return getChannels23Count(); case RADIO_HW_SUPPORTED_BAND_24: - *channels = getChannels24(); + *ppuChannels = getChannels24(); return getChannels24Count(); case RADIO_HW_SUPPORTED_BAND_25: - *channels = getChannels25(); + *ppuChannels = getChannels25(); return getChannels25Count(); case RADIO_HW_SUPPORTED_BAND_58: - *channels = getChannels58(); + *ppuChannels = getChannels58(); return getChannels58Count(); default: break; } - *channels = NULL; + *ppuChannels = NULL; return -1; } @@ -150,12 +151,15 @@ int getBand(u32 freqKhz) int getChannelIndexForFrequency(u32 nBand, u32 freqKhz) { - u32* channels = NULL; - int channelcount = _getChannelsAndCount(nBand, &channels); - if( channels != NULL ) { - for( int i=0; i= maxChannels ) - return countSupported; + iCountSupported++; + if ( iCountSupported >= maxChannels ) + return iCountSupported; } if ( includeSeparator ) { *pOutChannels = 0; pOutChannels++; - countSupported++; - if ( countSupported >= maxChannels ) - return countSupported; + iCountSupported++; + if ( iCountSupported >= maxChannels ) + return iCountSupported; } } } - return countSupported; + return iCountSupported; } int *getDataRatesBPS() { return s_WiFidataRates; } @@ -525,109 +531,110 @@ FILE* try_open_base_version_file(char* szOutputFile) return fd; } +u32 s_uBaseRubyVersion = 0; + void get_Ruby_BaseVersion(int* pMajor, int* pMinor) { - int iMajor = 0; - int iMinor = 0; + if ( NULL != pMajor ) + *pMajor = 0; + if ( NULL != pMinor ) + *pMinor = 0; + + if ( 0 != s_uBaseRubyVersion ) + { + if ( NULL != pMajor ) + *pMajor = (s_uBaseRubyVersion >> 8) & 0xFF; + if ( NULL != pMinor ) + *pMinor = s_uBaseRubyVersion & 0xFF; + return; + } - char szVersion[32]; - szVersion[0] = 0; + char szFile[MAX_FILE_PATH_SIZE]; + szFile[0] = 0; - FILE* fd = try_open_base_version_file(NULL); - if ( NULL != fd ) + FILE* fd = try_open_base_version_file(szFile); + if ( NULL == fd ) { - if ( 1 != fscanf(fd, "%s", szVersion) ) - szVersion[0] = 0; - fclose(fd); + log_softerror_and_alarm("[Config] Failed to open base Ruby version file (%s).", szFile); + return; } - else + char szBuff[64]; + if ( 1 != fscanf(fd, "%s", szBuff) ) { - if ( NULL != pMajor ) - *pMajor = SYSTEM_SW_VERSION_MAJOR; - if ( NULL != pMinor ) - *pMinor = 0; + fclose(fd); + log_softerror_and_alarm("[Config] Failed to read base Ruby version file (%s).", szFile); return; } + fclose(fd); + log_line("[Config] Read raw base Ruby version: [%s] from file (%s)", szBuff, szFile); - if ( 0 != szVersion[0] ) + for( int i=0; i<(int)strlen(szBuff); i++ ) { - char* p = &szVersion[0]; - while ( *p ) - { - if ( isdigit(*p) ) - iMajor = iMajor * 10 + ((*p)-'0'); - if ( (*p) == '.' ) - break; - p++; - } - if ( 0 != *p ) + if ( szBuff[i] == '.' ) { - p++; - while ( *p ) - { - if ( isdigit(*p) ) - iMinor = iMinor * 10 + ((*p)-'0'); - if ( (*p) == '.' ) - break; - p++; - } + szBuff[i] = 0; + int iMajor = 0; + int iMinor = 0; + sscanf(szBuff, "%d", &iMajor); + sscanf(&szBuff[i+1], "%d", &iMinor); + s_uBaseRubyVersion = (((u32)iMajor) << 8) | ((u32)iMinor); + log_line("[Config] Parsed base Ruby version: %u.%u", (s_uBaseRubyVersion>>8) & 0xFF, s_uBaseRubyVersion & 0xFF); + + if ( NULL != pMajor ) + *pMajor = (s_uBaseRubyVersion >> 8) & 0xFF; + if ( NULL != pMinor ) + *pMinor = s_uBaseRubyVersion & 0xFF; + + return; } - if ( iMinor > 9 ) - iMinor = iMinor/10; } - if ( NULL != pMajor ) - *pMajor = iMajor; - if ( NULL != pMinor ) - *pMinor = iMinor; + log_softerror_and_alarm("[Config] Failed to parse base Ruby version from file (%s).", szFile); } void get_Ruby_UpdatedVersion(int* pMajor, int* pMinor) { - int iMajor = 0; - int iMinor = 0; + if ( NULL != pMajor ) + *pMajor = 0; + if ( NULL != pMinor ) + *pMinor = 0; - char szVersion[32]; - szVersion[0] = 0; + char szBuff[64]; + szBuff[0] = 0; char szFile[MAX_FILE_PATH_SIZE]; strcpy(szFile, FOLDER_CONFIG); strcat(szFile, FILE_INFO_LAST_UPDATE); + FILE* fd = fopen(szFile, "r"); - if ( NULL != fd ) + if ( NULL == fd ) + return; + + if ( 1 != fscanf(fd, "%s", szBuff) ) { - if ( 1 != fscanf(fd, "%s", szVersion) ) - szVersion[0] = 0; fclose(fd); + return; } + fclose(fd); + + log_line("[Config] Read update Ruby version: [%s] from file (%s)", szBuff, szFile); - if ( 0 != szVersion[0] ) + for( int i=0; i<(int)strlen(szBuff); i++ ) { - char* p = &szVersion[0]; - while ( *p ) + if ( szBuff[i] == '.' ) { - if ( isdigit(*p) ) - iMajor = iMajor * 10 + ((*p)-'0'); - if ( (*p) == '.' ) - break; - p++; + szBuff[i] = 0; + int iMajor = 0; + int iMinor = 0; + sscanf(szBuff, "%d", &iMajor); + sscanf(&szBuff[i+1], "%d", &iMinor); + log_line("[Config] Parsed updated Ruby version: %u.%u", iMajor, iMinor); + + if ( NULL != pMajor ) + *pMajor = iMajor; + if ( NULL != pMinor ) + *pMinor = iMinor; + + return; } - if ( 0 != *p ) - { - p++; - while ( *p ) - { - if ( isdigit(*p) ) - iMinor = iMinor * 10 + ((*p)-'0'); - if ( (*p) == '.' ) - break; - p++; - } - } - if ( iMinor > 9 ) - iMinor = iMinor/10; } - if ( NULL != pMajor ) - *pMajor = iMajor; - if ( NULL != pMinor ) - *pMinor = iMinor; } diff --git a/code/base/config.h b/code/base/config.h index fe5a264f..79f07fcb 100644 --- a/code/base/config.h +++ b/code/base/config.h @@ -53,7 +53,7 @@ #define SYSTEM_RT_INFO_UPDATE_INTERVAL_MS 5 -#define SYSTEM_RT_INFO_INTERVALS 180 +#define SYSTEM_RT_INFO_INTERVALS 400 #define DEFAULT_TX_TIME_OVERLOAD 500 // milisec @@ -91,11 +91,9 @@ #define DEFAULT_USE_PPCAP_FOR_TX 1 #define DEFAULT_BYPASS_SOCKET_BUFFERS 1 -#define DEFAULT_RADIO_TX_POWER_CONTROLLER 20 +#define DEFAULT_RADIO_TX_POWER_CONTROLLER 25 #define DEFAULT_RADIO_TX_POWER 20 #define DEFAULT_RADIO_SIK_TX_POWER 11 -#define DEFAULT_RADIO_SLOTTIME 9 -#define DEFAULT_RADIO_THRESH62 26 #define DEFAULT_OVERVOLTAGE 3 #define DEFAULT_ARM_FREQ 900 #define DEFAULT_GPU_FREQ 400 @@ -103,6 +101,7 @@ #define DEFAULT_FREQ_RADXA 1416 #define DEFAULT_PRIORITY_PROCESS_ROUTER -12 +#define DEFAULT_PRIORITY_PROCESS_ROUTER_OPIC -15 #define DEFAULT_IO_PRIORITY_ROUTER 3 //(negative for disabled) #define DEFAULT_PRIORITY_PROCESS_RC -9 #define DEFAULT_IO_PRIORITY_RC 2 // (negative for disabled) @@ -111,6 +110,7 @@ #define DEFAULT_IO_PRIORITY_VIDEO_TX 3 #define DEFAULT_IO_PRIORITY_VIDEO_RX 3 #define DEFAULT_PRIORITY_PROCESS_TELEMETRY -8 +#define DEFAULT_PRIORITY_PROCESS_TELEMETRY_OIPC -3 #define DEFAULT_PRIORITY_PROCESS_OTHERS -3 #define DEFAULT_PRIORITY_PROCESS_CENTRAL -3 diff --git a/code/base/config_file_names.h b/code/base/config_file_names.h index 7fedd330..218693dc 100644 --- a/code/base/config_file_names.h +++ b/code/base/config_file_names.h @@ -84,12 +84,14 @@ #define SUBFOLDER_UPDATES_PI "bin/pi/" #define SUBFOLDER_UPDATES_RADXA "bin/radxaz3/" #define SUBFOLDER_UPDATES_OIPC "bin/ssc338q/" +#define SUBFOLDER_UPDATES_DRIVERS "bin/drivers/" //------------------------------------------- #ifdef HW_PLATFORM_RASPBERRY #define FOLDER_BINARIES "/home/pi/ruby/" +#define FOLDER_DRIVERS "/home/pi/ruby/drivers/" #define FOLDER_CONFIG "/home/pi/ruby/config/" #define FOLDER_CONFIG_MODELS "/home/pi/ruby/config/models/" #define FOLDER_VEHICLE_HISTORY "/home/pi/ruby/config/models/history-%d/" @@ -119,7 +121,6 @@ #define VIDEO_RECORDER_COMMAND_VEYE_SHORT_NAME "ruby_capture_veye" #define VIDEO_PLAYER_PIPE "ruby_player_p" -#define VIDEO_PLAYER_STDIN "ruby_player_s" #define VIDEO_PLAYER_OFFLINE "ruby_player_f2" #define VEYE_COMMANDS_FOLDER "/usr/local/share/veye-raspberrypi" @@ -133,6 +134,7 @@ #if defined(HW_PLATFORM_RADXA_ZERO3) #define FOLDER_BINARIES "/home/radxa/ruby/" +#define FOLDER_DRIVERS "/home/radxa/ruby/drivers/" #define FOLDER_CONFIG "/home/radxa/ruby/config/" #define FOLDER_CONFIG_MODELS "/home/radxa/ruby/config/models/" #define FOLDER_VEHICLE_HISTORY "/home/radxa/ruby/config/models/history-%d/" @@ -164,6 +166,7 @@ #ifdef HW_PLATFORM_OPENIPC_CAMERA #define FOLDER_BINARIES "/usr/sbin/" +#define FOLDER_DRIVERS "/usr/sbin/drivers/" #define FOLDER_CONFIG "/root/ruby/config/" #define FOLDER_CONFIG_MODELS "/root/ruby/config/models/" #define FOLDER_VEHICLE_HISTORY "/root/ruby/config/models/history-%d/" diff --git a/code/base/config_timers.h b/code/base/config_timers.h index 3982220f..db944f02 100644 --- a/code/base/config_timers.h +++ b/code/base/config_timers.h @@ -6,6 +6,7 @@ #define DEFAULT_DELAY_WIFI_CHANGE 60 #define TIMEOUT_TELEMETRY_LOST 2000 // miliseconds +#define TIMEOUT_FC_TELEMETRY_LOST 2000 // miliseconds #define TIMEOUT_FC_MESSAGE 2500 // How long should the last message from FC should be send to controller. Send it for 2 seconds #define TIMEOUT_RADIO_FRAMES_FLAGS_CHANGE_CONFIRMATION 5000 diff --git a/code/base/config_video.h b/code/base/config_video.h index aef421ec..75d36abc 100644 --- a/code/base/config_video.h +++ b/code/base/config_video.h @@ -4,7 +4,7 @@ // Maximum percent of radio datarate to use for video #define DEFAULT_VIDEO_LINK_MAX_LOAD_PERCENT 90 -#define DEFAULT_VIDEO_LINK_LOAD_PERCENT 80 +#define DEFAULT_VIDEO_LINK_LOAD_PERCENT 75 #define DEFAULT_LOWER_VIDEO_RADIO_DATARATE_AFTER_MS 50 #define DEFAULT_MINIMUM_OK_INTERVAL_MS_TO_SWITCH_VIDEO_PROFILE_UP 1500 @@ -13,7 +13,10 @@ #define DEFAULT_CONTROLLER_LINK_MILISECONDS_TIMEOUT_TO_DISABLE_RETRANSMISSIONS 3000 #define DEFAULT_VIDEO_H264_QUANTIZATION -18 +#define DEFAULT_VIDEO_H264_IPQUANTIZATION_DELTA_HQ -3 +#define DEFAULT_VIDEO_H264_IPQUANTIZATION_DELTA_HP -4 #define DEFAULT_VIDEO_H264_SLICES 4 +#define DEFAULT_VIDEO_H264_SLICES_OIPC 1 #define MAX_VIDEO_PACKET_DATA_SIZE 1150 @@ -25,10 +28,10 @@ #define DEFAULT_VIDEO_AUTO_INITIAL_KEYFRAME_INTERVAL 200 // in miliseconds #define DEFAULT_VIDEO_KEYFRAME_INTERVAL_WHEN_RELAYING 200 // in miliseconds -#define DEFAULT_VIDEO_RETRANS_MS5_HP ((u32)10) // 10*5 = 50 milisec -#define DEFAULT_VIDEO_RETRANS_MS5_HQ ((u32)10) // 10*5 = 50 milisec -#define DEFAULT_VIDEO_RETRANS_MS5_MQ ((u32)10) // 10*5 = 50 milisec -#define DEFAULT_VIDEO_RETRANS_MS5_LQ ((u32)10) // 10*5 = 50 milisec +#define DEFAULT_VIDEO_RETRANS_MS5_HP ((u32)14) // 10*5 = 50 milisec +#define DEFAULT_VIDEO_RETRANS_MS5_HQ ((u32)14) // 14*5 = 70 milisec +#define DEFAULT_VIDEO_RETRANS_MS5_MQ ((u32)14) // 14*5 = 70 milisec +#define DEFAULT_VIDEO_RETRANS_MS5_LQ ((u32)14) // 14*5 = 70 milisec #define DEFAULT_VIDEO_RETRANS_MINIMUM_RETRY_INTERVAL 10 //milisec #define DEFAULT_VIDEO_RETRANS_REQUEST_ON_VIDEO_SILENCE_MS 70 // milisec @@ -40,7 +43,7 @@ //#define DEFAULT_VIDEO_HEIGHT 576 #define DEFAULT_VIDEO_FPS 30 #define DEFAULT_VIDEO_FPS_OIPC 60 -#define DEFAULT_VIDEO_FPS_OIPC_SIGMASTAR 120 +#define DEFAULT_VIDEO_FPS_OIPC_SIGMASTAR 60 #define DEFAULT_LOWEST_ALLOWED_ADAPTIVE_VIDEO_BITRATE 1000000 #define DEFAULT_VIDEO_BITRATE 6000000 // in bps diff --git a/code/base/controller_rt_info.cpp b/code/base/controller_rt_info.cpp index 41224384..72fcd935 100644 --- a/code/base/controller_rt_info.cpp +++ b/code/base/controller_rt_info.cpp @@ -202,12 +202,17 @@ int controller_rt_info_check_advance_index(controller_runtime_info* pRTInfo, u32 { pRTInfo->uRxVideoPackets[iIndex][i] = 0; pRTInfo->uRxVideoECPackets[iIndex][i] = 0; - pRTInfo->uRxVideoRetrPackets[iIndex][i] = 0; pRTInfo->uRxDataPackets[iIndex][i] = 0; + pRTInfo->uRxHighPriorityPackets[iIndex][i] = 0; pRTInfo->uRxMissingPackets[iIndex][i] = 0; pRTInfo->uRxMissingPacketsMaxGap[iIndex][i] = 0; } pRTInfo->uRxProcessedPackets[iIndex] = 0; + pRTInfo->uRxMaxAirgapSlots[iIndex] = 0; + pRTInfo->uRxMaxAirgapSlots2[iIndex] = 0; + + pRTInfo->uTxPackets[iIndex] = 0; + pRTInfo->uTxHighPriorityPackets[iIndex] = 0; pRTInfo->uRecvVideoDataPackets[iIndex] = 0; pRTInfo->uRecvVideoECPackets[iIndex] = 0; @@ -224,6 +229,7 @@ int controller_rt_info_check_advance_index(controller_runtime_info* pRTInfo, u32 pRTInfo->vehicles[i].uCountAckRetransmissions[iIndex] = 0; } pRTInfo->uOutputedVideoPackets[iIndex] = 0; + pRTInfo->uOutputedVideoPacketsRetransmitted[iIndex] = 0; pRTInfo->uOutputedVideoPacketsSingleECUsed[iIndex] = 0; pRTInfo->uOutputedVideoPacketsTwoECUsed[iIndex] = 0; pRTInfo->uOutputedVideoPacketsMultipleECUsed[iIndex] = 0; diff --git a/code/base/controller_rt_info.h b/code/base/controller_rt_info.h index 0966860d..719c3eb2 100644 --- a/code/base/controller_rt_info.h +++ b/code/base/controller_rt_info.h @@ -52,17 +52,23 @@ typedef struct u32 uSliceUpdateTime[SYSTEM_RT_INFO_INTERVALS]; u8 uRxVideoPackets[SYSTEM_RT_INFO_INTERVALS][MAX_RADIO_INTERFACES]; u8 uRxVideoECPackets[SYSTEM_RT_INFO_INTERVALS][MAX_RADIO_INTERFACES]; - u8 uRxVideoRetrPackets[SYSTEM_RT_INFO_INTERVALS][MAX_RADIO_INTERFACES]; u8 uRxDataPackets[SYSTEM_RT_INFO_INTERVALS][MAX_RADIO_INTERFACES]; + u8 uRxHighPriorityPackets[SYSTEM_RT_INFO_INTERVALS][MAX_RADIO_INTERFACES]; u8 uRxMissingPackets[SYSTEM_RT_INFO_INTERVALS][MAX_RADIO_INTERFACES]; u8 uRxMissingPacketsMaxGap[SYSTEM_RT_INFO_INTERVALS][MAX_RADIO_INTERFACES]; u8 uRxProcessedPackets[SYSTEM_RT_INFO_INTERVALS]; + u8 uRxMaxAirgapSlots[SYSTEM_RT_INFO_INTERVALS]; + u8 uRxMaxAirgapSlots2[SYSTEM_RT_INFO_INTERVALS]; + + u8 uTxPackets[SYSTEM_RT_INFO_INTERVALS]; + u8 uTxHighPriorityPackets[SYSTEM_RT_INFO_INTERVALS]; u8 uRecvVideoDataPackets[SYSTEM_RT_INFO_INTERVALS]; u8 uRecvVideoECPackets[SYSTEM_RT_INFO_INTERVALS]; u8 uRecvEndOfFrame[SYSTEM_RT_INFO_INTERVALS]; u8 uOutputedVideoPackets[SYSTEM_RT_INFO_INTERVALS]; + u8 uOutputedVideoPacketsRetransmitted[SYSTEM_RT_INFO_INTERVALS]; u8 uOutputedVideoPacketsSingleECUsed[SYSTEM_RT_INFO_INTERVALS]; u8 uOutputedVideoPacketsTwoECUsed[SYSTEM_RT_INFO_INTERVALS]; u8 uOutputedVideoPacketsMultipleECUsed[SYSTEM_RT_INFO_INTERVALS]; diff --git a/code/base/ctrl_interfaces.cpp b/code/base/ctrl_interfaces.cpp index b69753d0..d45e5a14 100644 --- a/code/base/ctrl_interfaces.cpp +++ b/code/base/ctrl_interfaces.cpp @@ -36,6 +36,7 @@ #include "hardware_radio.h" #include "ctrl_interfaces.h" #include "ctrl_settings.h" +#include "tx_powers.h" #include "../common/string_utils.h" #if defined(HW_PLATFORM_RASPBERRY) || defined(HW_PLATFORM_RADXA_ZERO3) @@ -44,6 +45,12 @@ ControllerInterfacesSettings s_CIS; bool s_bAddedNewRadioInterfaces = false; int s_iNewCardRadioInterfaceIndex = -1; +// returns true if the power levels where updated +bool controllerInterfacesCheckPowerLevels() +{ + return false; +} + // Returns the index of the card int controllerAddedNewRadioInterfaces() { @@ -72,7 +79,7 @@ void _controller_interfaces_add_card(const char* szMAC) if ( hardware_radio_is_sik_radio(pRadioInfo) ) s_CIS.listRadioInterfaces[s_CIS.radioInterfacesCount].capabilities_flags &= ~(RADIO_HW_CAPABILITY_FLAG_CAN_USE_FOR_VIDEO); - s_CIS.listRadioInterfaces[s_CIS.radioInterfacesCount].iDummy1 = 0; + s_CIS.listRadioInterfaces[s_CIS.radioInterfacesCount].iRawPowerLevel = DEFAULT_RADIO_TX_POWER_CONTROLLER; s_CIS.listRadioInterfaces[s_CIS.radioInterfacesCount].szUserDefinedName = (char*)malloc(2); s_CIS.listRadioInterfaces[s_CIS.radioInterfacesCount].szUserDefinedName[0] = 0; s_CIS.listRadioInterfaces[s_CIS.radioInterfacesCount].iInternal = false; @@ -146,10 +153,11 @@ int save_ControllerInterfacesSettings() if ( szBuff[0] == '~' && szBuff[1] == 0 ) szBuff[0] = 0; if ( 0 == szBuff[0] ) - fprintf(fd, "~ %s %d %u %d\n", s_CIS.listRadioInterfaces[i].szMAC, s_CIS.listRadioInterfaces[i].cardModel, s_CIS.listRadioInterfaces[i].capabilities_flags, s_CIS.listRadioInterfaces[i].iDummy1); + fprintf(fd, "~ %s %d %u %d\n", s_CIS.listRadioInterfaces[i].szMAC, s_CIS.listRadioInterfaces[i].cardModel, s_CIS.listRadioInterfaces[i].capabilities_flags, s_CIS.listRadioInterfaces[i].iRawPowerLevel); else - fprintf(fd, "%s %s %d %u %d\n", szBuff, s_CIS.listRadioInterfaces[i].szMAC, s_CIS.listRadioInterfaces[i].cardModel, s_CIS.listRadioInterfaces[i].capabilities_flags, s_CIS.listRadioInterfaces[i].iDummy1); + fprintf(fd, "%s %s %d %u %d\n", szBuff, s_CIS.listRadioInterfaces[i].szMAC, s_CIS.listRadioInterfaces[i].cardModel, s_CIS.listRadioInterfaces[i].capabilities_flags, s_CIS.listRadioInterfaces[i].iRawPowerLevel); fprintf(fd, "%d\n", s_CIS.listRadioInterfaces[i].iInternal); + log_line("Saved raw tx power for card %d: %d", i, s_CIS.listRadioInterfaces[i].iRawPowerLevel); } fprintf(fd, "TX_Preferred: %d\n", s_CIS.listMACTXPreferredCount ); @@ -260,7 +268,7 @@ int load_ControllerInterfacesSettings() } s_CIS.listRadioInterfaces[i].capabilities_flags = tmp; - s_CIS.listRadioInterfaces[i].iDummy1 = tmp2; + s_CIS.listRadioInterfaces[i].iRawPowerLevel = tmp2; int kSize = (int)strlen(s_CIS.listRadioInterfaces[i].szUserDefinedName); for( int k=0; ksupportedBands, szBands); if ( NULL != pCardInfo ) - log_line("* RadioInterface %d: %s, %s MAC:%s phy#%d, %s %s, %s", i+1, str_get_radio_card_model_string(pCardInfo->cardModel), pRadioInfo->szName, pRadioInfo->szMAC, pRadioInfo->phy_index, (controllerIsCardDisabled(pRadioInfo->szMAC)?"[DISABLED]":"[ENABLED]"), szBuff, szBands); + log_line("* RadioInterface %d: %s, %s MAC:%s phy#%d, %s %s, %s, raw_tx_power: %d", i+1, str_get_radio_card_model_string(pCardInfo->cardModel), pRadioInfo->szName, pRadioInfo->szMAC, pRadioInfo->phy_index, (controllerIsCardDisabled(pRadioInfo->szMAC)?"[DISABLED]":"[ENABLED]"), szBuff, szBands, pCardInfo->iRawPowerLevel); else log_line("* RadioInterface %d: %s, %s MAC:%s phy#%d, %s %s, %s", i+1, "Unknown Type", pRadioInfo->szName, pRadioInfo->szMAC, pRadioInfo->phy_index, (controllerIsCardDisabled(pRadioInfo->szMAC)?"[DISABLED]":"[ENABLED]"), szBuff, szBands); u32 uFlags = controllerGetCardFlags(pRadioInfo->szMAC); @@ -652,6 +660,38 @@ void controllerGetCardUserDefinedNameOrType(radio_hw_info_t* pRadioHWInfo, char* strcpy(szOutput, "Generic"); } + +void controllerGetCardUserDefinedNameOrShortType(radio_hw_info_t* pRadioHWInfo, char* szOutput) +{ + if ( NULL != szOutput ) + szOutput[0] = 0; + if ( (NULL == pRadioHWInfo) || (NULL == szOutput) ) + return; + char* szN = NULL; + if ( NULL != pRadioHWInfo ) + szN = controllerGetCardUserDefinedName(pRadioHWInfo->szMAC); + if ( (NULL != szN) && (0 != szN[0]) ) + { + strcpy(szOutput, szN); + return; + } + + t_ControllerRadioInterfaceInfo* pCardInfo = NULL; + if ( NULL != pRadioHWInfo ) + pCardInfo = controllerGetRadioCardInfo(pRadioHWInfo->szMAC); + if ( NULL != pCardInfo ) + { + const char* szCardModel = str_get_radio_card_model_string_short(pCardInfo->cardModel); + if ( NULL != szCardModel && 0 != szCardModel[0] ) + { + strcpy(szOutput, szCardModel); + return; + } + } + + strcpy(szOutput, "Generic"); +} + char* controllerGetCardUserDefinedName(const char* szMAC) { int index = _controller_interfaces_get_card_index(szMAC); @@ -1183,7 +1223,6 @@ t_ControllerInputInterface* controllerInterfacesGetAt(int index) return NULL; } - #else int save_ControllerInterfacesSettings() { return 0; } diff --git a/code/base/ctrl_interfaces.h b/code/base/ctrl_interfaces.h index f167b6f8..9e35fd22 100644 --- a/code/base/ctrl_interfaces.h +++ b/code/base/ctrl_interfaces.h @@ -40,7 +40,7 @@ typedef struct u32 capabilities_flags; //Deprecated in 9.5 //int datarateBPSMCS; // positive: bps; negative: mcs rate; 0: none - int iDummy1; + int iRawPowerLevel; int iInternal; } t_ControllerRadioInterfaceInfo; @@ -81,12 +81,15 @@ int controllerGetTXPreferredIndexForCard(const char* szMAC); void controllerSetCardInternal(const char* szMAC, bool bInternal); bool controllerIsCardInternal(const char* szMAC); +bool controllerInterfacesCheckPowerLevels(); + int controllerAddedNewRadioInterfaces(); u32 controllerGetCardFlags(const char* szMAC); void controllerSetCardFlags(const char* szMAC, u32 flags); void controllerGetCardUserDefinedNameOrType(radio_hw_info_t* pRadioHWInfo, char* szOutput); +void controllerGetCardUserDefinedNameOrShortType(radio_hw_info_t* pRadioHWInfo, char* szOutput); char* controllerGetCardUserDefinedName(const char* szMAC); void controllerSetCardUserDefinedName(const char* szMAC, const char* szName); diff --git a/code/base/ctrl_preferences.c b/code/base/ctrl_preferences.c index 149fcbf2..3e9747da 100644 --- a/code/base/ctrl_preferences.c +++ b/code/base/ctrl_preferences.c @@ -61,7 +61,7 @@ void reset_Preferences() s_Preferences.iVideoDestination = prefVideoDestination_Disk; s_Preferences.iStartVideoRecOnArm = 0; s_Preferences.iStopVideoRecOnDisarm = 0; - s_Preferences.iShowControllerCPUInfo = 1; + s_Preferences.iShowControllerCPUInfo = 0; s_Preferences.iShowBigRecordButton = 0; s_Preferences.iSwapUpDownButtons = 0; s_Preferences.iSwapUpDownButtonsValues = 0; @@ -101,7 +101,7 @@ void reset_Preferences() s_Preferences.iDebugShowVideoSnapshotOnDiscard = 0; s_Preferences.iDebugWiFiChangeDelay = DEFAULT_DELAY_WIFI_CHANGE; - s_Preferences.iAutoExportSettings = 1; + s_Preferences.iAutoExportSettings = 0; s_Preferences.iAutoExportSettingsWasModified = 0; s_Preferences.iShowProcessesMonitor = 0; @@ -110,12 +110,13 @@ void reset_Preferences() s_Preferences.iShowOnlyPresentTxPowerCards = 1; s_Preferences.iShowTxBoosters = 0; s_Preferences.iMenuStyle = 0; + s_Preferences.iStopRecordingAfterLinkLostSeconds = 20; s_Preferences.iDebugStatsQAButton = 0; - s_Preferences.uDebugStatsFlags = CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_VIDEO_DATA_PACKETS | + s_Preferences.uDebugStatsFlags = CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_TX_PACKETS | CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_H264265_FRAMES | - CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_DBM | - CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_MISSING_PACKETS_MAX_GAP | + //CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_DBM | + //CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_MISSING_PACKETS_MAX_GAP | //CTRL_RT_DEBUG_INFO_FLAG_SHOW_MIN_MAX_ACK_TIME | CTRL_RT_DEBUG_INFO_FLAG_SHOW_ACK_TIME_HISTORY | CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_VIDEO_MAX_EC_USED | @@ -182,8 +183,8 @@ int save_Preferences() fprintf(fd, "%d \n", s_Preferences.iShowCPULoad); fprintf(fd, "%d %d %d\n", s_Preferences.iShowOnlyPresentTxPowerCards, s_Preferences.iShowTxBoosters, s_Preferences.iMenuStyle); - fprintf(fd, "%d %d\n", s_Preferences.iDebugStatsQAButton, s_Preferences.uDebugStatsFlags); - + fprintf(fd, "%d %u\n", s_Preferences.iDebugStatsQAButton, s_Preferences.uDebugStatsFlags); + fprintf(fd, "%d\n", s_Preferences.iStopRecordingAfterLinkLostSeconds); fclose(fd); log_line("Saved preferences to file: %s", szFile); return 1; @@ -323,18 +324,21 @@ int load_Preferences() if ( bOk && 1 != fscanf(fd, "%d", &s_Preferences.iDebugShowVideoSnapshotOnDiscard) ) { s_Preferences.iDebugShowVideoSnapshotOnDiscard = 0; + bOk = 0; } if ( bOk && 2 != fscanf(fd, "%d %d", &s_Preferences.iDebugShowVehicleVideoStats, &s_Preferences.iDebugShowVehicleVideoGraphs) ) { s_Preferences.iDebugShowVehicleVideoStats = 0; s_Preferences.iDebugShowVehicleVideoGraphs = 0; + bOk = 0; } if ( bOk && 2 != fscanf(fd, "%d %d", &s_Preferences.iAutoExportSettings, &s_Preferences.iAutoExportSettingsWasModified) ) { s_Preferences.iAutoExportSettings = 1; s_Preferences.iAutoExportSettingsWasModified = 0; + bOk = 0; } if ( bOk && 1 != fscanf(fd, "%d", &s_Preferences.iShowProcessesMonitor) ) @@ -352,14 +356,21 @@ int load_Preferences() if ( bOk && 1 != fscanf(fd, "%d", &s_Preferences.iMenuStyle) ) s_Preferences.iMenuStyle = 0; - if ( bOk && 2 != fscanf(fd, "%d %d", &s_Preferences.iDebugStatsQAButton, &s_Preferences.uDebugStatsFlags) ) + if ( bOk && 2 != fscanf(fd, "%d %u", &s_Preferences.iDebugStatsQAButton, &s_Preferences.uDebugStatsFlags) ) { s_Preferences.iDebugStatsQAButton = 0; - s_Preferences.uDebugStatsFlags = CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_VIDEO_DATA_PACKETS | + s_Preferences.uDebugStatsFlags = CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_TX_PACKETS | CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_MISSING_PACKETS_MAX_GAP | //CTRL_RT_DEBUG_INFO_FLAG_SHOW_MIN_MAX_ACK_TIME | CTRL_RT_DEBUG_INFO_FLAG_SHOW_ACK_TIME_HISTORY | CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_VIDEO_MAX_EC_USED; + bOk = 0; + } + + if ( bOk && 1 != fscanf(fd, "%d", &s_Preferences.iStopRecordingAfterLinkLostSeconds) ) + { + s_Preferences.iStopRecordingAfterLinkLostSeconds = 20; + bOk = 0; } // ---------------------------------------------------- @@ -403,6 +414,8 @@ int load_Preferences() fclose(fd); return 0; } + if ( ! bOk ) + log_softerror_and_alarm("Some preferences settings where missing from file."); fclose(fd); log_line("Loaded preferences from file: %s", szFile); return 1; diff --git a/code/base/ctrl_preferences.h b/code/base/ctrl_preferences.h index 7fa38ebd..049b6fd1 100644 --- a/code/base/ctrl_preferences.h +++ b/code/base/ctrl_preferences.h @@ -6,7 +6,7 @@ extern "C" { #endif -#define CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_VIDEO_DATA_PACKETS ((u32)(((u32)0x01)<<2)) +#define CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_TX_PACKETS ((u32)(((u32)0x01)<<2)) #define CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_H264265_FRAMES ((u32)(((u32)0x01)<<3)) #define CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_DBM ((u32)(((u32)0x01)<<4)) #define CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_MISSING_PACKETS ((u32)(((u32)0x01)<<5)) @@ -18,6 +18,7 @@ extern "C" { #define CTRL_RT_DEBUG_INFO_FLAG_SHOW_VIDEO_PROFILE_CHANGES ((u32)(((u32)0x01)<<11)) #define CTRL_RT_DEBUG_INFO_FLAG_SHOW_VIDEO_RETRANSMISSIONS ((u32)(((u32)0x01)<<12)) #define CTRL_RT_DEBUG_INFO_FLAG_SHOW_ACK_TIME_HISTORY ((u32)(((u32)0x01)<<13)) +#define CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_AIR_GAPS ((u32)(((u32)0x01)<<14)) typedef enum @@ -122,7 +123,7 @@ typedef struct int iShowOnlyPresentTxPowerCards; int iShowTxBoosters; int iMenuStyle; // 0: clasic, 1: sticky left - + int iStopRecordingAfterLinkLostSeconds; int iDebugStatsQAButton; u32 uDebugStatsFlags; } Preferences; diff --git a/code/base/ctrl_settings.c b/code/base/ctrl_settings.c index 9c7bcff2..e9b1152f 100644 --- a/code/base/ctrl_settings.c +++ b/code/base/ctrl_settings.c @@ -46,13 +46,7 @@ void reset_ControllerSettings() { memset(&s_CtrlSettings, 0, sizeof(s_CtrlSettings)); s_CtrlSettings.iUseBrokenVideoCRC = 0; - s_CtrlSettings.iTXPowerRTL8812AU = DEFAULT_RADIO_TX_POWER_CONTROLLER; - s_CtrlSettings.iTXPowerRTL8812EU = DEFAULT_RADIO_TX_POWER_CONTROLLER; - s_CtrlSettings.iTXPowerAtheros = DEFAULT_RADIO_TX_POWER_CONTROLLER; - s_CtrlSettings.iTXPowerSiK = DEFAULT_RADIO_SIK_TX_POWER; - s_CtrlSettings.iMaxTXPowerRTL8812AU = MAX_TX_POWER; - s_CtrlSettings.iMaxTXPowerRTL8812EU = MAX_TX_POWER; - s_CtrlSettings.iMaxTXPowerAtheros = MAX_TX_POWER; + s_CtrlSettings.iFixedTxPower = 0; s_CtrlSettings.iHDMIBoost = 6; s_CtrlSettings.iOverVoltage = 0; s_CtrlSettings.iFreqARM = 0; @@ -90,8 +84,8 @@ void reset_ControllerSettings() s_CtrlSettings.nRotaryEncoderFunction2 = 2; // 0 - none, 1 - menu, 2 - camera s_CtrlSettings.nRotaryEncoderSpeed2 = 0; // 0 - normal, 1 - slow s_CtrlSettings.nPingClockSyncFrequency = DEFAULT_PING_FREQUENCY; - s_CtrlSettings.nGraphRadioRefreshInterval = 100; - s_CtrlSettings.nGraphVideoRefreshInterval = 100; + s_CtrlSettings.nGraphRadioRefreshInterval = 50; + s_CtrlSettings.nGraphVideoRefreshInterval = 50; s_CtrlSettings.iDisableRetransmissionsAfterControllerLinkLostMiliseconds = DEFAULT_CONTROLLER_LINK_MILISECONDS_TIMEOUT_TO_DISABLE_RETRANSMISSIONS; s_CtrlSettings.iVideoDecodeStatsSnapshotClosesOnTimeout = 1; s_CtrlSettings.iFreezeOSD = 0; @@ -133,8 +127,7 @@ int save_ControllerSettings() } fprintf(fd, "%s\n", CONTROLLER_SETTINGS_STAMP_ID); fprintf(fd, "%d %d %d\n", s_CtrlSettings.iDeveloperMode, s_CtrlSettings.iUseBrokenVideoCRC, s_CtrlSettings.iHDMIBoost); - fprintf(fd, "%d %d %d %d %d %d\n", s_CtrlSettings.iTXPowerRTL8812AU, s_CtrlSettings.iTXPowerRTL8812EU, s_CtrlSettings.iTXPowerAtheros, s_CtrlSettings.iMaxTXPowerRTL8812AU, s_CtrlSettings.iMaxTXPowerRTL8812EU, s_CtrlSettings.iMaxTXPowerAtheros); - + fprintf(fd, "%d %d %d\n", s_CtrlSettings.iOverVoltage, s_CtrlSettings.iFreqARM, s_CtrlSettings.iFreqGPU); fprintf(fd, "%d %d %d\n%d %d\n", s_CtrlSettings.iNiceRouter, s_CtrlSettings.iNiceCentral, s_CtrlSettings.iNiceRXVideo, s_CtrlSettings.ioNiceRouter, s_CtrlSettings.ioNiceRXVideo); @@ -163,14 +156,13 @@ int save_ControllerSettings() fprintf(fd, "%d %d\n", -1, s_CtrlSettings.iFreezeOSD); fprintf(fd, "%d %d\n", s_CtrlSettings.iDevSwitchVideoProfileUsingQAButton, s_CtrlSettings.iShowControllerAdaptiveInfoStats); fprintf(fd, "%d\n", s_CtrlSettings.iShowVideoStreamInfoCompactType); - fprintf(fd, "%d\n", s_CtrlSettings.iTXPowerSiK); fprintf(fd, "%d %d %d %d\n", s_CtrlSettings.iSearchSiKAirRate, s_CtrlSettings.iSearchSiKECC, s_CtrlSettings.iSearchSiKLBT, s_CtrlSettings.iSearchSiKMCSTR); fprintf(fd, "%d %d\n", s_CtrlSettings.iAudioOutputDevice, s_CtrlSettings.iAudioOutputVolume); fprintf(fd, "%d %u\n", s_CtrlSettings.iDevRxLoopTimeout, s_CtrlSettings.uShowBigRxHistoryInterface); fprintf(fd, "%d\n", s_CtrlSettings.iSiKPacketSize); fprintf(fd, "%d %d\n", s_CtrlSettings.iRadioRxThreadPriority, s_CtrlSettings.iRadioTxThreadPriority); - fprintf(fd, "%d %d\n", s_CtrlSettings.iRadioTxUsesPPCAP, s_CtrlSettings.iRadioBypassSocketBuffers); + fprintf(fd, "%d %d %d\n", s_CtrlSettings.iRadioTxUsesPPCAP, s_CtrlSettings.iRadioBypassSocketBuffers, s_CtrlSettings.iFixedTxPower); fclose(fd); log_line("Saved controller settings to file: %s", szFile); @@ -212,175 +204,81 @@ int load_ControllerSettings() return 0; } - if ( 1 != fscanf(fd, "%d", &s_CtrlSettings.iDeveloperMode) ) - s_CtrlSettings.iDeveloperMode = 0; - if ( 1 != fscanf(fd, "%d", &s_CtrlSettings.iUseBrokenVideoCRC) ) - s_CtrlSettings.iUseBrokenVideoCRC = 0; - if ( 1 != fscanf(fd, "%d", &s_CtrlSettings.iHDMIBoost) ) - s_CtrlSettings.iHDMIBoost = 5; - - if ( 3 != fscanf(fd, "%d %d %d", &s_CtrlSettings.iTXPowerRTL8812AU, &s_CtrlSettings.iTXPowerRTL8812EU, &s_CtrlSettings.iTXPowerAtheros) ) - { - s_CtrlSettings.iTXPowerRTL8812AU = DEFAULT_RADIO_TX_POWER_CONTROLLER; - s_CtrlSettings.iTXPowerRTL8812EU = DEFAULT_RADIO_TX_POWER_CONTROLLER; - s_CtrlSettings.iTXPowerAtheros = DEFAULT_RADIO_TX_POWER_CONTROLLER; - hardware_radio_set_txpower_rtl8812au(DEFAULT_RADIO_TX_POWER_CONTROLLER); - hardware_radio_set_txpower_rtl8812eu(DEFAULT_RADIO_TX_POWER_CONTROLLER); - hardware_radio_set_txpower_atheros(DEFAULT_RADIO_TX_POWER_CONTROLLER); - } - - if ( 3 != fscanf(fd, "%d %d %d", &s_CtrlSettings.iMaxTXPowerRTL8812AU, &s_CtrlSettings.iMaxTXPowerRTL8812EU, &s_CtrlSettings.iMaxTXPowerAtheros) ) - { - s_CtrlSettings.iMaxTXPowerRTL8812AU = MAX_TX_POWER; - s_CtrlSettings.iMaxTXPowerRTL8812EU = MAX_TX_POWER; - s_CtrlSettings.iMaxTXPowerAtheros = MAX_TX_POWER; - } + if ( 3 != fscanf(fd, "%d %d %d", &s_CtrlSettings.iDeveloperMode, &s_CtrlSettings.iUseBrokenVideoCRC, &s_CtrlSettings.iHDMIBoost) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 1"); } if ( 3 != fscanf(fd, "%d %d %d", &s_CtrlSettings.iOverVoltage, &s_CtrlSettings.iFreqARM, &s_CtrlSettings.iFreqGPU) ) - { s_CtrlSettings.iOverVoltage = 0; s_CtrlSettings.iFreqARM = 0; s_CtrlSettings.iFreqGPU = 0; } + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 2"); } if ( 5 != fscanf(fd, "%d %d %d %d %d", &s_CtrlSettings.iNiceRouter, &s_CtrlSettings.iNiceCentral, &s_CtrlSettings.iNiceRXVideo, &s_CtrlSettings.ioNiceRouter, &s_CtrlSettings.ioNiceRXVideo) ) - { log_softerror_and_alarm("Failed to load controller settings (line nice)"); } - + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 3"); } - if ( (!failed) && (3 != fscanf(fd, "%*s %d %d %d", &s_CtrlSettings.iVideoForwardUSBType, &s_CtrlSettings.iVideoForwardUSBPort, &s_CtrlSettings.iVideoForwardUSBPacketSize)) ) - { s_CtrlSettings.iVideoForwardUSBType = 0; s_CtrlSettings.iVideoForwardUSBPort = 0; s_CtrlSettings.iVideoForwardUSBPacketSize = 1024; failed = 4; } - if ( (!failed) && (3 != fscanf(fd, "%*s %d %d %d", &s_CtrlSettings.iTelemetryForwardUSBType, &s_CtrlSettings.iTelemetryForwardUSBPort, &s_CtrlSettings.iTelemetryForwardUSBPacketSize)) ) - { s_CtrlSettings.iTelemetryForwardUSBType = 0; s_CtrlSettings.iTelemetryForwardUSBPort = 0; s_CtrlSettings.iTelemetryForwardUSBPacketSize = 1024; failed = 5; } + if ( 3 != fscanf(fd, "%*s %d %d %d", &s_CtrlSettings.iVideoForwardUSBType, &s_CtrlSettings.iVideoForwardUSBPort, &s_CtrlSettings.iVideoForwardUSBPacketSize) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 4"); } - if ( (!failed) && (2 != fscanf(fd, "%d %d", &s_CtrlSettings.iTelemetryOutputSerialPortIndex, &s_CtrlSettings.iTelemetryInputSerialPortIndex)) ) - { - s_CtrlSettings.iTelemetryOutputSerialPortIndex = -1; - s_CtrlSettings.iTelemetryInputSerialPortIndex = -1; - failed = 6; - } - if ( (!failed) && (2 != fscanf(fd, "%d %d", &s_CtrlSettings.iMAVLinkSysIdController, &s_CtrlSettings.iDisableHDMIOverscan)) ) - { - s_CtrlSettings.iMAVLinkSysIdController = DEFAULT_MAVLINK_SYS_ID_CONTROLLER; - s_CtrlSettings.iDisableHDMIOverscan = 0; - failed = 7; - } - if ( (!failed) && (1 != fscanf(fd, "%d", &s_CtrlSettings.iRenderFPS)) ) - { s_CtrlSettings.iRenderFPS = 10; failed = 8; } + if ( 3 != fscanf(fd, "%*s %d %d %d", &s_CtrlSettings.iTelemetryForwardUSBType, &s_CtrlSettings.iTelemetryForwardUSBPort, &s_CtrlSettings.iTelemetryForwardUSBPacketSize) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 5"); } - if ( (!failed) && (1 != fscanf(fd, "%d", &s_CtrlSettings.iShowVoltage)) ) - { s_CtrlSettings.iShowVoltage = 1; failed = 9; } + if ( 2 != fscanf(fd, "%d %d", &s_CtrlSettings.iTelemetryOutputSerialPortIndex, &s_CtrlSettings.iTelemetryInputSerialPortIndex) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 6"); } - if ( (!failed) && (2 != fscanf(fd, "%d %d", &s_CtrlSettings.nRetryRetransmissionAfterTimeoutMS, &s_CtrlSettings.nRequestRetransmissionsOnVideoSilenceMs)) ) - { - s_CtrlSettings.nRetryRetransmissionAfterTimeoutMS = DEFAULT_VIDEO_RETRANS_MINIMUM_RETRY_INTERVAL; - s_CtrlSettings.nRequestRetransmissionsOnVideoSilenceMs = DEFAULT_VIDEO_RETRANS_REQUEST_ON_VIDEO_SILENCE_MS; - failed = 10; - } - - if ( (!failed) && (2 != fscanf(fd, "%d %u", &s_CtrlSettings.nUseFixedIP, &s_CtrlSettings.uFixedIP)) ) - { - s_CtrlSettings.nUseFixedIP = 0; - s_CtrlSettings.uFixedIP = (192<<24) | (168<<16) | (1<<8) | 20; - failed = 11; - } + if ( 2 != fscanf(fd, "%d %d", &s_CtrlSettings.iMAVLinkSysIdController, &s_CtrlSettings.iDisableHDMIOverscan) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 7"); } - if ( (!failed) && (3 != fscanf(fd, "%*s %d %d %d", &s_CtrlSettings.nVideoForwardETHType, &s_CtrlSettings.nVideoForwardETHPort, &s_CtrlSettings.nVideoForwardETHPacketSize)) ) - { s_CtrlSettings.nVideoForwardETHType = 0; s_CtrlSettings.nVideoForwardETHPort = 5010; s_CtrlSettings.nVideoForwardETHPacketSize = 1024; failed = 12; } + if ( 2 != fscanf(fd, "%d %d", &s_CtrlSettings.iRenderFPS, &s_CtrlSettings.iShowVoltage) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 8"); } - if ( (!failed) && (1 != fscanf(fd, "%d", &s_CtrlSettings.nAutomaticTxCard)) ) - { - s_CtrlSettings.nAutomaticTxCard = 1; - failed = 13; - } + if ( 2 != fscanf(fd, "%d %d", &s_CtrlSettings.nRetryRetransmissionAfterTimeoutMS, &s_CtrlSettings.nRequestRetransmissionsOnVideoSilenceMs) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 9"); } + + if ( 2 != fscanf(fd, "%d %u", &s_CtrlSettings.nUseFixedIP, &s_CtrlSettings.uFixedIP) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 10"); } - if ( (!failed) && (2 != fscanf(fd, "%d %d", &s_CtrlSettings.nRotaryEncoderFunction, &s_CtrlSettings.nRotaryEncoderSpeed)) ) - { - s_CtrlSettings.nRotaryEncoderFunction = 1; - s_CtrlSettings.nRotaryEncoderSpeed = 0; - failed = 14; - } + if ( 3 != fscanf(fd, "%*s %d %d %d", &s_CtrlSettings.nVideoForwardETHType, &s_CtrlSettings.nVideoForwardETHPort, &s_CtrlSettings.nVideoForwardETHPacketSize) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 11"); } - if ( (!failed) && (2 != fscanf(fd, "%d %d", &s_CtrlSettings.nPingClockSyncFrequency, &s_CtrlSettings.nGraphRadioRefreshInterval)) ) - { - s_CtrlSettings.nPingClockSyncFrequency = DEFAULT_PING_FREQUENCY; - s_CtrlSettings.nGraphRadioRefreshInterval = 100; - failed = 15; - } + if ( 3 != fscanf(fd, "%d %d %d", &s_CtrlSettings.nAutomaticTxCard, &s_CtrlSettings.nRotaryEncoderFunction, &s_CtrlSettings.nRotaryEncoderSpeed) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 12"); } - if ( (!failed) && (1 != fscanf(fd, "%d", &s_CtrlSettings.nGraphVideoRefreshInterval)) ) - s_CtrlSettings.nGraphVideoRefreshInterval = 100; + if ( 3 != fscanf(fd, "%d %d %d", &s_CtrlSettings.nPingClockSyncFrequency, &s_CtrlSettings.nGraphRadioRefreshInterval, &s_CtrlSettings.nGraphVideoRefreshInterval) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 13"); } // Extended values - if ( (!failed) && (1 != fscanf(fd, "%d", &s_CtrlSettings.iDisableRetransmissionsAfterControllerLinkLostMiliseconds)) ) - s_CtrlSettings.iDisableRetransmissionsAfterControllerLinkLostMiliseconds = DEFAULT_CONTROLLER_LINK_MILISECONDS_TIMEOUT_TO_DISABLE_RETRANSMISSIONS; - - if ( (!failed) && (1 != fscanf(fd, "%d", &s_CtrlSettings.iVideoDecodeStatsSnapshotClosesOnTimeout)) ) - s_CtrlSettings.iVideoDecodeStatsSnapshotClosesOnTimeout = 1; - - if ( (!failed) && (2 != fscanf(fd, "%d %d", &s_CtrlSettings.nRotaryEncoderFunction2, &s_CtrlSettings.nRotaryEncoderSpeed2)) ) - { - s_CtrlSettings.nRotaryEncoderFunction2 = 2; - s_CtrlSettings.nRotaryEncoderSpeed2 = 0; - } + if ( 2 != fscanf(fd, "%d %d", &s_CtrlSettings.iDisableRetransmissionsAfterControllerLinkLostMiliseconds, &s_CtrlSettings.iVideoDecodeStatsSnapshotClosesOnTimeout) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 14"); } - if ( (!failed) && ( 1 != fscanf(fd, "%d", &iDummy)) ) - iDummy = -1; - - if ( (!failed) && ( 1 != fscanf(fd, "%d", &s_CtrlSettings.iFreezeOSD)) ) - s_CtrlSettings.iFreezeOSD = 0; + if ( 2 != fscanf(fd, "%d %d", &s_CtrlSettings.nRotaryEncoderFunction2, &s_CtrlSettings.nRotaryEncoderSpeed2) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 15"); } - if ( (!failed) && ( 1 != fscanf(fd, "%d", &s_CtrlSettings.iDevSwitchVideoProfileUsingQAButton)) ) - s_CtrlSettings.iDevSwitchVideoProfileUsingQAButton = -1; - - if ( (!failed) && ( 1 != fscanf(fd, "%d", &s_CtrlSettings.iShowControllerAdaptiveInfoStats)) ) - s_CtrlSettings.iShowControllerAdaptiveInfoStats = 0; + if ( 2 != fscanf(fd, "%d %d", &iDummy, &s_CtrlSettings.iFreezeOSD) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 16"); } - if ( (!failed) && ( 1 != fscanf(fd, "%d", &s_CtrlSettings.iShowVideoStreamInfoCompactType)) ) - s_CtrlSettings.iShowVideoStreamInfoCompactType = 0; + if ( 2 != fscanf(fd, "%d %d", &s_CtrlSettings.iDevSwitchVideoProfileUsingQAButton, &s_CtrlSettings.iShowControllerAdaptiveInfoStats) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 17"); } - if ( (!failed) && ( 1 != fscanf(fd, "%d", &s_CtrlSettings.iTXPowerSiK)) ) - s_CtrlSettings.iTXPowerSiK = DEFAULT_RADIO_SIK_TX_POWER; + if ( 1 != fscanf(fd, "%d", &s_CtrlSettings.iShowVideoStreamInfoCompactType) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 18"); } - if ( (!failed) && ( 4 != fscanf(fd, "%d %d %d %d", &s_CtrlSettings.iSearchSiKAirRate, &s_CtrlSettings.iSearchSiKECC, &s_CtrlSettings.iSearchSiKLBT, &s_CtrlSettings.iSearchSiKMCSTR)) ) - { - s_CtrlSettings.iSearchSiKAirRate = DEFAULT_RADIO_DATARATE_SIK_AIR; - s_CtrlSettings.iSearchSiKECC = 0; - s_CtrlSettings.iSearchSiKLBT = 0; - s_CtrlSettings.iSearchSiKMCSTR = 0; - } + if ( 4 != fscanf(fd, "%d %d %d %d", &s_CtrlSettings.iSearchSiKAirRate, &s_CtrlSettings.iSearchSiKECC, &s_CtrlSettings.iSearchSiKLBT, &s_CtrlSettings.iSearchSiKMCSTR) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 19"); } - if ( (!failed) && (2 != fscanf(fd, "%d %d", &s_CtrlSettings.iAudioOutputDevice, &s_CtrlSettings.iAudioOutputVolume)) ) - { - s_CtrlSettings.iAudioOutputDevice = 1; - s_CtrlSettings.iAudioOutputVolume = 100; - failed = 15; - } - if ( (!failed) && (2 != fscanf(fd, "%d %u", &s_CtrlSettings.iDevRxLoopTimeout, &s_CtrlSettings.uShowBigRxHistoryInterface)) ) - { - s_CtrlSettings.iDevRxLoopTimeout = DEFAULT_MAX_RX_LOOP_TIMEOUT_MILISECONDS; - s_CtrlSettings.uShowBigRxHistoryInterface = 0; - failed = 16; - } + if ( 2 != fscanf(fd, "%d %d", &s_CtrlSettings.iAudioOutputDevice, &s_CtrlSettings.iAudioOutputVolume) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 20"); } - if ( (!failed) && (1 != fscanf(fd, "%d", &s_CtrlSettings.iSiKPacketSize)) ) - { s_CtrlSettings.iSiKPacketSize = DEFAULT_SIK_PACKET_SIZE; } + if ( 2 != fscanf(fd, "%d %u", &s_CtrlSettings.iDevRxLoopTimeout, &s_CtrlSettings.uShowBigRxHistoryInterface) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 21"); } - if ( (!failed) && (2 != fscanf(fd, "%d %d", &s_CtrlSettings.iRadioRxThreadPriority, &s_CtrlSettings.iRadioTxThreadPriority)) ) - { - s_CtrlSettings.iRadioRxThreadPriority = DEFAULT_PRIORITY_THREAD_RADIO_RX; - s_CtrlSettings.iRadioTxThreadPriority = DEFAULT_PRIORITY_THREAD_RADIO_TX; - } + if ( 1 != fscanf(fd, "%d", &s_CtrlSettings.iSiKPacketSize) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 22"); } - if ( (!failed) && (2 != fscanf(fd, "%d %d", &s_CtrlSettings.iRadioRxThreadPriority, &s_CtrlSettings.iRadioTxThreadPriority)) ) - { - s_CtrlSettings.iRadioRxThreadPriority = DEFAULT_PRIORITY_THREAD_RADIO_RX; - s_CtrlSettings.iRadioTxThreadPriority = DEFAULT_PRIORITY_THREAD_RADIO_TX; - } + if ( 2 != fscanf(fd, "%d %d", &s_CtrlSettings.iRadioRxThreadPriority, &s_CtrlSettings.iRadioTxThreadPriority) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 23"); } - if ( (!failed) && (2 != fscanf(fd, "%d %d", &s_CtrlSettings.iRadioTxUsesPPCAP, &s_CtrlSettings.iRadioBypassSocketBuffers)) ) - { - s_CtrlSettings.iRadioTxUsesPPCAP = DEFAULT_USE_PPCAP_FOR_TX; - s_CtrlSettings.iRadioBypassSocketBuffers = DEFAULT_BYPASS_SOCKET_BUFFERS; - } + if ( 3 != fscanf(fd, "%d %d %d", &s_CtrlSettings.iRadioTxUsesPPCAP, &s_CtrlSettings.iRadioBypassSocketBuffers, &s_CtrlSettings.iFixedTxPower) ) + { failed = 1; log_softerror_and_alarm("Load ctrl settings, failed on line 24"); } fclose(fd); @@ -401,11 +299,6 @@ int load_ControllerSettings() s_CtrlSettings.iNiceRXVideo = DEFAULT_PRIORITY_PROCESS_VIDEO_RX; if ( s_CtrlSettings.iNiceCentral < -16 || s_CtrlSettings.iNiceCentral > 0 ) s_CtrlSettings.iNiceCentral = DEFAULT_PRIORITY_PROCESS_CENTRAL; - - if ( s_CtrlSettings.iTXPowerSiK < 1 ) - s_CtrlSettings.iTXPowerSiK = DEFAULT_RADIO_SIK_TX_POWER; - if ( s_CtrlSettings.iTXPowerSiK > 20 ) - s_CtrlSettings.iTXPowerSiK = DEFAULT_RADIO_SIK_TX_POWER; if ( s_CtrlSettings.iRenderFPS < 10 || s_CtrlSettings.iRenderFPS > 30 ) s_CtrlSettings.iRenderFPS = 10; @@ -420,6 +313,7 @@ int load_ControllerSettings() if ( (s_CtrlSettings.iSiKPacketSize < 10) || (s_CtrlSettings.iSiKPacketSize > 250 ) ) s_CtrlSettings.iSiKPacketSize = DEFAULT_SIK_PACKET_SIZE; + if ( failed ) { log_line("Incomplete/Invalid settings file %s, error code: %d. Reseted to default.", szFile, failed); diff --git a/code/base/ctrl_settings.h b/code/base/ctrl_settings.h index bfae5fef..ac7b4c69 100644 --- a/code/base/ctrl_settings.h +++ b/code/base/ctrl_settings.h @@ -2,7 +2,7 @@ #include "../base/hardware.h" #include "../base/ctrl_preferences.h" -#define CONTROLLER_SETTINGS_STAMP_ID "vV.6" +#define CONTROLLER_SETTINGS_STAMP_ID "v10.1" #ifdef __cplusplus extern "C" { @@ -11,13 +11,7 @@ extern "C" { typedef struct { int iUseBrokenVideoCRC; - int iTXPowerRTL8812AU; - int iTXPowerRTL8812EU; - int iTXPowerAtheros; - int iTXPowerSiK; - int iMaxTXPowerRTL8812AU; - int iMaxTXPowerRTL8812EU; - int iMaxTXPowerAtheros; + int iFixedTxPower; int iHDMIBoost; int iOverVoltage; // 0 - disabled int iFreqARM; // 0 - disabled diff --git a/code/base/flags.h b/code/base/flags.h index 48710f8c..549dc1ef 100644 --- a/code/base/flags.h +++ b/code/base/flags.h @@ -91,6 +91,8 @@ #define MODEL_CHANGED_CONTROLLER_TELEMETRY 25 #define MODEL_CHANGED_RELAY_PARAMS 26 +#define MODEL_CHANGED_VIDEO_IPQUANTIZATION_DELTA 27 + #define MODEL_CHANGED_SERIAL_PORTS 30 #define MODEL_CHANGED_AUDIO_PARAMS 31 diff --git a/code/base/flags_osd.h b/code/base/flags_osd.h index 863c23ba..48e9d61a 100644 --- a/code/base/flags_osd.h +++ b/code/base/flags_osd.h @@ -4,7 +4,7 @@ #define OSD_FLAG_SHOW_VIDEO_MBPS ((u32)(((u32)0x01))) #define OSD_FLAG_TOTAL_DISTANCE ((u32)(((u32)0x01)<<1)) #define OSD_FLAG_EXTENDED_VIDEO_DECODE_STATS ((u32)(((u32)0x01)<<2)) -#define OSD_FLAG_SHOW_STATS_VIDEO_KEYFRAMES_INFO ((u32)(((u32)0x01)<<3)) +#define OSD_FLAG_SHOW_STATS_VIDEO_H264_FRAMES_INFO ((u32)(((u32)0x01)<<3)) #define OSD_FLAG_SHOW_EFFICIENCY_STATS ((u32)(((u32)0x01)<<5)) #define OSD_FLAG_REVERT_PITCH ((u32)(((u32)0x01)<<6)) // bit 7 #define OSD_FLAG_REVERT_ROLL ((u32)(((u32)0x01)<<7)) // bit 8 diff --git a/code/base/flags_video.h b/code/base/flags_video.h index 2dc5e736..72ccb701 100644 --- a/code/base/flags_video.h +++ b/code/base/flags_video.h @@ -53,7 +53,8 @@ #define VIDEO_BITRATE_FIELD_MASK 0x7FFFFFFF // Video flags -#define VIDEO_FLAG_FILL_H264_SPT_TIMINGS ((u32)((u32)0x01)) + +//#define VIDEO_FLAG_FILL_H264_SPT_TIMINGS ((u32)((u32)0x01)) // deprecated in 10.1 #define VIDEO_FLAG_IGNORE_TX_SPIKES ((u32)(((u32)0x01)<<1)) #define VIDEO_FLAG_ENABLE_LOCAL_HDMI_OUTPUT ((u32)(((u32)0x01)<<2)) #define VIDEO_FLAG_RETRANSMISSIONS_FAST ((u32)(((u32)0x01)<<3)) diff --git a/code/base/hardware.cpp b/code/base/hardware.cpp index 53545bfb..dc2464af 100644 --- a/code/base/hardware.cpp +++ b/code/base/hardware.cpp @@ -127,8 +127,6 @@ hw_joystick_info_t s_HardwareJoystickInfo[MAX_JOYSTICK_INTERFACES]; int s_iUSBMounted = 0; char s_szUSBMountName[64]; -u32 s_uBaseRubyVersion = 0; - void _hardware_detectSystemType() { log_line("[Hardware] Detecting system type..."); @@ -160,11 +158,21 @@ void _hardware_detectSystemType() log_line("Hardware: Detected GPIO signal to start as vehicle or relay."); s_iHardwareSystemIsVehicle = 1; } - else if( (access( FILE_FORCE_VEHICLE, R_OK ) != -1) || (access( "/boot/forcevehicle.txt", R_OK ) != -1) ) + #endif + + #if defined (HW_PLATFORM_RASPBERRY) || defined (HW_PLATFORM_RADXA_ZERO3) + if( access( FILE_FORCE_VEHICLE, R_OK ) != -1 ) { log_line("Hardware: Detected file %s to force start as vehicle or relay.", FILE_FORCE_VEHICLE); s_iHardwareSystemIsVehicle = 1; } + strcpy(szFile, FOLDER_WINDOWS_PARTITION); + strcat(szFile, "forcevehicle.txt"); + if( access( szFile, R_OK ) != -1 ) + { + log_line("Hardware: Detected file %s to force start as vehicle or relay.", szFile); + s_iHardwareSystemIsVehicle = 1; + } #endif if( access( FILE_FORCE_VEHICLE_NO_CAMERA, R_OK ) != -1 ) @@ -173,12 +181,14 @@ void _hardware_detectSystemType() s_iHardwareSystemIsVehicle = 1; } + #if defined (HW_PLATFORM_RASPBERRY) || defined (HW_PLATFORM_OPENIPC_CAMERA) if ( hardware_hasCamera() && (hardware_getCameraType() != CAMERA_TYPE_NONE) ) { log_line("Hardware: Has Camera."); s_iHardwareSystemIsVehicle = 1; } - + #endif + #ifdef HW_CAPABILITY_GPIO val = GPIORead(GPIOGetPinDetectController()); if ( val == 1 ) @@ -207,6 +217,8 @@ void _hardware_detectSystemType() strcpy(szBuff, "N/A"); log_line("[Hardware] Detected board type: %s", szBuff); + strcpy(szFile, FOLDER_RUBY_TEMP); + strcat(szFile, FILE_CONFIG_SYSTEM_TYPE); fd = fopen(szFile, "w"); if ( NULL != fd ) { @@ -470,6 +482,12 @@ void hardware_swap_buttons(int swap) u32 hardware_getOnlyBoardType() { + static int s_iGetBoardTypeOnlyExecuted = 0; + + if ( s_iGetBoardTypeOnlyExecuted ) + return s_uHardwareBoardType; + + s_iGetBoardTypeOnlyExecuted = 1; char szBuff[256]; #ifdef HW_PLATFORM_RASPBERRY hw_execute_bash_command("cat /proc/cpuinfo | grep 'Revision' | awk '{print $3}'", szBuff); @@ -495,24 +513,42 @@ u32 hardware_getOnlyBoardType() if ( strcmp(szBuff, "d03115") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI4B;} if ( strcmp(szBuff, "d03116") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI4B;} + if ( strcmp(szBuff, "9020e0") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI3APLUS;} if ( strcmp(szBuff, "29020e0") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI3APLUS;} + + if ( strcmp(szBuff, "a02082") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI3B;} + if ( strcmp(szBuff, "a22082") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI3B;} + if ( strcmp(szBuff, "a32082") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI3B;} + if ( strcmp(szBuff, "a52082") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI3B;} + if ( strcmp(szBuff, "a020d3") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI3BPLUS;} if ( strcmp(szBuff, "2a02082") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI3B;} if ( strcmp(szBuff, "2a22082") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI3B;} if ( strcmp(szBuff, "2a32082") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI3B;} if ( strcmp(szBuff, "2a52082") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI3B;} if ( strcmp(szBuff, "2a020d3") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI3BPLUS;} + if ( strcmp(szBuff, "900093") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PIZERO;} + if ( strcmp(szBuff, "9000c1") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PIZEROW;} + if ( strcmp(szBuff, "900092") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PIZERO;} if ( strcmp(szBuff, "1900093") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PIZERO;} if ( strcmp(szBuff, "19000c1") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PIZEROW;} if ( strcmp(szBuff, "2900092") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PIZERO;} - if ( strcmp(szBuff, "2900093") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PIZERO;} if ( strcmp(szBuff, "29000c1") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PIZEROW;} + + if ( strcmp(szBuff, "902120") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PIZERO2;} if ( strcmp(szBuff, "2902120") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PIZERO2;} + if ( strcmp(szBuff, "920092") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PIZERO;} + if ( strcmp(szBuff, "920093") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PIZERO;} if ( strcmp(szBuff, "2920092") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PIZERO;} if ( strcmp(szBuff, "2920093") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PIZERO;} + if ( strcmp(szBuff, "a01040") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI2B;} + if ( strcmp(szBuff, "a21041") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI2BV11;} + if ( strcmp(szBuff, "a01041") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI2BV11;} + if ( strcmp(szBuff, "a22042") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI2BV12;} + if ( strcmp(szBuff, "2a01040") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI2B;} if ( strcmp(szBuff, "2a21041") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI2BV11;} if ( strcmp(szBuff, "2a01041") == 0 ) { s_uHardwareBoardType = BOARD_TYPE_PI2BV11;} @@ -540,9 +576,9 @@ u32 hardware_getOnlyBoardType() s_uHardwareBoardType = BOARD_TYPE_OPENIPC_GOKE300; } if ( NULL != strstr(szBuff, "ssc338") ) - s_uHardwareBoardType = BOARD_TYPE_OPENIPC_SIGMASTER_338Q; + s_uHardwareBoardType = BOARD_TYPE_OPENIPC_SIGMASTAR_338Q; if ( NULL != strstr(szBuff, "ssc33x") ) - s_uHardwareBoardType = BOARD_TYPE_OPENIPC_SIGMASTER_338Q; + s_uHardwareBoardType = BOARD_TYPE_OPENIPC_SIGMASTAR_338Q; #endif @@ -560,48 +596,6 @@ u32 hardware_getBoardType() return s_uHardwareBoardType; } -u32 hardware_get_base_ruby_version() -{ - if ( 0 != s_uBaseRubyVersion ) - return s_uBaseRubyVersion; - - char szFile[MAX_FILE_PATH_SIZE]; - szFile[0] = 0; - FILE* fd = try_open_base_version_file(szFile); - if ( NULL == fd ) - { - log_softerror_and_alarm("[Hardware] Failed to open base Ruby version file (%s).", szFile); - return s_uBaseRubyVersion; - } - char szBuff[32]; - if ( 1 != fscanf(fd, "%s", szBuff) ) - { - fclose(fd); - log_softerror_and_alarm("[Hardware] Failed to read base Ruby version file (%s).", szFile); - return s_uBaseRubyVersion; - } - fclose(fd); - log_line("[Hardware] Read raw base Ruby version: [%s] from file (%s)", szBuff, szFile); - - for( int i=0; i<(int)strlen(szBuff); i++ ) - { - if ( szBuff[i] == '.' ) - { - szBuff[i] = 0; - int iMajor = 0; - int iMinor = 0; - sscanf(szBuff, "%d", &iMajor); - sscanf(&szBuff[i+1], "%d", &iMinor); - s_uBaseRubyVersion = (((u32)iMajor) << 8) | ((u32)iMinor); - log_line("[Hardware] Parsed base Ruby version: %u.%u", (s_uBaseRubyVersion>>8) & 0xFF, s_uBaseRubyVersion & 0xFF); - return s_uBaseRubyVersion; - } - } - log_softerror_and_alarm("[Hardware] Failed to parse base Ruby version from file (%s).", szFile); - return s_uBaseRubyVersion; -} - - int hardware_board_is_raspberry(u32 uBoardType) { if ( (uBoardType & BOARD_TYPE_MASK) > 0 ) @@ -614,7 +608,7 @@ int hardware_board_is_openipc(u32 uBoardType) { if ( hardware_board_is_goke(uBoardType) ) return 1; - if ( (uBoardType & BOARD_TYPE_MASK) == BOARD_TYPE_OPENIPC_SIGMASTER_338Q ) + if ( (uBoardType & BOARD_TYPE_MASK) == BOARD_TYPE_OPENIPC_SIGMASTAR_338Q ) return 1; return 0; } @@ -630,7 +624,7 @@ int hardware_board_is_goke(u32 uBoardType) int hardware_board_is_sigmastar(u32 uBoardType) { - if ( (uBoardType & BOARD_TYPE_MASK) == BOARD_TYPE_OPENIPC_SIGMASTER_338Q ) + if ( (uBoardType & BOARD_TYPE_MASK) == BOARD_TYPE_OPENIPC_SIGMASTAR_338Q ) return 1; return 0; } @@ -1704,29 +1698,43 @@ void hardware_recording_led_set_blinking() s_TimeLastRecordingLedBlink = get_current_timestamp_ms(); } -int hardware_has_eth() +static char s_szHardwareETHName[64]; + +char* hardware_has_eth() { - int nHasETH = 1; - char szOutput[1024]; + char szETHName[128]; + s_szHardwareETHName[0] = 0; - szOutput[0] = 0; - #if defined(HW_PLATFORM_RASPBERRY) - hw_execute_bash_command_raw("ip link | grep eth0 2>&1", szOutput); - #endif + hw_execute_bash_command_raw("ls /sys/class/net/ | grep eth0", szETHName); + if ( strlen(szETHName) < 4 ) + hw_execute_bash_command_raw("ls /sys/class/net/ | grep eth1", szETHName); + if ( strlen(szETHName) < 4 ) + hw_execute_bash_command_raw("ls /sys/class/net/ | grep etx", szETHName); - #if defined(HW_PLATFORM_RADXA_ZERO3) - hw_execute_bash_command_raw("ip link | grep enx 2>&1", szOutput); - if ( 0 == szOutput[0] || NULL != strstr(szOutput, "not found") ) - hw_execute_bash_command_raw("ip link | grep eth0 2>&1", szOutput); - #endif - - if ( (0 == szOutput[0]) || (NULL != strstr(szOutput, "not found")) ) + if ( strlen(szETHName) < 4 ) { - nHasETH = 0; - szOutput[1023] = 0; - log_line("ETH not found. Response: [%s]", szOutput); + log_line("ETH not found."); + return NULL; + } + + for( int i=strlen(szETHName)-1; i>0; i-- ) + { + if ( (szETHName[i] == 10) || (szETHName[i] == 13) || (szETHName[i] == ' ') ) + szETHName[i] = 0; + else + break; } - return nHasETH; + strncpy(s_szHardwareETHName, szETHName, sizeof(s_szHardwareETHName)/sizeof(s_szHardwareETHName[0])); + + char szComm[256]; + char szOutput[1024]; + szOutput[0] = 0; + sprintf(szComm, "ip link set dev %s up", szETHName); + hw_execute_bash_command(szComm, szOutput); + if ( 5 < strlen(szOutput) ) + log_line("ETH up command failed: (%s)", szOutput); + + return s_szHardwareETHName; } void hardware_set_default_sigmastar_cpu_freq() @@ -1949,7 +1957,7 @@ void hardware_set_oipc_gpu_boost(int iGPUBoost) #endif } -void _hardware_set_int_affinity_core(char* szIntName, int iCoreIndex) +void _hardware_set_int_affinity_core(const char* szIntName, int iCoreIndex) { if ( (NULL == szIntName) || (0 == szIntName[0]) || (iCoreIndex < 0) ) return; diff --git a/code/base/hardware.h b/code/base/hardware.h index 19f37080..a441f1a7 100644 --- a/code/base/hardware.h +++ b/code/base/hardware.h @@ -14,6 +14,7 @@ #define BOARD_TYPE_MASK (u32)0xFF #define BOARD_SUBTYPE_MASK (u32)0xFF00 +#define BOARD_SUBTYPE_SHIFT 8 #define BOARD_TYPE_NONE 0 #define BOARD_TYPE_PIZERO 1 @@ -31,13 +32,17 @@ #define BOARD_TYPE_OPENIPC_GOKE210 31 #define BOARD_TYPE_OPENIPC_GOKE300 32 -#define BOARD_TYPE_OPENIPC_SIGMASTER_338Q 40 +#define BOARD_TYPE_OPENIPC_SIGMASTAR_338Q 40 #define BOARD_SUBTYPE_OPENIPC_UNKNOWN 0 -#define BOARD_SUBTYPE_OPENIPC_GENERIC ((u32)(((u32)1)<<8)) -#define BOARD_SUBTYPE_OPENIPC_AIO_ULTRASIGHT ((u32)(((u32)2)<<8)) -#define BOARD_SUBTYPE_OPENIPC_AIO_MARIO ((u32)(((u32)3)<<8)) -#define BOARD_SUBTYPE_OPENIPC_AIO_RUNCAM ((u32)(((u32)4)<<8)) +#define BOARD_SUBTYPE_OPENIPC_GENERIC ((u32)1) +#define BOARD_SUBTYPE_OPENIPC_GENERIC_30KQ ((u32)2) +#define BOARD_SUBTYPE_OPENIPC_AIO_ULTRASIGHT ((u32)3) +#define BOARD_SUBTYPE_OPENIPC_AIO_MARIO ((u32)4) +#define BOARD_SUBTYPE_OPENIPC_AIO_RUNCAM ((u32)5) +#define BOARD_SUBTYPE_OPENIPC_AIO_EMAX ((u32)6) +#define BOARD_SUBTYPE_OPENIPC_AIO_THINKER ((u32)7) +#define BOARD_SUBTYPE_OPENIPC_LAST ((u32)8) #define BOARD_TYPE_RADXA_ZERO3 60 @@ -95,7 +100,6 @@ void hardware_swap_buttons(int swap); u32 hardware_getOnlyBoardType(); u32 hardware_getBoardType(); -u32 hardware_get_base_ruby_version(); int hardware_board_is_raspberry(u32 uBoardType); int hardware_board_is_openipc(u32 uBoardType); @@ -152,7 +156,7 @@ void hardware_recording_led_set_off(); void hardware_recording_led_set_on(); void hardware_recording_led_set_blinking(); -int hardware_has_eth(); +char* hardware_has_eth(); void hardware_set_default_sigmastar_cpu_freq(); void hardware_set_default_radxa_cpu_freq(); diff --git a/code/base/hardware_camera.cpp b/code/base/hardware_camera.cpp index e0acb9db..c407249d 100644 --- a/code/base/hardware_camera.cpp +++ b/code/base/hardware_camera.cpp @@ -416,7 +416,19 @@ void hardware_camera_apply_all_majestic_settings(Model* pModel, camera_profile_p hw_execute_bash_command_raw("cli -s .video1.enabled false", NULL); hw_execute_bash_command_raw("cli -s .video0.enabled true", NULL); hw_execute_bash_command_raw("cli -s .video0.rcMode cbr", NULL); + hw_execute_bash_command_raw("cli -s .isp.slowShutter disabled", NULL); + if ( pVideoParams->iH264Slices <= 1 ) + { + hw_execute_bash_command_raw("cli -s .video0.sliceUnits 1", NULL); + hw_execute_bash_command_raw("cli -d .video0.sliceUnits", NULL); + } + else + { + sprintf(szComm, "cli -s .video0.sliceUnits %d", pVideoParams->iH264Slices); + hw_execute_bash_command_raw(szComm, NULL); + } + if ( pVideoParams->uVideoExtraFlags & VIDEO_FLAG_GENERATE_H265 ) hw_execute_bash_command_raw("cli -s .video0.codec h265", NULL); else @@ -431,6 +443,9 @@ void hardware_camera_apply_all_majestic_settings(Model* pModel, camera_profile_p sprintf(szComm, "cli -s .video0.size %dx%d", pModel->video_link_profiles[iVideoProfile].width, pModel->video_link_profiles[iVideoProfile].height); hw_execute_bash_command_raw(szComm, NULL); + sprintf(szComm, "cli -s .video0.qpDelta %d", pModel->video_link_profiles[iVideoProfile].iIPQuantizationDelta); + hw_execute_bash_command_raw(szComm, NULL); + float fGOP = 0.5; int keyframe_ms = pModel->getInitialKeyframeIntervalMs(iVideoProfile); fGOP = ((float)keyframe_ms) / 1000.0; diff --git a/code/base/hardware_files.h b/code/base/hardware_files.h index 0c36da83..0756c1ae 100644 --- a/code/base/hardware_files.h +++ b/code/base/hardware_files.h @@ -12,7 +12,6 @@ extern "C" { void hardware_mount_root(); void hardware_mount_boot(); int hardware_get_free_space_kb(); - #ifdef __cplusplus } #endif diff --git a/code/base/hardware_radio.c b/code/base/hardware_radio.c index 813b3dd3..be17b831 100644 --- a/code/base/hardware_radio.c +++ b/code/base/hardware_radio.c @@ -52,7 +52,7 @@ #include "hw_procs.h" #include "../common/string_utils.h" -#define MAX_USB_DEVICES_INFO 12 +#define MAX_USB_DEVICES_INFO 24 static int s_iEnumeratedUSBRadioInterfaces = 0; @@ -64,8 +64,8 @@ static int s_iHwRadiosCount = 0; static int s_iHwRadiosSupportedCount = 0; static int s_HardwareRadiosEnumeratedOnce = 0; -int g_ArrayTestRadioRates[] = {18000000, 24000000, 36000000, 48000000, -1, -2, -3, -4, -5, -6, -7, -8}; -int g_ArrayTestRadioRatesCount = 12; +int g_ArrayTestRadioRates[] = {18000000, 24000000, 36000000, 48000000, -1, -2, -3, -4, -5, -6}; +int g_ArrayTestRadioRatesCount = 10; void reset_runtime_radio_rx_info(type_runtime_radio_rx_info* pRuntimeRadioRxInfo) { @@ -106,18 +106,29 @@ radio_hw_info_t* hardware_get_radio_info_array() return &(sRadioInfo[0]); } -void hardware_log_radio_info() +void hardware_log_radio_info(radio_hw_info_t* pRadioInfoArray, int iCount) { char szBuff[1024]; log_line(""); - for( int i=0; i= MAX_RADIO_INTERFACES ) + if ( (iTotalCount < 0) || (iTotalCount >= MAX_RADIO_INTERFACES) ) succeeded = 0; - memcpy(bufferIn+posIn, &s_iHwRadiosCount, sizeof(s_iHwRadiosCount)); - posIn += sizeof(s_iHwRadiosCount); + memcpy(bufferIn+posIn, &iTotalCount, sizeof(iTotalCount)); + posIn += sizeof(iTotalCount); } + + // Read supported interfaces count if ( succeeded ) { - if ( sizeof(s_iHwRadiosSupportedCount) != fread(&s_iHwRadiosSupportedCount, 1, sizeof(s_iHwRadiosSupportedCount), fp) ) + if ( sizeof(iSupportedCount) != fread(&iSupportedCount, 1, sizeof(iSupportedCount), fp) ) succeeded = 0; - if ( s_iHwRadiosSupportedCount < 0 || s_iHwRadiosSupportedCount >= MAX_RADIO_INTERFACES ) + if ( (iSupportedCount < 0) || (iSupportedCount >= MAX_RADIO_INTERFACES) ) succeeded = 0; - memcpy(bufferIn+posIn, &s_iHwRadiosSupportedCount, sizeof(s_iHwRadiosSupportedCount)); - posIn += sizeof(s_iHwRadiosSupportedCount); + memcpy(bufferIn+posIn, &iSupportedCount, sizeof(iSupportedCount)); + posIn += sizeof(iSupportedCount); } + + // Read interfaces if ( succeeded ) { - for( int i=0; i 0) && (iCardModel <50) ) + return RADIO_HW_DRIVER_REALTEK_RTL88XXAU; return 0; } -void _hardware_find_usb_radio_interfaces_info() +int _hardware_find_usb_radio_interfaces_info() { s_iEnumeratedUSBRadioInterfaces = 1; s_iFoundUSBRadioInterfaces = 0; + int iCountKnownRadioCards = 0; #ifdef HW_PLATFORM_OPENIPC_CAMERA log_line("[HardwareRadio] Finding USB radio interfaces and devices for OpenIPC platform..."); #else @@ -667,7 +715,7 @@ void _hardware_find_usb_radio_interfaces_info() bLookForId = 0; #ifdef HW_PLATFORM_OPENIPC_CAMERA - s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].iDriver = _hardware_radio_get_product_id_open_ipc_wifi_radio_driver_id(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szProductId); + s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].iDriver = hardware_radio_get_driver_id_for_product_id(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szProductId); strncpy(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName, str_get_radio_card_model_string(_hardware_detect_card_model(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szProductId)), sizeof(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName)/sizeof(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName[0]) ); s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName[sizeof(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName)/sizeof(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName[0]) - 1] = 0; s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].iPortNb = -1; @@ -677,6 +725,13 @@ void _hardware_find_usb_radio_interfaces_info() s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szProductId, s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName); + int iCardModel = _hardware_detect_card_model(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szProductId); + if ( iCardModel > 0 ) + { + iCountKnownRadioCards++; + log_line("[HardwareRadio] USB device %s is a known radio interface, type: %s", + s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szProductId, str_get_radio_card_model_string(iCardModel)); + } if ( s_iFoundUSBRadioInterfaces < MAX_USB_DEVICES_INFO-1 ) s_iFoundUSBRadioInterfaces++; else @@ -689,7 +744,7 @@ void _hardware_find_usb_radio_interfaces_info() //strncpy(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName, szBuff+i, sizeof(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName)-1 ); //s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].iDriver = 0; //s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName[sizeof(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName)-1] = 0; - s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].iDriver = _hardware_radio_get_product_id_open_ipc_wifi_radio_driver_id(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szProductId); + s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].iDriver = hardware_radio_get_driver_id_for_product_id(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szProductId); strncpy(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName, str_get_radio_card_model_string(_hardware_detect_card_model(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szProductId)), sizeof(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName)/sizeof(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName[0]) ); s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName[sizeof(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName)/sizeof(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName[0]) - 1] = 0; @@ -700,6 +755,13 @@ void _hardware_find_usb_radio_interfaces_info() s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szProductId, s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szName); + int iCardModel = _hardware_detect_card_model(s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szProductId); + if ( iCardModel > 0 ) + { + iCountKnownRadioCards++; + log_line("[HardwareRadio] USB device %s is a known radio interface, type: %s", + s_USB_RadioInterfacesInfo[s_iFoundUSBRadioInterfaces].szProductId, str_get_radio_card_model_string(iCardModel)); + } if ( s_iFoundUSBRadioInterfaces < MAX_USB_DEVICES_INFO-1 ) s_iFoundUSBRadioInterfaces++; else @@ -713,7 +775,8 @@ void _hardware_find_usb_radio_interfaces_info() iPos = iEndLine; } - log_line("[HardwareRadio] Done finding USB devices. Found %d USB devices.", s_iFoundUSBRadioInterfaces); + log_line("[HardwareRadio] Done finding USB devices. Found %d USB devices of which %d are known radio cards.", s_iFoundUSBRadioInterfaces, iCountKnownRadioCards); + return iCountKnownRadioCards; } int _hardware_enumerate_wifi_radios() @@ -967,8 +1030,13 @@ int _hardware_enumerate_wifi_radios() } else { - log_line("phy string: [%s], length: %d", szComm, strlen(szComm)); - sRadioInfo[i].phy_index = szComm[strlen(szComm)-1] - '0'; + int iPhyStrLen = strlen(szComm); + log_line("phy string: [%s], length: %d", szComm, iPhyStrLen); + sRadioInfo[i].phy_index = szComm[iPhyStrLen-1] - '0'; + if ( (iPhyStrLen > 2) && isdigit(szComm[iPhyStrLen-2]) ) + { + sRadioInfo[i].phy_index = 10 * (szComm[iPhyStrLen-2] - '0') + sRadioInfo[i].phy_index; + } } // Check supported bands @@ -1065,7 +1133,7 @@ int hardware_enumerate_radio_interfaces_step(int iStep) if( iStep == -1 || iStep == 1 ) { - hardware_log_radio_info(); + hardware_log_radio_info(&sRadioInfo[0], s_iHwRadiosCount); hardware_save_radio_info(); } s_HardwareRadiosEnumeratedOnce = 1; @@ -1078,7 +1146,7 @@ int hardware_enumerate_radio_interfaces_step(int iStep) // Called only once, from ruby_start process int hardware_radio_load_radio_modules(int iEchoToConsole) { - _hardware_find_usb_radio_interfaces_info(); + int iCountKnownRadios = _hardware_find_usb_radio_interfaces_info(); if ( 0 == s_iFoundUSBRadioInterfaces ) { @@ -1091,6 +1159,17 @@ int hardware_radio_load_radio_modules(int iEchoToConsole) return 0; } + if ( 0 == iCountKnownRadios ) + { + log_softerror_and_alarm("[HardwareRadio] No known USB radio devices found!"); + if ( iEchoToConsole ) + { + printf("Ruby: ERROR: No known USB radio cards found!\n\n"); + fflush(stdout); + } + return 0; + } + #if defined(HW_PLATFORM_RASPBERRY) log_line("[HardwareRadio] Adding radio modules on Raspberry for detected radio cards..."); #endif @@ -1122,24 +1201,12 @@ int hardware_radio_load_radio_modules(int iEchoToConsole) printf("Ruby: Adding radio modules for RTL8812AU radio cards...\n"); fflush(stdout); } - #if defined(HW_PLATFORM_RASPBERRY) - hw_execute_bash_command("sudo modprobe -f 88XXau 2>&1", szOutput); - #endif - - #if defined(HW_PLATFORM_OPENIPC_CAMERA) - hw_execute_bash_command("modprobe 88XXau rtw_tx_pwr_idx_override=40", szOutput); - #endif - - #if defined(HW_PLATFORM_RADXA_ZERO3) - hw_execute_bash_command("sudo modprobe -f 88XXau_wfb", szOutput); - #endif - - if ( (0 != szOutput[0]) && (strlen(szOutput) > 10) ) + if ( 1 != hardware_install_driver_rtl8812au(0) ) { - log_softerror_and_alarm("[HardwareRadio] Error on loading driver RTL8812AU: [%s]", szOutput); + log_softerror_and_alarm("[HardwareRadio] Error on loading driver RTL8812AU"); if ( iEchoToConsole ) { - printf("Ruby: ERROR on loading driver RTL8812AU: [%s]\n", szOutput); + printf("Ruby: ERROR on loading driver RTL8812AU\n"); fflush(stdout); } } @@ -1158,27 +1225,13 @@ int hardware_radio_load_radio_modules(int iEchoToConsole) fflush(stdout); } log_line("[HardwareRadio] Found RTL8812EU card. Loading module..."); - #if defined(HW_PLATFORM_RASPBERRY) - hw_execute_bash_command("sudo modprobe cfg80211", NULL); - hw_execute_bash_command("sudo insmod /lib/modules/$(uname -r)/kernel/drivers/net/wireless/8812eu_pi.ko rtw_tx_pwr_by_rate=0 rtw_tx_pwr_lmt_enable=0", szOutput); - #endif - - #if defined(HW_PLATFORM_RADXA_ZERO3) - hw_execute_bash_command("sudo modprobe cfg80211", NULL); - hw_execute_bash_command("sudo insmod /lib/modules/$(uname -r)/kernel/drivers/net/wireless/8812eu_radxa.ko rtw_tx_pwr_by_rate=0 rtw_tx_pwr_lmt_enable=0 2>&1 1>/dev/null", szOutput); - #endif - - #if defined(HW_PLATFORM_OPENIPC_CAMERA) - hw_execute_bash_command("modprobe cfg80211", NULL); - hw_execute_bash_command("insmod /lib/modules/$(uname -r)/extra/8812eu.ko rtw_tx_pwr_by_rate=0 rtw_tx_pwr_lmt_enable=0 2>&1 1>/dev/null", szOutput); - #endif - if ( (0 != szOutput[0]) && (strlen(szOutput) > 10) ) + if ( 1 != hardware_install_driver_rtl8812eu(0) ) { - log_softerror_and_alarm("[HardwareRadio] Error on loading driver RTL8812EU: [%s]", szOutput); + log_softerror_and_alarm("[HardwareRadio] Error on loading driver RTL8812EU"); if ( iEchoToConsole ) { - printf("Ruby: ERROR on loading driver RTL8812EU: [%s]\n", szOutput); + printf("Ruby: ERROR on loading driver RTL8812EU\n"); fflush(stdout); } } @@ -1213,6 +1266,140 @@ int hardware_radio_load_radio_modules(int iEchoToConsole) return iCountLoaded; } + +int hardware_install_driver_rtl8812au(int iRemoveFirst) +{ + hw_execute_bash_command("sudo modprobe cfg80211", NULL); + char szOutput[1024]; + char szPlatform[256]; + char szDriver[128]; + char szDriverFullPath[MAX_FILE_PATH_SIZE]; + szDriver[0] = 0; + hw_execute_bash_command("uname -r", szPlatform); + + #if defined HW_PLATFORM_RASPBERRY + if ( NULL != strstr(szPlatform, "v7l+") ) + strcpy(szDriver, "88XXau-pi+.ko"); + else + strcpy(szDriver, "88XXau-pi.ko"); + #endif + + #if defined HW_PLATFORM_RADXA_ZERO3 + strcpy(szDriver, "88XXau-radxa.ko"); + #endif + + #if defined HW_PLATFORM_OPENIPC_CAMERA + hw_execute_bash_command("modprobe 88XXau rtw_tx_pwr_idx_override=1", szOutput); + #endif + + if ( 0 != szDriver[0] ) + { + szOutput[0] = 0; + strcpy(szDriverFullPath, FOLDER_BINARIES); + strcat(szDriverFullPath, "drivers/"); + strcat(szDriverFullPath, szDriver); + if ( access(szDriverFullPath, R_OK) != -1 ) + { + if ( iRemoveFirst ) + hw_execute_bash_command("rmmod 88XXau 2>&1 1>/dev/null", NULL); + char szComm[256]; + sprintf(szComm, "insmod %s rtw_tx_pwr_idx_override=1 2>&1", szDriverFullPath); + hw_execute_bash_command_raw(szComm, szOutput); + } + if ( (iRemoveFirst) && (strlen(szOutput) > 10) ) + { + log_softerror_and_alarm("[HardwareRadio] Failed to install driver (%s) on platform (%s), error: (%s)", szDriver, szPlatform, szOutput); + return 0; + } + } + return 1; +} + +int hardware_install_driver_rtl8812eu(int iRemoveFirst) +{ + hw_execute_bash_command("sudo modprobe cfg80211", NULL); + char szOutput[1024]; + char szDriver[128]; + char szPlatform[256]; + char szDriverFullPath[MAX_FILE_PATH_SIZE]; + szDriver[0] = 0; + + hw_execute_bash_command("uname -r", szPlatform); + + #if defined HW_PLATFORM_RASPBERRY + if ( NULL != strstr(szPlatform, "v7l+") ) + strcpy(szDriver, "/home/pi/8812eu-pi+.ko"); + else + strcpy(szDriver, "/home/pi/8812eu-pi.ko"); + #endif + + #if defined HW_PLATFORM_RADXA_ZERO3 + strcpy(szDriver, "8812eu-radxa.ko"); + #endif + + #if defined (HW_PLATFORM_OPENIPC_CAMERA) + hw_execute_bash_command("insmod /lib/modules/$(uname -r)/extra/8812eu.ko rtw_tx_pwr_by_rate=0 rtw_tx_pwr_lmt_enable=0 2>&1 1>/dev/null", szOutput); + #endif + + if ( 0 != szDriver[0] ) + { + szOutput[0] = 0; + strcpy(szDriverFullPath, FOLDER_BINARIES); + strcat(szDriverFullPath, "drivers/"); + strcat(szDriverFullPath, szDriver); + if ( access(szDriver, R_OK) != -1 ) + { + if ( iRemoveFirst ) + hw_execute_bash_command("rmmod 8812eu 2>&1 1>/dev/null", NULL); + char szComm[256]; + sprintf(szComm, "insmod %s rtw_tx_pwr_by_rate=0 rtw_tx_pwr_lmt_enable=0 2>&1", szDriverFullPath); + hw_execute_bash_command_raw(szComm, szOutput); + } + if ( iRemoveFirst && (strlen(szOutput) > 10) ) + { + log_softerror_and_alarm("[HardwareRadio] Failed to install driver (%s) on platform (%s), error: (%s)", szDriver, szPlatform, szOutput); + return 0; + } + } + return 1; +} + +void hardware_install_drivers() +{ + log_line("[Hardware] Installing drivers..."); + + hardware_install_driver_rtl8812au(1); + hardware_install_driver_rtl8812eu(1); + + #if defined HW_PLATFORM_RASPBERRY + + hw_execute_bash_command("depmod -a", NULL); + hw_execute_bash_command("lsusb", NULL); + //hw_execute_bash_command("sudo modprobe -f 88XXau 2>&1 1>/dev/null", NULL); + //hw_execute_bash_command("sudo modprobe -f 8812eu 2>&1 1>/dev/null", NULL); + hw_execute_bash_command("lsusb", NULL); + hw_execute_bash_command("lsmod", NULL); + hw_execute_bash_command("ip link", NULL); + hw_execute_bash_command("sync", NULL); + + #endif + + #if defined HW_PLATFORM_RADXA_ZERO3 + + hw_execute_bash_command("depmod -a", NULL); + hw_execute_bash_command("lsusb", NULL); + hw_execute_bash_command("sudo modprobe -r aic8800_fdrv 2>&1 1>/dev/null", NULL); + hw_execute_bash_command("sudo modprobe -r aic8800_bsp 2>&1 1>/dev/null", NULL); + hw_execute_bash_command("lsusb", NULL); + hw_execute_bash_command("lsmod", NULL); + hw_execute_bash_command("ip link", NULL); + hw_execute_bash_command("sync", NULL); + + #endif + + log_line("[Hardware] Done installing drivers."); +} + int hardware_get_radio_interfaces_count() { if ( ! s_HardwareRadiosEnumeratedOnce ) @@ -1312,11 +1499,7 @@ int hardware_radio_has_rtl8812au_cards() { for( int i=0; i 0 ) { hardware_save_radio_info(); - hardware_log_radio_info(); + hardware_log_radio_info(NULL, 0); } return iCountAdded; } diff --git a/code/base/hardware_radio_txpower.c b/code/base/hardware_radio_txpower.c index d15b8ae5..9d55d357 100644 --- a/code/base/hardware_radio_txpower.c +++ b/code/base/hardware_radio_txpower.c @@ -4,83 +4,36 @@ #include "hardware_radio.h" #include "hw_procs.h" -void hardware_radio_set_txpower_rtl8812au(int iTxPower) +void hardware_radio_set_txpower_raw_rtl8812au(int iCardIndex, int iTxPower) { - log_line("Setting RTL8812AU TX Power to: %d", iTxPower); + log_line("Setting radio interface %d RTL8812AU raw tx power to %d using iw dev...", iCardIndex+1, iTxPower); if ( (iTxPower < 1) || (iTxPower > MAX_TX_POWER) ) iTxPower = DEFAULT_RADIO_TX_POWER; - #ifdef HW_PLATFORM_RASPBERRY - - int iHasOrgFile = 0; - if ( access( "/etc/modprobe.d/rtl8812au.conf.org", R_OK ) != -1 ) - iHasOrgFile = 1; - if ( iHasOrgFile ) - { - FILE *pF = fopen("/etc/modprobe.d/rtl8812au.conf.org", "rb"); - if ( NULL == pF ) - iHasOrgFile = 0; - else - { - fseek(pF, 0, SEEK_END); - long fsize = ftell(pF); - fclose(pF); - if ( fsize < 20 || fsize > 512 ) - iHasOrgFile = 0; - } - } - - char szBuff[256]; - szBuff[0] = 0; - if ( iHasOrgFile ) - sprintf(szBuff, "cp /etc/modprobe.d/rtl8812au.conf.org tmp/rtl8812au.conf; sed -i 's/rtw_tx_pwr_idx_override=[0-9]*/rtw_tx_pwr_idx_override=%d/g' tmp/rtl8812au.conf; cp tmp/rtl8812au.conf /etc/modprobe.d/", iTxPower); - else if ( access( "/etc/modprobe.d/rtl8812au.conf", R_OK ) != -1 ) - sprintf(szBuff, "cp /etc/modprobe.d/rtl8812au.conf tmp/rtl8812au.conf; sed -i 's/rtw_tx_pwr_idx_override=[0-9]*/rtw_tx_pwr_idx_override=%d/g' tmp/rtl8812au.conf; cp tmp/rtl8812au.conf /etc/modprobe.d/", iTxPower); - else - log_softerror_and_alarm("Can't access/find RTL power config files."); - - if ( 0 != szBuff[0] ) - hw_execute_bash_command(szBuff, NULL); - - szBuff[0] = 0; - if ( iHasOrgFile ) - sprintf(szBuff, "cp /etc/modprobe.d/rtl88XXau.conf.org tmp/rtl88XXau.conf; sed -i 's/rtw_tx_pwr_idx_override=[0-9]*/rtw_tx_pwr_idx_override=%d/g' tmp/rtl88XXau.conf; cp tmp/rtl88XXau.conf /etc/modprobe.d/", iTxPower); - else if ( access( "/etc/modprobe.d/rtl88XXau.conf", R_OK ) != -1 ) - sprintf(szBuff, "cp /etc/modprobe.d/rtl88XXau.conf tmp/rtl88XXau.conf; sed -i 's/rtw_tx_pwr_idx_override=[0-9]*/rtw_tx_pwr_idx_override=%d/g' tmp/rtl88XXau.conf; cp tmp/rtl88XXau.conf /etc/modprobe.d/", iTxPower); - else - log_softerror_and_alarm("Can't access/find RTL-XX power config files."); - - if ( 0 != szBuff[0] ) - hw_execute_bash_command(szBuff, NULL); - #endif - - #if defined(HW_PLATFORM_OPENIPC_CAMERA) || defined(HW_PLATFORM_RADXA_ZERO3) - - log_line("Set tx power now using iw dev..."); char szComm[256]; for( int i=0; iiRadioDriver == RADIO_HW_DRIVER_REALTEK_RTL88XXAU) || - (pRadioHWInfo->iRadioDriver == RADIO_HW_DRIVER_REALTEK_RTL8812AU) || - (pRadioHWInfo->iRadioDriver == RADIO_HW_DRIVER_REALTEK_8812AU) || - (pRadioHWInfo->iRadioDriver == RADIO_HW_DRIVER_REALTEK_RTL88X2BU) || - (pRadioHWInfo->iRadioDriver == RADIO_HW_DRIVER_MEDIATEK) ) + if ( (hardware_radio_driver_is_rtl8812au_card(pRadioHWInfo->iRadioDriver)) || + (pRadioHWInfo->iRadioType == RADIO_TYPE_REALTEK) || + (pRadioHWInfo->iRadioType == RADIO_TYPE_RALINK) ) { sprintf(szComm, "iw dev %s set txpower fixed %d", pRadioHWInfo->szName, -100*iTxPower); hw_execute_bash_command(szComm, NULL); } } - #endif - log_line("RTL8812AU TX Power changed to: %d", iTxPower); + log_line("Radio interface %d RTL8812AU raw tx power changed to: %d", iCardIndex+1, iTxPower); } -void hardware_radio_set_txpower_rtl8812eu(int iTxPower) +void hardware_radio_set_txpower_raw_rtl8812eu(int iCardIndex, int iTxPower) { - log_line("Setting RTL8812EU TX Power to: %d", iTxPower); + log_line("Setting radio interface %d RTL8812EU raw tx power to: %d", iCardIndex+1, iTxPower); if ( (iTxPower < 1) || (iTxPower > MAX_TX_POWER) ) iTxPower = DEFAULT_RADIO_TX_POWER; @@ -88,22 +41,24 @@ void hardware_radio_set_txpower_rtl8812eu(int iTxPower) char szComm[256]; for( int i=0; iiRadioDriver == RADIO_HW_DRIVER_REALTEK_8812EU ) + if ( hardware_radio_driver_is_rtl8812eu_card(pRadioHWInfo->iRadioDriver) ) { sprintf(szComm, "iw dev %s set txpower fixed %d", pRadioHWInfo->szName, iTxPower*40); hw_execute_bash_command(szComm, NULL); } } - log_line("RTL8812EU TX Power changed to: %d", iTxPower); + log_line("Radio interface %d RTL8812EU raw tx power changed to: %d", iCardIndex+1, iTxPower); } -void hardware_radio_set_txpower_atheros(int iTxPower) +void hardware_radio_set_txpower_raw_atheros(int iCardIndex, int iTxPower) { - log_line("Setting Atheros TX Power to: %d", iTxPower); + log_line("Setting radio interface %d Atheros raw tx power to: %d", iCardIndex+1, iTxPower); if ( (iTxPower < 1) || (iTxPower > MAX_TX_POWER) ) iTxPower = DEFAULT_RADIO_TX_POWER; @@ -148,5 +103,6 @@ void hardware_radio_set_txpower_atheros(int iTxPower) hw_execute_bash_command(szBuff, NULL); } #endif - log_line("Atheros TX Power changed to: %d", iTxPower); + log_line("Radio interface %d Atheros raw tx power changed to: %d", iCardIndex+1, iTxPower); } + diff --git a/code/base/hardware_radio_txpower.h b/code/base/hardware_radio_txpower.h index c9aa30c9..da4dd53e 100644 --- a/code/base/hardware_radio_txpower.h +++ b/code/base/hardware_radio_txpower.h @@ -5,9 +5,9 @@ extern "C" { #endif // Power is 0..71 -void hardware_radio_set_txpower_rtl8812au(int iTxPower); -void hardware_radio_set_txpower_rtl8812eu(int iTxPower); -void hardware_radio_set_txpower_atheros(int iTxPower); +void hardware_radio_set_txpower_raw_rtl8812au(int iCardIndex, int iTxPower); +void hardware_radio_set_txpower_raw_rtl8812eu(int iCardIndex, int iTxPower); +void hardware_radio_set_txpower_raw_atheros(int iCardIndex, int iTxPower); #ifdef __cplusplus } diff --git a/code/base/hardware_serial.c b/code/base/hardware_serial.c index 72dac289..2bfe84dd 100644 --- a/code/base/hardware_serial.c +++ b/code/base/hardware_serial.c @@ -81,22 +81,28 @@ void _hardware_enumerate_serial_ports() strcpy(s_HardwareSerialPortsInfo[0].szName, "Serial-0"); strcpy(s_HardwareSerialPortsInfo[0].szPortDeviceName, "/dev/ttyAMA0"); - if ( (hardware_getOnlyBoardType() & BOARD_TYPE_MASK) == BOARD_TYPE_OPENIPC_SIGMASTER_338Q ) + if ( (hardware_getOnlyBoardType() & BOARD_TYPE_MASK) == BOARD_TYPE_OPENIPC_SIGMASTAR_338Q ) strcpy(s_HardwareSerialPortsInfo[0].szPortDeviceName, "/dev/ttyS0"); s_HardwareSerialPortsInfo[0].iSupported = 1; s_HardwareSerialPortsInfo[0].lPortSpeed = DEFAULT_FC_TELEMETRY_SERIAL_SPEED; s_HardwareSerialPortsInfo[0].iPortUsage = SERIAL_PORT_USAGE_NONE; s_iCountHardwareSerialPorts = 1; - if ( (hardware_getOnlyBoardType() & BOARD_TYPE_MASK) == BOARD_TYPE_OPENIPC_SIGMASTER_338Q ) + //if ( (hardware_getOnlyBoardType() & BOARD_TYPE_MASK) == BOARD_TYPE_OPENIPC_SIGMASTAR_338Q ) { - strcpy(s_HardwareSerialPortsInfo[1].szName, "Serial-2"); - strcpy(s_HardwareSerialPortsInfo[1].szPortDeviceName, "/dev/ttyS2"); - s_HardwareSerialPortsInfo[1].iSupported = 1; - s_HardwareSerialPortsInfo[1].lPortSpeed = DEFAULT_FC_TELEMETRY_SERIAL_SPEED; - s_HardwareSerialPortsInfo[1].iPortUsage = SERIAL_PORT_USAGE_NONE; - s_iCountHardwareSerialPorts = 2; - } + for( int i=1; i<5; i++ ) + { + sprintf(s_HardwareSerialPortsInfo[s_iCountHardwareSerialPorts].szPortDeviceName, "/dev/ttyS%d", i); + if ( access(s_HardwareSerialPortsInfo[s_iCountHardwareSerialPorts].szPortDeviceName, R_OK) != -1 ) + { + sprintf(s_HardwareSerialPortsInfo[s_iCountHardwareSerialPorts].szName, "Serial-%d", i); + s_HardwareSerialPortsInfo[s_iCountHardwareSerialPorts].iSupported = 1; + s_HardwareSerialPortsInfo[s_iCountHardwareSerialPorts].lPortSpeed = DEFAULT_FC_TELEMETRY_SERIAL_SPEED; + s_HardwareSerialPortsInfo[s_iCountHardwareSerialPorts].iPortUsage = SERIAL_PORT_USAGE_NONE; + s_iCountHardwareSerialPorts++; + } + } + } #endif for( int i=0; i 16 ) + { video_params.iH264Slices = DEFAULT_VIDEO_H264_SLICES; - + if ( hardware_board_is_openipc(hardware_getOnlyBoardType()) ) + video_params.iH264Slices = DEFAULT_VIDEO_H264_SLICES_OIPC; + } video_params.videoAdjustmentStrength = tmp2; if ( video_params.lowestAllowedAdaptiveVideoBitrate < 250000 ) video_params.lowestAllowedAdaptiveVideoBitrate = DEFAULT_LOWEST_ALLOWED_ADAPTIVE_VIDEO_BITRATE; @@ -580,9 +584,8 @@ bool Model::loadVersion8(FILE* fd) if ( bOk && (5 != fscanf(fd, "%d %d %d %d %d", &(video_link_profiles[i].block_packets), &(video_link_profiles[i].block_fecs), &(video_link_profiles[i].video_data_length), &(video_link_profiles[i].fps), &(video_link_profiles[i].keyframe_ms))) ) { log_softerror_and_alarm("Load model8: Error on video link profiles 3"); bOk = false; } - if ( bOk && (5 != fscanf(fd, "%d %d %d %d %d", &(video_link_profiles[i].h264profile), &(video_link_profiles[i].h264level), &(video_link_profiles[i].h264refresh), &(video_link_profiles[i].h264quantization), &tmp1)) ) + if ( bOk && (5 != fscanf(fd, "%d %d %d %d %d", &(video_link_profiles[i].h264profile), &(video_link_profiles[i].h264level), &(video_link_profiles[i].h264refresh), &(video_link_profiles[i].h264quantization), &(video_link_profiles[i].iIPQuantizationDelta))) ) { log_softerror_and_alarm("Load model8: Error on video link profiles 4"); bOk = false; } - video_link_profiles[i].insertPPS = (tmp1!=0)?1:0; } @@ -702,13 +705,13 @@ bool Model::loadVersion8(FILE* fd) //---------------------------------------- // Hardware info - if ( 4 == fscanf(fd, "%*s %d %d %d %d", &hardwareInterfacesInfo.radio_interface_count, &hardwareInterfacesInfo.i2c_bus_count, &hardwareInterfacesInfo.i2c_device_count, &hardwareInterfacesInfo.serial_bus_count) ) + if ( 4 == fscanf(fd, "%*s %d %d %d %d", &hardwareInterfacesInfo.radio_interface_count, &hardwareInterfacesInfo.i2c_bus_count, &hardwareInterfacesInfo.i2c_device_count, &hardwareInterfacesInfo.serial_port_count) ) { if ( hardwareInterfacesInfo.i2c_bus_count < 0 || hardwareInterfacesInfo.i2c_bus_count > MAX_MODEL_I2C_BUSSES ) { log_softerror_and_alarm("Load model8: Error on hw info1"); return false; } if ( hardwareInterfacesInfo.i2c_device_count < 0 || hardwareInterfacesInfo.i2c_device_count > MAX_MODEL_I2C_DEVICES ) { log_softerror_and_alarm("Load model8: Error on hw info2"); return false; } - if ( hardwareInterfacesInfo.serial_bus_count < 0 || hardwareInterfacesInfo.serial_bus_count > MAX_MODEL_SERIAL_BUSSES ) + if ( hardwareInterfacesInfo.serial_port_count < 0 || hardwareInterfacesInfo.serial_port_count > MAX_MODEL_SERIAL_PORTS ) { log_softerror_and_alarm("Load model8: Error on hw info3"); return false; } for( int i=0; i= RXTX_SYNC_TYPE_LAST ) - rxtx_sync_type = RXTX_SYNC_TYPE_NONE; + rxtx_sync_type = RXTX_SYNC_TYPE_BASIC; validate_settings(); @@ -1063,20 +1065,20 @@ bool Model::loadVersion9(FILE* fd) radioInterfacesParams.interface_supported_bands[i] = (u8)tmp2; radioInterfacesParams.interface_radiotype_and_driver[i] = tmp32; radioInterfacesParams.interface_current_radio_flags[i] = tmp5; + radioInterfacesParams.interface_raw_power[i] = tmp6; radioInterfacesParams.interface_szMAC[i][strlen(radioInterfacesParams.interface_szMAC[i])-1] = 0; szTmp[strlen(szTmp)-1] = 0; szTmp[2] = 0; strcpy(radioInterfacesParams.interface_szPort[i], szTmp); } - if ( 9 != fscanf(fd, "%d %d %d %d %d %d %d %d %d", &tmp1, &radioInterfacesParams.txPowerRTL8812AU, &radioInterfacesParams.txPowerRTL8812EU, &radioInterfacesParams.txPowerAtheros, &radioInterfacesParams.txMaxPowerRTL8812AU, &radioInterfacesParams.txMaxPowerRTL8812EU, &radioInterfacesParams.txMaxPowerAtheros, &radioInterfacesParams.slotTime, &radioInterfacesParams.thresh62) ) + if ( 9 != fscanf(fd, "%d %d %d %d %d %d %d %d %d", &tmp1, &radioInterfacesParams.iAutoVehicleTxPower, &radioInterfacesParams.iAutoControllerTxPower, &radioInterfacesParams.iDummyR3, &radioInterfacesParams.iDummyR4, &radioInterfacesParams.iDummyR5, &radioInterfacesParams.iDummyR6, &radioInterfacesParams.iDummyR7, &radioInterfacesParams.iDummyR8) ) { log_softerror_and_alarm("Load model8: Error on line 8"); return false; } enableDHCP = (bool)tmp1; - if ( 1 != fscanf(fd, "%d", &radioInterfacesParams.txPowerSiK) ) + if ( 1 != fscanf(fd, "%d", &radioInterfacesParams.iDummyR9) ) { - log_softerror_and_alarm("Failed to read SiK params from model config file."); - radioInterfacesParams.txPowerSiK = DEFAULT_RADIO_SIK_TX_POWER; + radioInterfacesParams.iDummyR9 = 0; } if ( 1 != fscanf(fd, "%*s %d", &radioLinksParams.links_count) ) @@ -1138,8 +1140,11 @@ bool Model::loadVersion9(FILE* fd) { log_softerror_and_alarm("Load model8: Error on line 19"); return false; } if ( video_params.iH264Slices < 1 || video_params.iH264Slices > 16 ) + { video_params.iH264Slices = DEFAULT_VIDEO_H264_SLICES; - + if ( hardware_board_is_openipc(hardware_getOnlyBoardType()) ) + video_params.iH264Slices = DEFAULT_VIDEO_H264_SLICES_OIPC; + } video_params.videoAdjustmentStrength = tmp2; if ( video_params.lowestAllowedAdaptiveVideoBitrate < 250000 ) video_params.lowestAllowedAdaptiveVideoBitrate = DEFAULT_LOWEST_ALLOWED_ADAPTIVE_VIDEO_BITRATE; @@ -1182,9 +1187,8 @@ bool Model::loadVersion9(FILE* fd) if ( bOk && (5 != fscanf(fd, "%d %d %d %d %d", &(video_link_profiles[i].block_packets), &(video_link_profiles[i].block_fecs), &(video_link_profiles[i].video_data_length), &(video_link_profiles[i].fps), &(video_link_profiles[i].keyframe_ms))) ) { log_softerror_and_alarm("Load model8: Error on video link profiles 3"); bOk = false; } - if ( bOk && (5 != fscanf(fd, "%d %d %d %d %d", &(video_link_profiles[i].h264profile), &(video_link_profiles[i].h264level), &(video_link_profiles[i].h264refresh), &(video_link_profiles[i].h264quantization), &tmp1)) ) + if ( bOk && (5 != fscanf(fd, "%d %d %d %d %d", &(video_link_profiles[i].h264profile), &(video_link_profiles[i].h264level), &(video_link_profiles[i].h264refresh), &(video_link_profiles[i].h264quantization), &(video_link_profiles[i].iIPQuantizationDelta))) ) { log_softerror_and_alarm("Load model8: Error on video link profiles 4"); bOk = false; } - video_link_profiles[i].insertPPS = (tmp1!=0)?1:0; } @@ -1305,13 +1309,13 @@ bool Model::loadVersion9(FILE* fd) //---------------------------------------- // Hardware info - if ( 4 == fscanf(fd, "%*s %d %d %d %d", &hardwareInterfacesInfo.radio_interface_count, &hardwareInterfacesInfo.i2c_bus_count, &hardwareInterfacesInfo.i2c_device_count, &hardwareInterfacesInfo.serial_bus_count) ) + if ( 4 == fscanf(fd, "%*s %d %d %d %d", &hardwareInterfacesInfo.radio_interface_count, &hardwareInterfacesInfo.i2c_bus_count, &hardwareInterfacesInfo.i2c_device_count, &hardwareInterfacesInfo.serial_port_count) ) { if ( hardwareInterfacesInfo.i2c_bus_count < 0 || hardwareInterfacesInfo.i2c_bus_count > MAX_MODEL_I2C_BUSSES ) { log_softerror_and_alarm("Load model8: Error on hw info1"); return false; } if ( hardwareInterfacesInfo.i2c_device_count < 0 || hardwareInterfacesInfo.i2c_device_count > MAX_MODEL_I2C_DEVICES ) { log_softerror_and_alarm("Load model8: Error on hw info2"); return false; } - if ( hardwareInterfacesInfo.serial_bus_count < 0 || hardwareInterfacesInfo.serial_bus_count > MAX_MODEL_SERIAL_BUSSES ) + if ( hardwareInterfacesInfo.serial_port_count < 0 || hardwareInterfacesInfo.serial_port_count > MAX_MODEL_SERIAL_PORTS ) { log_softerror_and_alarm("Load model8: Error on hw info3"); return false; } for( int i=0; i= RXTX_SYNC_TYPE_LAST ) - rxtx_sync_type = RXTX_SYNC_TYPE_NONE; + rxtx_sync_type = RXTX_SYNC_TYPE_BASIC; validate_settings(); @@ -1638,20 +1642,20 @@ bool Model::loadVersion10(FILE* fd) radioInterfacesParams.interface_supported_bands[i] = (u8)tmp2; radioInterfacesParams.interface_radiotype_and_driver[i] = tmp32; radioInterfacesParams.interface_current_radio_flags[i] = tmp5; + radioInterfacesParams.interface_raw_power[i] = tmp6; radioInterfacesParams.interface_szMAC[i][strlen(radioInterfacesParams.interface_szMAC[i])-1] = 0; szTmp[strlen(szTmp)-1] = 0; szTmp[2] = 0; strcpy(radioInterfacesParams.interface_szPort[i], szTmp); } - if ( 9 != fscanf(fd, "%d %d %d %d %d %d %d %d %d", &tmp1, &radioInterfacesParams.txPowerRTL8812AU, &radioInterfacesParams.txPowerRTL8812EU, &radioInterfacesParams.txPowerAtheros, &radioInterfacesParams.txMaxPowerRTL8812AU, &radioInterfacesParams.txMaxPowerRTL8812EU, &radioInterfacesParams.txMaxPowerAtheros, &radioInterfacesParams.slotTime, &radioInterfacesParams.thresh62) ) + if ( 9 != fscanf(fd, "%d %d %d %d %d %d %d %d %d", &tmp1, &radioInterfacesParams.iAutoVehicleTxPower, &radioInterfacesParams.iAutoControllerTxPower, &radioInterfacesParams.iDummyR3, &radioInterfacesParams.iDummyR4, &radioInterfacesParams.iDummyR5, &radioInterfacesParams.iDummyR6, &radioInterfacesParams.iDummyR7, &radioInterfacesParams.iDummyR8) ) { log_softerror_and_alarm("Load model8: Error on line 8"); return false; } enableDHCP = (bool)tmp1; - if ( 1 != fscanf(fd, "%d", &radioInterfacesParams.txPowerSiK) ) + if ( 1 != fscanf(fd, "%d", &radioInterfacesParams.iDummyR9) ) { - log_softerror_and_alarm("Failed to read SiK params from model config file."); - radioInterfacesParams.txPowerSiK = DEFAULT_RADIO_SIK_TX_POWER; + radioInterfacesParams.iDummyR9 = 0; } if ( 1 != fscanf(fd, "%*s %d", &radioLinksParams.links_count) ) @@ -1728,8 +1732,11 @@ bool Model::loadVersion10(FILE* fd) { log_softerror_and_alarm("Load model8: Error on line 19"); return false; } if ( video_params.iH264Slices < 1 || video_params.iH264Slices > 16 ) + { video_params.iH264Slices = DEFAULT_VIDEO_H264_SLICES; - + if ( hardware_board_is_openipc(hardware_getOnlyBoardType()) ) + video_params.iH264Slices = DEFAULT_VIDEO_H264_SLICES_OIPC; + } video_params.videoAdjustmentStrength = tmp2; if ( video_params.lowestAllowedAdaptiveVideoBitrate < 250000 ) video_params.lowestAllowedAdaptiveVideoBitrate = DEFAULT_LOWEST_ALLOWED_ADAPTIVE_VIDEO_BITRATE; @@ -1772,9 +1779,8 @@ bool Model::loadVersion10(FILE* fd) if ( bOk && (5 != fscanf(fd, "%d %d %d %d %d", &(video_link_profiles[i].block_packets), &(video_link_profiles[i].block_fecs), &(video_link_profiles[i].video_data_length), &(video_link_profiles[i].fps), &(video_link_profiles[i].keyframe_ms))) ) { log_softerror_and_alarm("Load model8: Error on video link profiles 3"); bOk = false; } - if ( bOk && (5 != fscanf(fd, "%d %d %d %d %d", &(video_link_profiles[i].h264profile), &(video_link_profiles[i].h264level), &(video_link_profiles[i].h264refresh), &(video_link_profiles[i].h264quantization), &tmp1)) ) + if ( bOk && (5 != fscanf(fd, "%d %d %d %d %d", &(video_link_profiles[i].h264profile), &(video_link_profiles[i].h264level), &(video_link_profiles[i].h264refresh), &(video_link_profiles[i].h264quantization), &(video_link_profiles[i].iIPQuantizationDelta))) ) { log_softerror_and_alarm("Load model8: Error on video link profiles 4"); bOk = false; } - video_link_profiles[i].insertPPS = (tmp1!=0)?1:0; } @@ -1895,13 +1901,13 @@ bool Model::loadVersion10(FILE* fd) //---------------------------------------- // Hardware info - if ( 4 == fscanf(fd, "%*s %d %d %d %d", &hardwareInterfacesInfo.radio_interface_count, &hardwareInterfacesInfo.i2c_bus_count, &hardwareInterfacesInfo.i2c_device_count, &hardwareInterfacesInfo.serial_bus_count) ) + if ( 4 == fscanf(fd, "%*s %d %d %d %d", &hardwareInterfacesInfo.radio_interface_count, &hardwareInterfacesInfo.i2c_bus_count, &hardwareInterfacesInfo.i2c_device_count, &hardwareInterfacesInfo.serial_port_count) ) { if ( hardwareInterfacesInfo.i2c_bus_count < 0 || hardwareInterfacesInfo.i2c_bus_count > MAX_MODEL_I2C_BUSSES ) { log_softerror_and_alarm("Load model8: Error on hw info1"); return false; } if ( hardwareInterfacesInfo.i2c_device_count < 0 || hardwareInterfacesInfo.i2c_device_count > MAX_MODEL_I2C_DEVICES ) { log_softerror_and_alarm("Load model8: Error on hw info2"); return false; } - if ( hardwareInterfacesInfo.serial_bus_count < 0 || hardwareInterfacesInfo.serial_bus_count > MAX_MODEL_SERIAL_BUSSES ) + if ( hardwareInterfacesInfo.serial_port_count < 0 || hardwareInterfacesInfo.serial_port_count > MAX_MODEL_SERIAL_PORTS ) { log_softerror_and_alarm("Load model8: Error on hw info3"); return false; } for( int i=0; i= RXTX_SYNC_TYPE_LAST ) - rxtx_sync_type = RXTX_SYNC_TYPE_NONE; + rxtx_sync_type = RXTX_SYNC_TYPE_BASIC; validate_settings(); @@ -2325,13 +2342,13 @@ bool Model::saveVersion10(FILE* fd, bool isOnController) { sprintf(szSetting, "%d %d %u\n", radioInterfacesParams.interface_card_model[i], radioInterfacesParams.interface_link_id[i], radioInterfacesParams.interface_current_frequency_khz[i]); strcat(szModel, szSetting); - sprintf(szSetting, " %u %d %u %d %d %d %s- %s-\n", radioInterfacesParams.interface_capabilities_flags[i], radioInterfacesParams.interface_supported_bands[i], radioInterfacesParams.interface_radiotype_and_driver[i], radioInterfacesParams.interface_current_radio_flags[i], radioInterfacesParams.interface_dummy1[i], radioInterfacesParams.interface_dummy2[i], radioInterfacesParams.interface_szMAC[i], radioInterfacesParams.interface_szPort[i]); + sprintf(szSetting, " %u %d %u %d %d %d %s- %s-\n", radioInterfacesParams.interface_capabilities_flags[i], radioInterfacesParams.interface_supported_bands[i], radioInterfacesParams.interface_radiotype_and_driver[i], radioInterfacesParams.interface_current_radio_flags[i], radioInterfacesParams.interface_raw_power[i], radioInterfacesParams.interface_dummy2[i], radioInterfacesParams.interface_szMAC[i], radioInterfacesParams.interface_szPort[i]); strcat(szModel, szSetting); } - sprintf(szSetting, "%d %d %d %d %d %d %d %d %d\n", enableDHCP, radioInterfacesParams.txPowerRTL8812AU, radioInterfacesParams.txPowerRTL8812EU, radioInterfacesParams.txPowerAtheros, radioInterfacesParams.txMaxPowerRTL8812AU, radioInterfacesParams.txMaxPowerRTL8812EU, radioInterfacesParams.txMaxPowerAtheros, radioInterfacesParams.slotTime, radioInterfacesParams.thresh62); + sprintf(szSetting, "%d %d %d %d %d %d %d %d %d\n", enableDHCP, radioInterfacesParams.iAutoVehicleTxPower, radioInterfacesParams.iAutoControllerTxPower, radioInterfacesParams.iDummyR3, radioInterfacesParams.iDummyR4, radioInterfacesParams.iDummyR5, radioInterfacesParams.iDummyR6, radioInterfacesParams.iDummyR7, radioInterfacesParams.iDummyR8); strcat(szModel, szSetting); - sprintf(szSetting, "%d\n", radioInterfacesParams.txPowerSiK); + sprintf(szSetting, "%d\n", radioInterfacesParams.iDummyR9); strcat(szModel, szSetting); sprintf(szSetting, "radio_links: %d\n", radioLinksParams.links_count); @@ -2410,7 +2427,7 @@ bool Model::saveVersion10(FILE* fd, bool isOnController) strcat(szModel, szSetting); sprintf(szSetting, " %d %d %d %d %d ", video_link_profiles[i].block_packets, video_link_profiles[i].block_fecs, video_link_profiles[i].video_data_length, video_link_profiles[i].fps, video_link_profiles[i].keyframe_ms); strcat(szModel, szSetting); - sprintf(szSetting, "%d %d %d %d %d\n", video_link_profiles[i].h264profile, video_link_profiles[i].h264level, video_link_profiles[i].h264refresh, video_link_profiles[i].h264quantization, video_link_profiles[i].insertPPS); + sprintf(szSetting, "%d %d %d %d %d\n", video_link_profiles[i].h264profile, video_link_profiles[i].h264level, video_link_profiles[i].h264refresh, video_link_profiles[i].h264quantization, video_link_profiles[i].iIPQuantizationDelta); strcat(szModel, szSetting); } @@ -2488,7 +2505,7 @@ bool Model::saveVersion10(FILE* fd, bool isOnController) //---------------------------------------- // Hardware Info - sprintf(szSetting, "hw_info: %d %d %d %d\n", hardwareInterfacesInfo.radio_interface_count, hardwareInterfacesInfo.i2c_bus_count, hardwareInterfacesInfo.i2c_device_count, hardwareInterfacesInfo.serial_bus_count); + sprintf(szSetting, "hw_info: %d %d %d %d\n", hardwareInterfacesInfo.radio_interface_count, hardwareInterfacesInfo.i2c_bus_count, hardwareInterfacesInfo.i2c_device_count, hardwareInterfacesInfo.serial_port_count); strcat(szModel, szSetting); for( int i=0; iszName); - hardwareInterfacesInfo.serial_bus_speed[i] = pInfo->lPortSpeed; + strcpy(hardwareInterfacesInfo.serial_port_names[i], pInfo->szName); + hardwareInterfacesInfo.serial_port_speed[i] = pInfo->lPortSpeed; int iIndex = atoi(&(pInfo->szName[strlen(pInfo->szName)-1])); u32 uPortFlags = (((u32)iIndex) & 0x0F) << 8; @@ -2967,19 +3004,19 @@ bool Model::populateVehicleSerialPorts() if ( (NULL != strstr(pInfo->szName, "USB")) || (NULL != strstr(pInfo->szPortDeviceName, "USB")) ) uPortFlags |= MODEL_SERIAL_PORT_BIT_EXTRNAL_USB; - hardwareInterfacesInfo.serial_bus_supported_and_usage[i] = (((u32)(pInfo->iPortUsage)) & 0xFF) | uPortFlags; + hardwareInterfacesInfo.serial_port_supported_and_usage[i] = (((u32)(pInfo->iPortUsage)) & 0xFF) | uPortFlags; } - log_line("Model: Populated %d serial ports:", hardwareInterfacesInfo.serial_bus_count); - for( int i=0; isupportedBands, szBands); + log_line("Add hardware radio interface %d: name: (%s), driver: (%s), model: (%s), high capacity: %s, supported bands: %s", + i+1, pRadioHWInfo->szName, pRadioHWInfo->szDriver, str_get_radio_card_model_string(pRadioHWInfo->iCardModel), + pRadioHWInfo->isHighCapacityInterface?"yes":"no", szBands); if ( pRadioHWInfo->isHighCapacityInterface ) radioInterfacesParams.interface_capabilities_flags[i] |= RADIO_HW_CAPABILITY_FLAG_HIGH_CAPACITY; else @@ -3269,7 +3312,6 @@ void Model::populateDefaultRadioLinksInfoFromRadioInterfaces() if ( radioInterfacesParams.interface_link_id[i] >= 0 && radioInterfacesParams.interface_link_id[i] < radioLinksParams.links_count ) { radioInterfacesParams.interface_current_radio_flags[i] = radioLinksParams.link_radio_flags[radioInterfacesParams.interface_link_id[i]]; - radioInterfacesParams.interface_dummy1[i] = 0; radioInterfacesParams.interface_dummy2[i] = 0; } } @@ -3481,15 +3523,18 @@ void Model::logVehicleRadioInfo() strcpy(szPrefix, "Relay "); radio_hw_info_t* pRadioInfo = hardware_get_radio_info(i); if ( (NULL != pRadioInfo) && (0 == strcmp(pRadioInfo->szMAC, radioInterfacesParams.interface_szMAC[i]) ) ) - log_line("* %sRadio Interface %d: %s, %s, %s on port %s, %s, supported bands: %s, current frequency: %s, assigned to radio link %d, current capabilities: %s, current radio flags: %s", - szPrefix, i+1, pRadioInfo->szName, radioInterfacesParams.interface_szMAC[i], str_get_radio_card_model_string(radioInterfacesParams.interface_card_model[i]), radioInterfacesParams.interface_szPort[i], str_get_radio_driver_description(radioInterfacesParams.interface_radiotype_and_driver[i]), szBands, str_format_frequency(pRadioInfo->uCurrentFrequencyKhz), radioInterfacesParams.interface_link_id[i]+1, szBuff, szBuff2); + log_line("* %sRadio Interface %d: %s, %s, %s on port %s, %s, supported bands: %s, current frequency: %s, assigned to radio link %d, current capabilities: %s, current radio flags: %s, raw_tx_power: %d", + szPrefix, i+1, pRadioInfo->szName, radioInterfacesParams.interface_szMAC[i], str_get_radio_card_model_string(radioInterfacesParams.interface_card_model[i]), radioInterfacesParams.interface_szPort[i], str_get_radio_driver_description(radioInterfacesParams.interface_radiotype_and_driver[i]), szBands, str_format_frequency(pRadioInfo->uCurrentFrequencyKhz), radioInterfacesParams.interface_link_id[i]+1, szBuff, szBuff2, + radioInterfacesParams.interface_raw_power[i]); else - log_line("* %sRadio Interface %d: %s on port %s, %s, supported bands: %s, current frequency: %s, assigned to radio link %d, current capabilities: %s, current radio flags: %s", - szPrefix, i+1, str_get_radio_card_model_string(radioInterfacesParams.interface_card_model[i]), radioInterfacesParams.interface_szPort[i], str_get_radio_driver_description(radioInterfacesParams.interface_radiotype_and_driver[i]), szBands, str_format_frequency(radioInterfacesParams.interface_current_frequency_khz[i]), radioInterfacesParams.interface_link_id[i]+1, szBuff, szBuff2); + log_line("* %sRadio Interface %d: %s on port %s, %s, supported bands: %s, current frequency: %s, assigned to radio link %d, current capabilities: %s, current radio flags: %s, raw_tx_power: %d", + szPrefix, i+1, str_get_radio_card_model_string(radioInterfacesParams.interface_card_model[i]), radioInterfacesParams.interface_szPort[i], str_get_radio_driver_description(radioInterfacesParams.interface_radiotype_and_driver[i]), szBands, str_format_frequency(radioInterfacesParams.interface_current_frequency_khz[i]), radioInterfacesParams.interface_link_id[i]+1, szBuff, szBuff2, + radioInterfacesParams.interface_raw_power[i]); } else - log_line("* Radio Interface %d: %s, %s on port %s, %s, supported bands: %s, current frequency: %s, assigned to radio link %d, current capabilities: %s, current radio flags: %s", - i+1, radioInterfacesParams.interface_szMAC[i], str_get_radio_card_model_string(radioInterfacesParams.interface_card_model[i]), radioInterfacesParams.interface_szPort[i], str_get_radio_driver_description(radioInterfacesParams.interface_radiotype_and_driver[i]), szBands, str_format_frequency(radioInterfacesParams.interface_current_frequency_khz[i]), radioInterfacesParams.interface_link_id[i]+1, szBuff, szBuff2); + log_line("* Radio Interface %d: %s, %s on port %s, %s, supported bands: %s, current frequency: %s, assigned to radio link %d, current capabilities: %s, current radio flags: %s, raw_tx_power: %d", + i+1, radioInterfacesParams.interface_szMAC[i], str_get_radio_card_model_string(radioInterfacesParams.interface_card_model[i]), radioInterfacesParams.interface_szPort[i], str_get_radio_driver_description(radioInterfacesParams.interface_radiotype_and_driver[i]), szBands, str_format_frequency(radioInterfacesParams.interface_current_frequency_khz[i]), radioInterfacesParams.interface_link_id[i]+1, szBuff, szBuff2, + radioInterfacesParams.interface_raw_power[i]); } log_line("------------------------------------------------------"); @@ -3767,12 +3812,16 @@ bool Model::validate_settings() if ( (telemetry_params.iVideoBitrateHistoryGraphSampleInterval < 10) || (telemetry_params.iVideoBitrateHistoryGraphSampleInterval > 1000) ) telemetry_params.iVideoBitrateHistoryGraphSampleInterval = 200; + for( int i=0; i 3) ) radioLinksParams.uUplinkDataDataRateType[i] = FLAG_RADIO_LINK_DATARATE_DATA_TYPE_LOWEST; if ( (radioLinksParams.uDownlinkDataDataRateType[i] <= 0) || (radioLinksParams.uDownlinkDataDataRateType[i] > 3) ) radioLinksParams.uDownlinkDataDataRateType[i] = FLAG_RADIO_LINK_DATARATE_DATA_TYPE_LOWEST; + + if ( (radioInterfacesParams.interface_raw_power[i] < 1) || (radioInterfacesParams.interface_raw_power[i] > 71) ) + radioInterfacesParams.interface_raw_power[i] = DEFAULT_RADIO_TX_POWER; } if ( (radioLinksParams.iSiKPacketSize < DEFAULT_RADIO_SERIAL_AIR_MIN_PACKET_SIZE) || @@ -3869,11 +3918,6 @@ bool Model::validate_settings() if ( radioLinksParams.link_frequency_khz[i] == 0 ) radioLinksParams.link_frequency_khz[i] = DEFAULT_FREQUENCY; } - - if ( radioInterfacesParams.txPowerSiK <= 0 ) - radioInterfacesParams.txPowerSiK = DEFAULT_RADIO_SIK_TX_POWER; - if ( radioInterfacesParams.txPowerSiK > 20 ) - radioInterfacesParams.txPowerSiK = DEFAULT_RADIO_SIK_TX_POWER; if ( osd_params.layout < osdLayout1 || osd_params.layout >= osdLayoutLast ) osd_params.layout = osdLayout1; @@ -3897,13 +3941,13 @@ bool Model::validate_settings() if ( rxtx_sync_type < 0 || rxtx_sync_type >= RXTX_SYNC_TYPE_LAST ) rxtx_sync_type = RXTX_SYNC_TYPE_BASIC; - if ( processesPriorities.iNiceRouter < -18 || processesPriorities.iNiceRouter > 0 ) + if ( processesPriorities.iNiceRouter < -18 || processesPriorities.iNiceRouter > 5 ) processesPriorities.iNiceRouter = DEFAULT_PRIORITY_PROCESS_ROUTER; - if ( processesPriorities.iNiceVideo < -18 || processesPriorities.iNiceVideo > 0 ) + if ( processesPriorities.iNiceVideo < -18 || processesPriorities.iNiceVideo > 5 ) processesPriorities.iNiceVideo = DEFAULT_PRIORITY_PROCESS_VIDEO_TX; if ( processesPriorities.iNiceRC < -16 || processesPriorities.iNiceRC > 0 ) processesPriorities.iNiceRC = DEFAULT_PRIORITY_PROCESS_RC; - if ( processesPriorities.iNiceTelemetry < -16 || processesPriorities.iNiceTelemetry > 0 ) + if ( processesPriorities.iNiceTelemetry < -16 || processesPriorities.iNiceTelemetry > 5 ) processesPriorities.iNiceTelemetry = DEFAULT_PRIORITY_PROCESS_TELEMETRY; if ( audio_params.volume < 0 || audio_params.volume > 100 ) @@ -4057,6 +4101,14 @@ void Model::resetToDefaults(bool generateId) hwCapabilities.uBoardType = hardware_getOnlyBoardType(); resetHWCapabilities(); + if ( generateId ) + { + int iMajor = 0; + int iMinor = 0; + get_Ruby_BaseVersion(&iMajor, &iMinor); + hwCapabilities.uRubyBaseVersion = (((u32)iMajor)<<8) | (((u32)iMinor) & 0xFF); + } + uControllerId = 0; sw_version = (SYSTEM_SW_VERSION_MAJOR * 256 + SYSTEM_SW_VERSION_MINOR) | (SYSTEM_SW_BUILD_NUMBER<<16); log_line("SW Version: %d.%d (b%d)", (sw_version >> 8) & 0xFF, sw_version & 0xFF, sw_version >> 16); @@ -4079,7 +4131,7 @@ void Model::resetToDefaults(bool generateId) hardwareInterfacesInfo.radio_interface_count = 0; hardwareInterfacesInfo.i2c_bus_count = 0; hardwareInterfacesInfo.i2c_device_count = 0; - hardwareInterfacesInfo.serial_bus_count = 0; + hardwareInterfacesInfo.serial_port_count = 0; radioInterfacesParams.interfaces_count = 0; radioLinksParams.links_count = 0; @@ -4112,8 +4164,13 @@ void Model::resetToDefaults(bool generateId) processesPriorities.uProcessesFlags = PROCESSES_FLAGS_BALANCE_INT_CORES; processesPriorities.iNiceTelemetry = DEFAULT_PRIORITY_PROCESS_TELEMETRY; + if ( isRunningOnOpenIPCHardware() ) + processesPriorities.iNiceTelemetry = DEFAULT_PRIORITY_PROCESS_TELEMETRY_OIPC; + processesPriorities.iNiceRC = DEFAULT_PRIORITY_PROCESS_RC; processesPriorities.iNiceRouter = DEFAULT_PRIORITY_PROCESS_ROUTER; + if ( isRunningOnOpenIPCHardware() ) + processesPriorities.iNiceRouter = DEFAULT_PRIORITY_PROCESS_ROUTER_OPIC; processesPriorities.ioNiceRouter = DEFAULT_IO_PRIORITY_ROUTER; processesPriorities.iNiceVideo = DEFAULT_PRIORITY_PROCESS_VIDEO_TX; if ( hardware_board_is_openipc(hardware_getOnlyBoardType()) ) @@ -4177,16 +4234,16 @@ void Model::resetHWCapabilities() void Model::resetRadioLinksParams() { - log_line("Model: Did reset radio links params."); - radioInterfacesParams.txPowerRTL8812AU = DEFAULT_RADIO_TX_POWER; - radioInterfacesParams.txPowerRTL8812EU = DEFAULT_RADIO_TX_POWER; - radioInterfacesParams.txPowerAtheros = DEFAULT_RADIO_TX_POWER; - radioInterfacesParams.txPowerSiK = DEFAULT_RADIO_SIK_TX_POWER; - radioInterfacesParams.txMaxPowerRTL8812AU = MAX_TX_POWER; - radioInterfacesParams.txMaxPowerRTL8812EU = MAX_TX_POWER; - radioInterfacesParams.txMaxPowerAtheros = MAX_TX_POWER; - radioInterfacesParams.slotTime = DEFAULT_RADIO_SLOTTIME; - radioInterfacesParams.thresh62 = DEFAULT_RADIO_THRESH62; + log_line("Model: Reset radio links params..."); + radioInterfacesParams.iAutoVehicleTxPower = 1; + radioInterfacesParams.iAutoControllerTxPower = 1; + radioInterfacesParams.iDummyR3 = 0; + radioInterfacesParams.iDummyR4 = 0; + radioInterfacesParams.iDummyR5 = 0; + radioInterfacesParams.iDummyR6 = 0; + radioInterfacesParams.iDummyR7 = 0; + radioInterfacesParams.iDummyR8 = 0; + radioInterfacesParams.iDummyR9 = 0; radioLinksParams.iSiKPacketSize = DEFAULT_SIK_PACKET_SIZE; radioLinksParams.uGlobalRadioLinksFlags = 0; @@ -4195,7 +4252,7 @@ void Model::resetRadioLinksParams() for( int i=0; i 0 ) @@ -4897,11 +4951,7 @@ int Model::hasRadioCardsRTL8812AU() int iCount = 0; for( int i=0; i> 8) & 0xFF) == RADIO_HW_DRIVER_REALTEK_RTL88XXAU) || - (((radioInterfacesParams.interface_radiotype_and_driver[i] >> 8) & 0xFF) == RADIO_HW_DRIVER_REALTEK_RTL8812AU) || - (((radioInterfacesParams.interface_radiotype_and_driver[i] >> 8) & 0xFF) == RADIO_HW_DRIVER_REALTEK_8812AU) || - (((radioInterfacesParams.interface_radiotype_and_driver[i] >> 8) & 0xFF) == RADIO_HW_DRIVER_REALTEK_RTL88X2BU) || - (((radioInterfacesParams.interface_radiotype_and_driver[i] >> 8) & 0xFF) == RADIO_HW_DRIVER_MEDIATEK) ) + if ( hardware_radio_driver_is_rtl8812au_card((radioInterfacesParams.interface_radiotype_and_driver[i] >> 8) & 0xFF) ) iCount++; } return iCount; @@ -4912,7 +4962,7 @@ int Model::hasRadioCardsRTL8812EU() int iCount = 0; for( int i=0; i> 8) & 0xFF) == RADIO_HW_DRIVER_REALTEK_8812EU ) + if ( hardware_radio_driver_is_rtl8812eu_card((radioInterfacesParams.interface_radiotype_and_driver[i] >> 8) & 0xFF) ) iCount++; } return iCount; @@ -4923,7 +4973,7 @@ int Model::hasRadioCardsAtheros() int iCount = 0; for( int i=0; i> 8) & 0xFF) == RADIO_HW_DRIVER_ATHEROS ) + if ( hardware_radio_driver_is_atheros_card((radioInterfacesParams.interface_radiotype_and_driver[i] >> 8) & 0xFF) ) iCount++; } return iCount; @@ -5420,7 +5470,7 @@ void Model::getVideoFlags(char* szVideoFlags, int iVideoProfile) strcat(szVideoFlags, szBuff); } - if ( video_link_profiles[iVideoProfile].insertPPS ) + if ( video_params.iInsertPPSVideoFrames ) strcat(szVideoFlags, " -ih"); int iSlices = camera_get_active_camera_h264_slices(this); @@ -5430,7 +5480,7 @@ void Model::getVideoFlags(char* szVideoFlags, int iVideoProfile) strcat(szVideoFlags, szBuff); } - if ( video_params.uVideoExtraFlags & VIDEO_FLAG_FILL_H264_SPT_TIMINGS ) + if ( video_params.iInsertSPTVideoFramesTimings ) strcat(szVideoFlags, " -stm"); switch ( video_link_profiles[iVideoProfile].h264profile ) @@ -5438,7 +5488,7 @@ void Model::getVideoFlags(char* szVideoFlags, int iVideoProfile) case 0: strcat(szVideoFlags, " -pf baseline"); break; case 1: strcat(szVideoFlags, " -pf main"); break; case 2: strcat(szVideoFlags, " -pf high"); break; - //case 2: strcat(szVideoFlags, " -pf extended"); break; + case 3: strcat(szVideoFlags, " -pf extended"); break; } switch ( video_link_profiles[iVideoProfile].h264level ) @@ -5536,7 +5586,10 @@ void Model::populateFromVehicleTelemetryData_v1(t_packet_header_ruby_telemetry_e radioInterfacesParams.interface_current_frequency_khz[0] = radioLinksParams.link_frequency_khz[0]; strcpy(radioInterfacesParams.interface_szMAC[0], "XXXXXX"); strcpy(radioInterfacesParams.interface_szPort[0], "X"); - radioInterfacesParams.interface_dummy1[0] = 0; + + radioInterfacesParams.interface_raw_power[0] = DEFAULT_RADIO_TX_POWER; + if ( radioLinksParams.link_frequency_khz[0] < 1000000 ) + radioInterfacesParams.interface_raw_power[0] = DEFAULT_RADIO_SIK_TX_POWER; radioInterfacesParams.interface_dummy2[0] = 0; radioInterfacesParams.interface_card_model[0] = 0; @@ -5550,7 +5603,9 @@ void Model::populateFromVehicleTelemetryData_v1(t_packet_header_ruby_telemetry_e radioInterfacesParams.interface_current_frequency_khz[1] = radioLinksParams.link_frequency_khz[1]; strcpy(radioInterfacesParams.interface_szMAC[1], "XXXXXX"); strcpy(radioInterfacesParams.interface_szPort[1], "X"); - radioInterfacesParams.interface_dummy1[1] = 0; + radioInterfacesParams.interface_raw_power[1] = DEFAULT_RADIO_TX_POWER; + if ( radioLinksParams.link_frequency_khz[1] < 1000000 ) + radioInterfacesParams.interface_raw_power[1] = DEFAULT_RADIO_SIK_TX_POWER; radioInterfacesParams.interface_dummy2[1] = 0; radioInterfacesParams.interface_card_model[1] = 0; } @@ -5612,7 +5667,9 @@ void Model::populateFromVehicleTelemetryData_v2(t_packet_header_ruby_telemetry_e radioInterfacesParams.interface_current_frequency_khz[0] = radioLinksParams.link_frequency_khz[0]; strcpy(radioInterfacesParams.interface_szMAC[0], "XXXXXX"); strcpy(radioInterfacesParams.interface_szPort[0], "X"); - radioInterfacesParams.interface_dummy1[0] = 0; + radioInterfacesParams.interface_raw_power[0] = DEFAULT_RADIO_TX_POWER; + if ( radioLinksParams.link_frequency_khz[0] < 1000000 ) + radioInterfacesParams.interface_raw_power[0] = DEFAULT_RADIO_SIK_TX_POWER; radioInterfacesParams.interface_dummy2[0] = 0; radioInterfacesParams.interface_card_model[0] = 0; radioInterfacesParams.interface_supported_bands[0] = getBand(radioLinksParams.link_frequency_khz[0]); @@ -5634,7 +5691,9 @@ void Model::populateFromVehicleTelemetryData_v2(t_packet_header_ruby_telemetry_e radioInterfacesParams.interface_current_frequency_khz[radioInterfacesParams.interfaces_count] = radioLinksParams.link_frequency_khz[i]; strcpy(radioInterfacesParams.interface_szMAC[radioInterfacesParams.interfaces_count], "XXXXXX"); strcpy(radioInterfacesParams.interface_szPort[radioInterfacesParams.interfaces_count], "X"); - radioInterfacesParams.interface_dummy1[radioInterfacesParams.interfaces_count] = 0; + radioInterfacesParams.interface_raw_power[radioInterfacesParams.interfaces_count] = DEFAULT_RADIO_TX_POWER; + if ( radioLinksParams.link_frequency_khz[i] < 1000000 ) + radioInterfacesParams.interface_raw_power[radioInterfacesParams.interfaces_count] = DEFAULT_RADIO_SIK_TX_POWER; radioInterfacesParams.interface_dummy2[radioInterfacesParams.interfaces_count] = 0; radioInterfacesParams.interface_card_model[radioInterfacesParams.interfaces_count] = 0; radioInterfacesParams.interfaces_count++; @@ -5711,7 +5770,9 @@ void Model::populateFromVehicleTelemetryData_v3(t_packet_header_ruby_telemetry_e radioInterfacesParams.interface_current_frequency_khz[0] = radioLinksParams.link_frequency_khz[0]; strcpy(radioInterfacesParams.interface_szMAC[0], "XXXXXX"); strcpy(radioInterfacesParams.interface_szPort[0], "X"); - radioInterfacesParams.interface_dummy1[0] = 0; + radioInterfacesParams.interface_raw_power[0] = DEFAULT_RADIO_TX_POWER; + if ( radioLinksParams.link_frequency_khz[0] < 1000000 ) + radioInterfacesParams.interface_raw_power[0] = DEFAULT_RADIO_SIK_TX_POWER; radioInterfacesParams.interface_dummy2[0] = 0; radioInterfacesParams.interface_supported_bands[0] = getBand(radioLinksParams.link_frequency_khz[0]); radioInterfacesParams.interface_card_model[0] = 0; @@ -5740,7 +5801,9 @@ void Model::populateFromVehicleTelemetryData_v3(t_packet_header_ruby_telemetry_e radioInterfacesParams.interface_current_frequency_khz[iInterfaceIndex] = radioLinksParams.link_frequency_khz[i]; strcpy(radioInterfacesParams.interface_szMAC[iInterfaceIndex], "XXXXXX"); strcpy(radioInterfacesParams.interface_szPort[iInterfaceIndex], "X"); - radioInterfacesParams.interface_dummy1[iInterfaceIndex] = 0; + radioInterfacesParams.interface_raw_power[iInterfaceIndex] = DEFAULT_RADIO_TX_POWER; + if ( radioLinksParams.link_frequency_khz[i] < 1000000 ) + radioInterfacesParams.interface_raw_power[iInterfaceIndex] = DEFAULT_RADIO_SIK_TX_POWER; radioInterfacesParams.interface_dummy2[iInterfaceIndex] = 0; radioInterfacesParams.interface_supported_bands[iInterfaceIndex] = getBand(radioLinksParams.link_frequency_khz[i]); if ( getBand(radioLinksParams.link_frequency_khz[i]) == RADIO_HW_SUPPORTED_BAND_58 ) @@ -6092,7 +6155,7 @@ void Model::copy_radio_interface_params(int iFrom, int iTo) radioInterfacesParams.interface_card_model[iTo] = radioInterfacesParams.interface_card_model[iFrom]; radioInterfacesParams.interface_link_id[iTo] = radioInterfacesParams.interface_link_id[iFrom]; - radioInterfacesParams.interface_power[iTo] = radioInterfacesParams.interface_power[iFrom]; + radioInterfacesParams.interface_raw_power[iTo] = radioInterfacesParams.interface_raw_power[iFrom]; radioInterfacesParams.interface_radiotype_and_driver[iTo] = radioInterfacesParams.interface_radiotype_and_driver[iFrom]; radioInterfacesParams.interface_supported_bands[iTo] = radioInterfacesParams.interface_supported_bands[iFrom]; strcpy( radioInterfacesParams.interface_szMAC[iTo], radioInterfacesParams.interface_szMAC[iFrom]); @@ -6100,7 +6163,6 @@ void Model::copy_radio_interface_params(int iFrom, int iTo) radioInterfacesParams.interface_capabilities_flags[iTo] = radioInterfacesParams.interface_capabilities_flags[iFrom]; radioInterfacesParams.interface_current_frequency_khz[iTo] = radioInterfacesParams.interface_current_frequency_khz[iFrom]; radioInterfacesParams.interface_current_radio_flags[iTo] = radioInterfacesParams.interface_current_radio_flags[iFrom]; - radioInterfacesParams.interface_dummy1[iTo] = radioInterfacesParams.interface_dummy1[iFrom]; radioInterfacesParams.interface_dummy2[iTo] = radioInterfacesParams.interface_dummy2[iFrom]; } diff --git a/code/base/models.h b/code/base/models.h index c2f60a33..165a9746 100644 --- a/code/base/models.h +++ b/code/base/models.h @@ -69,6 +69,9 @@ typedef struct { int user_selected_video_link_profile; // set by user on the controller int iH264Slices; + int iRemovePPSVideoFrames; + int iInsertPPSVideoFrames; + int iInsertSPTVideoFramesTimings; int videoAdjustmentStrength; // 1..10 (from 10% to 100% strength) u32 lowestAllowedAdaptiveVideoBitrate; u32 uMaxAutoKeyframeIntervalMs; // in milisec @@ -117,7 +120,7 @@ typedef struct int h264level; //0 = 4.0, 1 = 4.1, 2 = 4.2 int h264refresh; // 0 = cyclic, 1 = adaptive, 2 = both, 3 = cyclicrows int h264quantization; // 0 - auto, // pozitive - value to use, // negative - value when disabled (auto) - u8 insertPPS; + int iIPQuantizationDelta; int width; int height; @@ -280,8 +283,8 @@ typedef struct #define MAX_MODEL_I2C_BUSSES 6 #define MAX_MODEL_I2C_DEVICES 16 -#define MAX_MODEL_SERIAL_BUSSES 6 -#define MAX_MODEL_SERIAL_BUS_NAME 16 +#define MAX_MODEL_SERIAL_PORTS 6 +#define MAX_MODEL_SERIAL_PORT_NAME 16 #define MODEL_SERIAL_PORT_BIT_EXTRNAL_USB ((u32)(((u32)0x01)<<11)) #define MODEL_SERIAL_PORT_BIT_SUPPORTED ((u32)(((u32)0x01)<<12)) @@ -294,15 +297,15 @@ typedef struct int i2c_devices_bus[MAX_MODEL_I2C_DEVICES]; int radio_interface_count; - int serial_bus_count; - char serial_bus_names[MAX_MODEL_SERIAL_BUSSES][MAX_MODEL_SERIAL_BUS_NAME]; - u32 serial_bus_supported_and_usage[MAX_MODEL_SERIAL_BUSSES]; + int serial_port_count; + char serial_port_names[MAX_MODEL_SERIAL_PORTS][MAX_MODEL_SERIAL_PORT_NAME]; + u32 serial_port_supported_and_usage[MAX_MODEL_SERIAL_PORTS]; // byte 0: usage type; same as hardware_serial enum: SERIAL_PORT_USAGE_xxxx // byte 1: bits 0...3 usb or hardware port index // bits 4 : 0 - hardware builtin, 1 - on usb // bits 5 : supported 0/1 - int serial_bus_speed[MAX_MODEL_SERIAL_BUSSES]; + int serial_port_speed[MAX_MODEL_SERIAL_PORTS]; } type_vehicle_hardware_interfaces_info; @@ -367,21 +370,30 @@ typedef struct typedef struct { - int txPowerRTL8812AU; - int txPowerRTL8812EU; - int txPowerAtheros; - int txPowerSiK; - int txMaxPowerRTL8812AU; - int txMaxPowerRTL8812EU; - int txMaxPowerAtheros; - int slotTime; - int thresh62; + //int txPowerRTL8812AU; + //int txPowerRTL8812EU; + //int txPowerAtheros; + //int txPowerSiK; + //int txMaxPowerRTL8812AU; + //int txMaxPowerRTL8812EU; + //int txMaxPowerAtheros; + //int slotTime; + //int thresh62; + int iAutoVehicleTxPower; + int iAutoControllerTxPower; + int iDummyR3; + int iDummyR4; + int iDummyR5; + int iDummyR6; + int iDummyR7; + int iDummyR8; + int iDummyR9; int interfaces_count; int interface_card_model[MAX_RADIO_INTERFACES]; // 0 or positive - autodetected, negative - user set int interface_link_id[MAX_RADIO_INTERFACES]; - int interface_power[MAX_RADIO_INTERFACES]; - u32 interface_radiotype_and_driver[MAX_RADIO_INTERFACES]; // first byte: radio type, second byte = driver type, third byte: supported card flag + int interface_raw_power[MAX_RADIO_INTERFACES]; + u32 interface_radiotype_and_driver[MAX_RADIO_INTERFACES]; // low byte: radio type, second byte = driver type, third byte: supported card flag u8 interface_supported_bands[MAX_RADIO_INTERFACES]; // bits 0-3: 2.3, 2.4, 2.5, 5.8 bands char interface_szMAC[MAX_RADIO_INTERFACES][MAX_MAC_LENGTH]; char interface_szPort[MAX_RADIO_INTERFACES][6]; // first byte - first char, sec byte - sec char @@ -389,10 +401,6 @@ typedef struct u32 interface_current_frequency_khz[MAX_RADIO_INTERFACES]; // current frequency for this card u32 interface_current_radio_flags[MAX_RADIO_INTERFACES]; // radio flags: frame type, STBC, LDP, MCS etc - // Deprecated in 9.5 - //int interface_datarate_video_bps[MAX_RADIO_INTERFACES]; // 0 - auto (use radio link datarates), positive: bps, negative (-1 or less): MCS rate - //int interface_datarate_data_bps[MAX_RADIO_INTERFACES]; // 0 - auto (use radio link datarates), positive: bps, negative (-1 or less): MCS rate - int interface_dummy1[MAX_RADIO_INTERFACES]; int interface_dummy2[MAX_RADIO_INTERFACES]; } type_radio_interfaces_parameters; @@ -476,7 +484,8 @@ typedef struct int iMaxTxVideoBlocksBuffer; // max blocks that can be cached on vehicle int iMaxTxVideoBlockPackets; // max packets in a video block u32 uFlags; - int dummyhwc[2]; + u32 uRubyBaseVersion; + int dummyhwc[1]; u32 dummyhwc2[3]; } type_hardware_capabilities; diff --git a/code/base/models_list.cpp b/code/base/models_list.cpp index 110d1d65..30c4882d 100644 --- a/code/base/models_list.cpp +++ b/code/base/models_list.cpp @@ -122,7 +122,7 @@ bool loadAllModels() } log_line("Loaded %d spectator models.", s_iModelsSpectatorCount); - log_line("Loaded controller models:"); + log_line("Loaded controller models (%d):", s_iModelsCount); for( int i=0; igetLongName(), s_pModels[i]->uVehicleId); @@ -231,6 +231,7 @@ int getControllerModelsSpectatorCount() void deleteAllModels() { + log_line("Deleted all controller models."); s_iModelsSpectatorCount = 0; s_iModelsCount = 0; char szFile[MAX_FILE_PATH_SIZE]; diff --git a/code/base/parser_h264.cpp b/code/base/parser_h264.cpp index cd899ddb..2001b33a 100644 --- a/code/base/parser_h264.cpp +++ b/code/base/parser_h264.cpp @@ -45,110 +45,86 @@ ParserH264::~ParserH264() void ParserH264::init() { m_iDetectedISlices = 1; + m_iConsecutiveSlicesForCurrentNALU = 0; m_uStreamCurrentParseToken = MAX_U32; m_uCurrentNALUType = 0; m_uLastNALUType = 0; - m_iConsecutiveSlicesForCurrentNALU = 0; - m_uTimeDurationOfLastFrame = 0; - m_uTimeStartOfCurrentFrame = 0; - m_uTimeLastStartOfIFrame = 0; m_uSizeCurrentFrame = 0; m_uSizeLastFrame = 0; - m_uCurrentDetectedKeyframeIntervalMs = 0; - m_uFramesSinceLastKeyframe = 0; + m_iFramesSinceLastKeyframe = 0; + m_iDetectedKeyframeIntervalInFrames = 1; - m_uDebugFramesCounter = 0; - m_uDebugTimeStartFramesCounter = 0; - m_uDebugDetectedFPS = 0; + m_uTimeLastFPSCompute = 0; + m_iFramesSinceLastFPSCompute = 0; + m_iDetectedFPS = 0; } -// Returns the number of starts of a new frames if it was found -int ParserH264::parseData(u8* pData, int iDataLength, u32 uTimeNowMs) +// Returns the number of bytes parsed from input +int ParserH264::parseDataUntillStartOfNextNAL(u8* pData, int iDataLength, u32 uTimeNow) { if ( (NULL == pData) || (iDataLength <= 0) ) return 0; - int iFoundFrameStartCount = 0; - + int iBytesParsed = 0; while ( iDataLength > 0 ) { m_uStreamCurrentParseToken = (m_uStreamCurrentParseToken<<8) | (*pData); - pData++; - iDataLength--; - m_uSizeCurrentFrame++; - // If not start a new NAL unit (00 00 01), continue parsing data if ( (m_uStreamCurrentParseToken & 0xFFFFFF00) != 0x0100 ) - continue; - - if ( _onParseStartOfNALUnit() ) { - iFoundFrameStartCount++; - m_uDebugFramesCounter++; - m_uTimeDurationOfLastFrame = uTimeNowMs - m_uTimeStartOfCurrentFrame; - m_uTimeStartOfCurrentFrame = uTimeNowMs; - - if ( m_uCurrentNALUType == 5 ) - { - m_uCurrentDetectedKeyframeIntervalMs = uTimeNowMs - m_uTimeLastStartOfIFrame; - m_uTimeLastStartOfIFrame = uTimeNowMs; - m_uFramesSinceLastKeyframe = 0; - } - - if ( uTimeNowMs >= m_uDebugTimeStartFramesCounter + 1000 ) - { - m_uDebugTimeStartFramesCounter = uTimeNowMs; - m_uDebugDetectedFPS = m_uDebugFramesCounter; - m_uDebugFramesCounter = 0; - } + pData++; + iDataLength--; + iBytesParsed++; + m_uSizeCurrentFrame++; + continue; } + _parseDetectedStartOfNALUnit(uTimeNow); + break; } - return iFoundFrameStartCount; + return iBytesParsed; } -// returns true if start of a new frame is detected (not of a new slice in a frame) -bool ParserH264::_onParseStartOfNALUnit() +void ParserH264::_parseDetectedStartOfNALUnit(u32 uTimeNow) { + m_uLastNALUType = m_uCurrentNALUType; m_uCurrentNALUType = m_uStreamCurrentParseToken & 0b11111; + m_uSizeLastFrame = m_uSizeCurrentFrame; + //log_line("DEBUG start of NAL %d, last NAL %d, last NAL size: %d", m_uCurrentNALUType, m_uLastNALUType, m_uSizeLastFrame); + m_uSizeCurrentFrame = 0; - // We started a new frame P,I or SPP PSP frames ? - bool bStartedNewFrame = false; - - if ( m_uCurrentNALUType != m_uLastNALUType ) - { - bStartedNewFrame = true; - if ( m_uLastNALUType == 5 ) - m_iDetectedISlices = m_iConsecutiveSlicesForCurrentNALU; - - m_iConsecutiveSlicesForCurrentNALU = 0; - m_uLastNALUType = m_uCurrentNALUType; - } - else if ( (m_iConsecutiveSlicesForCurrentNALU >= m_iDetectedISlices) && (m_uCurrentNALUType == 1) ) + // Begin: compute slices based on Iframe + if ( (m_uCurrentNALUType == 5) && (m_uLastNALUType != 5) ) + m_iConsecutiveSlicesForCurrentNALU = 1; + if ( (m_uCurrentNALUType == 5) && (m_uLastNALUType == 5) ) + m_iConsecutiveSlicesForCurrentNALU++; + if ( (m_uCurrentNALUType != 5) && (m_uLastNALUType == 5) ) { - bStartedNewFrame = true; - m_iConsecutiveSlicesForCurrentNALU = 0; + m_iDetectedISlices = m_iConsecutiveSlicesForCurrentNALU; + m_iConsecutiveSlicesForCurrentNALU = 0; + m_iDetectedKeyframeIntervalInFrames = m_iFramesSinceLastKeyframe/m_iDetectedISlices; + m_iFramesSinceLastKeyframe = 0; } - m_iConsecutiveSlicesForCurrentNALU++; - // P-frame is 1, I-frame is 5 - if ( (m_uCurrentNALUType != 1) && (m_uCurrentNALUType != 5) ) - return bStartedNewFrame; + // End: compute slices based on Iframe - // P or I frame (slice) just started. Compute info - - if ( bStartedNewFrame ) + if ( (m_uCurrentNALUType == 5) || (m_uCurrentNALUType == 1) ) + m_iFramesSinceLastKeyframe++; + m_iFramesSinceLastFPSCompute++; + if ( 100 == m_iFramesSinceLastFPSCompute ) { - m_uFramesSinceLastKeyframe++; - m_uSizeLastFrame = m_uSizeCurrentFrame; - m_uSizeCurrentFrame = 0; + if ( uTimeNow != m_uTimeLastFPSCompute ) + m_iDetectedFPS = 100000/(uTimeNow - m_uTimeLastFPSCompute); + if ( m_iDetectedISlices > 0 ) + m_iDetectedFPS /= m_iDetectedISlices; + m_uTimeLastFPSCompute = uTimeNow; + m_iFramesSinceLastFPSCompute = 0; } - return bStartedNewFrame; } -u32 ParserH264::getStartTimeOfCurrentFrame() +bool ParserH264::IsInsideIFrame() { - return m_uTimeStartOfCurrentFrame; + return (m_uCurrentNALUType == 5)?true:false; } u32 ParserH264::getCurrentFrameType() @@ -156,19 +132,15 @@ u32 ParserH264::getCurrentFrameType() return m_uCurrentNALUType; } -u32 ParserH264::getStartTimeOfLastIFrame() +u32 ParserH264::getPreviousFrameType() { - return m_uTimeLastStartOfIFrame; + return m_uLastNALUType; } -u32 ParserH264::getSizeOfLastCompleteFrame() -{ - return m_uSizeLastFrame; -} -u32 ParserH264::getTimeDurationOfLastCompleteFrame() +u32 ParserH264::getSizeOfLastCompleteFrameInBytes() { - return m_uTimeDurationOfLastFrame; + return m_uSizeLastFrame; } int ParserH264::getDetectedSlices() @@ -176,24 +148,8 @@ int ParserH264::getDetectedSlices() return m_iDetectedISlices; } -u32 ParserH264::getCurrentlyDetectedKeyframeIntervalMs() -{ - return m_uCurrentDetectedKeyframeIntervalMs; -} -bool ParserH264::IsInsideIFrame() +int ParserH264::getDetectedFPS() { - if ( m_uCurrentNALUType == 5 ) - return true; - return false; -} - -u32 ParserH264::getFramesSinceLastKeyframe() -{ - return m_uFramesSinceLastKeyframe; -} - -u32 ParserH264::getDetectedFPS() -{ - return m_uDebugDetectedFPS; -} + return m_iDetectedFPS; +} \ No newline at end of file diff --git a/code/base/parser_h264.h b/code/base/parser_h264.h index beec8aaa..87b6c205 100644 --- a/code/base/parser_h264.h +++ b/code/base/parser_h264.h @@ -9,39 +9,30 @@ class ParserH264 void init(); - // Returns number of start of a new frames that was found - int parseData(u8* pData, int iDataLength, u32 uTimeNowMs); + // Returns number of bytes parsed from input untill start of NAL detected + int parseDataUntillStartOfNextNAL(u8* pData, int iDataLength, u32 uTimeNow); - u32 getStartTimeOfCurrentFrame(); + bool IsInsideIFrame(); u32 getCurrentFrameType(); - u32 getStartTimeOfLastIFrame(); - u32 getSizeOfLastCompleteFrame(); - u32 getTimeDurationOfLastCompleteFrame(); + u32 getPreviousFrameType(); + u32 getSizeOfLastCompleteFrameInBytes(); int getDetectedSlices(); - u32 getCurrentlyDetectedKeyframeIntervalMs(); - bool IsInsideIFrame(); - u32 getFramesSinceLastKeyframe(); - u32 getDetectedFPS(); - + int getDetectedFPS(); + protected: - int m_iDetectedISlices; u32 m_uStreamCurrentParseToken; u32 m_uCurrentNALUType; u32 m_uLastNALUType; + int m_iDetectedISlices; int m_iConsecutiveSlicesForCurrentNALU; - u32 m_uTimeStartOfCurrentFrame; - u32 m_uTimeLastStartOfIFrame; - u32 m_uTimeDurationOfLastFrame; u32 m_uSizeCurrentFrame; u32 m_uSizeLastFrame; - u32 m_uCurrentDetectedKeyframeIntervalMs; - u32 m_uFramesSinceLastKeyframe; - - u32 m_uDebugFramesCounter; - u32 m_uDebugTimeStartFramesCounter; - u32 m_uDebugDetectedFPS; + int m_iDetectedKeyframeIntervalInFrames; + int m_iFramesSinceLastKeyframe; - // returns true if start of a new frame is detected (not of a new slice in a frame) - bool _onParseStartOfNALUnit(); + u32 m_uTimeLastFPSCompute; + int m_iFramesSinceLastFPSCompute; + int m_iDetectedFPS; + void _parseDetectedStartOfNALUnit(u32 uTimeNow); }; diff --git a/code/base/shared_mem.c b/code/base/shared_mem.c index 42b18745..1909dfec 100644 --- a/code/base/shared_mem.c +++ b/code/base/shared_mem.c @@ -171,59 +171,59 @@ void shared_mem_radio_stats_rx_hist_close(shared_mem_radio_stats_rx_hist* pAddre munmap(pAddress, sizeof(shared_mem_radio_stats_rx_hist)); } -shared_mem_video_info_stats* shared_mem_video_info_stats_open_for_read() +shared_mem_video_frames_stats* shared_mem_video_frames_stats_open_for_read() { - void *retVal = open_shared_mem_for_read(SHARED_MEM_VIDEO_STREAM_INFO_STATS , sizeof(shared_mem_video_info_stats)); - return (shared_mem_video_info_stats*)retVal; + void *retVal = open_shared_mem_for_read(SHARED_MEM_VIDEO_FRAMES_STATS , sizeof(shared_mem_video_frames_stats)); + return (shared_mem_video_frames_stats*)retVal; } -shared_mem_video_info_stats* shared_mem_video_info_stats_open_for_write() +shared_mem_video_frames_stats* shared_mem_video_frames_stats_open_for_write() { - void *retVal = open_shared_mem_for_write(SHARED_MEM_VIDEO_STREAM_INFO_STATS , sizeof(shared_mem_video_info_stats)); - return (shared_mem_video_info_stats*)retVal; + void *retVal = open_shared_mem_for_write(SHARED_MEM_VIDEO_FRAMES_STATS , sizeof(shared_mem_video_frames_stats)); + return (shared_mem_video_frames_stats*)retVal; } -void shared_mem_video_info_stats_close(shared_mem_video_info_stats* pAddress) +void shared_mem_video_frames_stats_close(shared_mem_video_frames_stats* pAddress) { if ( NULL != pAddress ) - munmap(pAddress, sizeof(shared_mem_video_info_stats)); + munmap(pAddress, sizeof(shared_mem_video_frames_stats)); } -shared_mem_video_info_stats* shared_mem_video_info_stats_radio_in_open_for_read() +shared_mem_video_frames_stats* shared_mem_video_frames_stats_radio_in_open_for_read() { - void *retVal = open_shared_mem_for_read(SHARED_MEM_VIDEO_STREAM_INFO_STATS_RADIO_IN , sizeof(shared_mem_video_info_stats)); - return (shared_mem_video_info_stats*)retVal; + void *retVal = open_shared_mem_for_read(SHARED_MEM_VIDEO_FRAMES_STATS_RADIO_IN , sizeof(shared_mem_video_frames_stats)); + return (shared_mem_video_frames_stats*)retVal; } -shared_mem_video_info_stats* shared_mem_video_info_stats_radio_in_open_for_write() +shared_mem_video_frames_stats* shared_mem_video_frames_stats_radio_in_open_for_write() { - void *retVal = open_shared_mem_for_write(SHARED_MEM_VIDEO_STREAM_INFO_STATS_RADIO_IN , sizeof(shared_mem_video_info_stats)); - return (shared_mem_video_info_stats*)retVal; + void *retVal = open_shared_mem_for_write(SHARED_MEM_VIDEO_FRAMES_STATS_RADIO_IN , sizeof(shared_mem_video_frames_stats)); + return (shared_mem_video_frames_stats*)retVal; } -void shared_mem_video_info_stats_radio_in_close(shared_mem_video_info_stats* pAddress) +void shared_mem_video_frames_stats_radio_in_close(shared_mem_video_frames_stats* pAddress) { if ( NULL != pAddress ) - munmap(pAddress, sizeof(shared_mem_video_info_stats)); + munmap(pAddress, sizeof(shared_mem_video_frames_stats)); } -shared_mem_video_info_stats* shared_mem_video_info_stats_radio_out_open_for_read() +shared_mem_video_frames_stats* shared_mem_video_frames_stats_radio_out_open_for_read() { - void *retVal = open_shared_mem_for_read(SHARED_MEM_VIDEO_STREAM_INFO_STATS_RADIO_OUT , sizeof(shared_mem_video_info_stats)); - return (shared_mem_video_info_stats*)retVal; + void *retVal = open_shared_mem_for_read(SHARED_MEM_VIDEO_FRAMES_STATS_RADIO_OUT , sizeof(shared_mem_video_frames_stats)); + return (shared_mem_video_frames_stats*)retVal; } -shared_mem_video_info_stats* shared_mem_video_info_stats_radio_out_open_for_write() +shared_mem_video_frames_stats* shared_mem_video_frames_stats_radio_out_open_for_write() { - void *retVal = open_shared_mem_for_write(SHARED_MEM_VIDEO_STREAM_INFO_STATS_RADIO_OUT , sizeof(shared_mem_video_info_stats)); - return (shared_mem_video_info_stats*)retVal; + void *retVal = open_shared_mem_for_write(SHARED_MEM_VIDEO_FRAMES_STATS_RADIO_OUT , sizeof(shared_mem_video_frames_stats)); + return (shared_mem_video_frames_stats*)retVal; } -void shared_mem_video_info_stats_radio_out_close(shared_mem_video_info_stats* pAddress) +void shared_mem_video_frames_stats_radio_out_close(shared_mem_video_frames_stats* pAddress) { if ( NULL != pAddress ) - munmap(pAddress, sizeof(shared_mem_video_info_stats)); + munmap(pAddress, sizeof(shared_mem_video_frames_stats)); } shared_mem_video_link_graphs* shared_mem_video_link_graphs_open_for_read() @@ -288,28 +288,26 @@ void shared_mem_rc_upstream_frame_close(t_packet_header_rc_full_frame_upstream* //shm_unlink(SHARED_MEM_RC_UPSTREAM_FRAME); } -void update_shared_mem_video_info_stats(shared_mem_video_info_stats* pSMVIStats, u32 uTimeNow) +void update_shared_mem_video_frames_stats(shared_mem_video_frames_stats* pSMVIStats, u32 uTimeNow) { if ( NULL == pSMVIStats ) return; - pSMVIStats->uTimeLastUpdate = uTimeNow; + pSMVIStats->uLastTimeStatsUpdate = uTimeNow; u32 uMinFrameTime = MAX_U32; u32 uMaxFrameTime = 0; for( int i=0; iuFramesDuration[i] & 0x7F) > uMaxFrameTime ) - uMaxFrameTime = (pSMVIStats->uFramesDuration[i] & 0x7F); - if ( (pSMVIStats->uFramesDuration[i] & 0x7F) < uMinFrameTime ) - uMinFrameTime = (pSMVIStats->uFramesDuration[i] & 0x7F); + if ( (pSMVIStats->uFramesTypesAndDuration[i] & 0x3F) > uMaxFrameTime ) + uMaxFrameTime = (pSMVIStats->uFramesTypesAndDuration[i] & 0x3F); + if ( (pSMVIStats->uFramesTypesAndDuration[i] & 0x3F) < uMinFrameTime ) + uMinFrameTime = (pSMVIStats->uFramesTypesAndDuration[i] & 0x3F); } pSMVIStats->uAverageFPS = 0; pSMVIStats->uAverageFrameTime = 0; - pSMVIStats->uAverageFrameSize = 0; - pSMVIStats->uAveragePFrameSize = 0; u32 uSumTime = 0; u32 uSumSizes = 0; @@ -318,19 +316,18 @@ void update_shared_mem_video_info_stats(shared_mem_video_info_stats* pSMVIStats, u32 uSumFramesPCount = 0; for( int i=0; iuFramesDuration[i] & 0x7F) == 0 ) + // Ignore non P frames + if ( (pSMVIStats->uFramesTypesAndDuration[i] & 0xC0) != 0 ) continue; - if ( pSMVIStats->uFramesTypesAndSizes[i] & (1<<7) ) + if ( pSMVIStats->uFramesSizes[i] == 0 ) continue; - else - { - uSumSizesP += ((u32)(pSMVIStats->uFramesTypesAndSizes[i] & 0x7F)) * 8000; - uSumFramesPCount++; - } - uSumTime += (pSMVIStats->uFramesDuration[i] & 0x7F); - uSumSizes += ((u32)(pSMVIStats->uFramesTypesAndSizes[i] & 0x7F)) * 8000; + uSumSizesP += ((u32)(pSMVIStats->uFramesSizes[i]) * 8000); + uSumFramesPCount++; + + uSumTime += (pSMVIStats->uFramesTypesAndDuration[i] & 0x3F); + uSumSizes += ((u32)(pSMVIStats->uFramesSizes[i]) * 8000); uSumFramesCount++; } @@ -340,26 +337,81 @@ void update_shared_mem_video_info_stats(shared_mem_video_info_stats* pSMVIStats, pSMVIStats->uAverageFrameTime = uSumTime / uSumFramesCount; } - if ( (0 < uSumFramesCount) && (0 < uSumSizes) ) - pSMVIStats->uAverageFrameSize = uSumSizes / uSumFramesCount; - if ( (0 < uSumFramesPCount) && (0 < uSumSizesP) ) - pSMVIStats->uAveragePFrameSize = uSumSizesP / uSumFramesPCount; - pSMVIStats->uMaxFrameDeltaTime = 0; for( int i=0; iuFramesDuration[i] & 0x7F) == 0 ) + if ( (pSMVIStats->uFramesTypesAndDuration[i] & 0x3F) == 0 ) continue; - if ( (pSMVIStats->uFramesDuration[i] & 0x7F) > pSMVIStats->uAverageFrameTime ) - if ( (pSMVIStats->uFramesDuration[i] & 0x7F) - pSMVIStats->uAverageFrameTime > pSMVIStats->uMaxFrameDeltaTime ) - pSMVIStats->uMaxFrameDeltaTime = (pSMVIStats->uFramesDuration[i] & 0x7F) - pSMVIStats->uAverageFrameTime; + if ( (pSMVIStats->uFramesTypesAndDuration[i] & 0x3F) > pSMVIStats->uAverageFrameTime ) + if ( (pSMVIStats->uFramesTypesAndDuration[i] & 0x3F) - pSMVIStats->uAverageFrameTime > pSMVIStats->uMaxFrameDeltaTime ) + pSMVIStats->uMaxFrameDeltaTime = (pSMVIStats->uFramesTypesAndDuration[i] & 0x3F) - pSMVIStats->uAverageFrameTime; //if ( pSMVIStats->uFramesTimes[i] < pSMVIStats->uAverageFrameTime ) //if ( pSMVIStats->uAverageFrameTime - pSMVIStats->uFramesTimes[i] > pSMVIStats->uMaxFrameDeltaTime ) // pSMVIStats->uMaxFrameDeltaTime = pSMVIStats->uAverageFrameTime - pSMVIStats->uFramesTimes[i]; } } +void update_shared_mem_video_frames_stats_on_new_frame(shared_mem_video_frames_stats* pSMVFStats, u32 uLastFrameSizeBytes, int iFrameType, int iDetectedSlices, int iDetectedFPS, u32 uTimeNow) +{ + if ( NULL == pSMVFStats ) + return; + + u32 uLastFrameDuration = 0; + if ( 0 != pSMVFStats->uLastFrameTime ) + uLastFrameDuration = uTimeNow - pSMVFStats->uLastFrameTime; + pSMVFStats->uLastFrameTime = uTimeNow; + + if ( uLastFrameDuration > 63 ) + uLastFrameDuration = 63; + if ( uLastFrameDuration < 1 ) + uLastFrameDuration = 1; + + u32 uLastFrameSizeKb = uLastFrameSizeBytes/1000; // transform from bytes to kbytes + if ( uLastFrameSizeKb > 255 ) + uLastFrameSizeKb = 255; // kbytes + + u32 uFrameIndex = pSMVFStats->uLastFrameIndex; + pSMVFStats->uFramesTypesAndDuration[uFrameIndex] = (pSMVFStats->uFramesTypesAndDuration[uFrameIndex] & VIDEO_FRAME_TYPE_MASK) | (uLastFrameDuration & VIDEO_FRAME_DURATION_MASK); + pSMVFStats->uFramesSizes[uFrameIndex] = (u8)uLastFrameSizeKb; + + if ( pSMVFStats->uFramesSizes[uFrameIndex] > 0 ) + { + int iLastFrameType = (pSMVFStats->uFramesTypesAndDuration[uFrameIndex] & 0xC0) >> 6; + if ( iLastFrameType == 1 ) + { + // IFrame + if ( 0 == pSMVFStats->uAverageIFrameSizeBytes ) + pSMVFStats->uAverageIFrameSizeBytes = uLastFrameSizeBytes; + else + pSMVFStats->uAverageIFrameSizeBytes = (pSMVFStats->uAverageIFrameSizeBytes * 3 + uLastFrameSizeBytes) / 4; + } + else if ( iLastFrameType == 0 ) + { + // PFrame + if ( 0 == pSMVFStats->uAveragePFrameSizeBytes ) + pSMVFStats->uAveragePFrameSizeBytes = uLastFrameSizeBytes; + else + pSMVFStats->uAveragePFrameSizeBytes = (pSMVFStats->uAveragePFrameSizeBytes * 5 + uLastFrameSizeBytes) / 6; + } + } + + uFrameIndex++; + uFrameIndex = (uFrameIndex % MAX_FRAMES_SAMPLES); + pSMVFStats->uLastFrameIndex = uFrameIndex; + + if ( iFrameType == 1 ) + pSMVFStats->uFramesTypesAndDuration[uFrameIndex] = 0; + else if ( iFrameType == 5 ) + pSMVFStats->uFramesTypesAndDuration[uFrameIndex] = 1<<6; + else + pSMVFStats->uFramesTypesAndDuration[uFrameIndex] = 2<<6; + pSMVFStats->uFramesSizes[uFrameIndex] = 0; + + pSMVFStats->uDetectedKeyframeIntervalMs = 0; + pSMVFStats->uDetectedFPS = (u32)iDetectedFPS; + pSMVFStats->uDetectedSlices = (u32)iDetectedSlices; +} void reset_radio_tx_timers(type_radio_tx_timers* pRadioTxTimers) { diff --git a/code/base/shared_mem.h b/code/base/shared_mem.h index f69daba4..592bc4ec 100644 --- a/code/base/shared_mem.h +++ b/code/base/shared_mem.h @@ -12,9 +12,9 @@ #define SHARED_MEM_RADIO_STATS "/SYSTEM_SHARED_MEM_RUBY_RADIO_STATS" #define SHARED_MEM_RADIO_STATS_RX_HIST "/SYSTEM_SHARED_MEM_RUBY_RADIO_STATS_RX_HIST" -#define SHARED_MEM_VIDEO_STREAM_INFO_STATS "/SYSTEM_SHARED_MEM_STATION_VIDEO_STREAM_INFO" -#define SHARED_MEM_VIDEO_STREAM_INFO_STATS_RADIO_IN "/SYSTEM_SHARED_MEM_STATION_VIDEO_STREAM_INFO_RADIO_IN" -#define SHARED_MEM_VIDEO_STREAM_INFO_STATS_RADIO_OUT "/SYSTEM_SHARED_MEM_STATION_VIDEO_STREAM_INFO_RADIO_OUT" +#define SHARED_MEM_VIDEO_FRAMES_STATS "/SYSTEM_SHARED_MEM_STATION_VIDEO_STREAM_INFO" +#define SHARED_MEM_VIDEO_FRAMES_STATS_RADIO_IN "/SYSTEM_SHARED_MEM_STATION_VIDEO_STREAM_INFO_RADIO_IN" +#define SHARED_MEM_VIDEO_FRAMES_STATS_RADIO_OUT "/SYSTEM_SHARED_MEM_STATION_VIDEO_STREAM_INFO_RADIO_OUT" #define SHARED_MEM_VIDEO_LINK_GRAPHS "/SYSTEM_SHARED_MEM_STATION_VIDEO_LINK_GRAPHS" #define SHARED_MEM_RC_DOWNLOAD_INFO "R_SHARED_MEM_VEHICLE_RC_DOWNLOAD_INFO" #define SHARED_MEM_RC_UPSTREAM_FRAME "R_SHARED_MEM_RC_UPSTREAM_FRAME" @@ -122,30 +122,37 @@ typedef struct } ALIGN_STRUCT_SPEC_INFO shared_mem_dev_video_bitrate_history; -#define MAX_FRAMES_SAMPLES 60 - +#define MAX_FRAMES_SAMPLES 121 +#define VIDEO_FRAME_TYPE_MASK 0xC0 +#define VIDEO_FRAME_DURATION_MASK 0x3F typedef struct { - u32 uTimeLastUpdate; // Last time statistics where updated - u8 uFramesDuration[MAX_FRAMES_SAMPLES]; // highest bit: 1 if keyframe interval was adjusted. lower 7 bits: frame duration in ms - u8 uFramesTypesAndSizes[MAX_FRAMES_SAMPLES]; // Frame type and size in kbytes (frame type: highest bit: 0 regular, 1 keframe; lower 7 bits: frame size in kbytes) - u32 uLastIndex; // Increases on each video frame detected + u32 uLastTimeStatsUpdate; // Last time statistics where updated + u32 uLastFrameIndex; // Increases on each video frame de tected + u32 uLastFrameTime; + u8 uFramesTypesAndDuration[MAX_FRAMES_SAMPLES]; + // highest 2 bits: 0-pframe, 1-iframe, 2-other frame + // lower 6 bits: frame duration in ms + u8 uFramesSizes[MAX_FRAMES_SAMPLES]; + // Frame size in kbytes // Computed on H264 parser u32 uDetectedFPS; u32 uDetectedSlices; - + u32 uDetectedKeyframeIntervalMs; + + // Computed on each frame update + u32 uAverageIFrameSizeBytes; + u32 uAveragePFrameSizeBytes; + // Computed on OSD side u32 uAverageFPS; u32 uAverageFrameTime; - u32 uAverageFrameSize; // in bits - u32 uAveragePFrameSize; // in bits u32 uMaxFrameDeltaTime; - u16 uKeyframeIntervalMs; u32 uExtraValue1; u32 uExtraValue2; -} ALIGN_STRUCT_SPEC_INFO shared_mem_video_info_stats; +} ALIGN_STRUCT_SPEC_INFO shared_mem_video_frames_stats; #define MAX_RADIO_TX_TIMES_HISTORY_INTERVALS 50 @@ -191,17 +198,17 @@ shared_mem_radio_stats_rx_hist* shared_mem_radio_stats_rx_hist_open_for_read(); shared_mem_radio_stats_rx_hist* shared_mem_radio_stats_rx_hist_open_for_write(); void shared_mem_radio_stats_rx_hist_close(shared_mem_radio_stats_rx_hist* pAddress); -shared_mem_video_info_stats* shared_mem_video_info_stats_open_for_read(); -shared_mem_video_info_stats* shared_mem_video_info_stats_open_for_write(); -void shared_mem_video_info_stats_close(shared_mem_video_info_stats* pAddress); +shared_mem_video_frames_stats* shared_mem_video_frames_stats_open_for_read(); +shared_mem_video_frames_stats* shared_mem_video_frames_stats_open_for_write(); +void shared_mem_video_frames_stats_close(shared_mem_video_frames_stats* pAddress); -shared_mem_video_info_stats* shared_mem_video_info_stats_radio_in_open_for_read(); -shared_mem_video_info_stats* shared_mem_video_info_stats_radio_in_open_for_write(); -void shared_mem_video_info_stats_radio_in_close(shared_mem_video_info_stats* pAddress); +shared_mem_video_frames_stats* shared_mem_video_frames_stats_radio_in_open_for_read(); +shared_mem_video_frames_stats* shared_mem_video_frames_stats_radio_in_open_for_write(); +void shared_mem_video_frames_stats_radio_in_close(shared_mem_video_frames_stats* pAddress); -shared_mem_video_info_stats* shared_mem_video_info_stats_radio_out_open_for_read(); -shared_mem_video_info_stats* shared_mem_video_info_stats_radio_out_open_for_write(); -void shared_mem_video_info_stats_radio_out_close(shared_mem_video_info_stats* pAddress); +shared_mem_video_frames_stats* shared_mem_video_frames_stats_radio_out_open_for_read(); +shared_mem_video_frames_stats* shared_mem_video_frames_stats_radio_out_open_for_write(); +void shared_mem_video_frames_stats_radio_out_close(shared_mem_video_frames_stats* pAddress); shared_mem_video_link_graphs* shared_mem_video_link_graphs_open_for_read(); @@ -216,7 +223,8 @@ t_packet_header_rc_full_frame_upstream* shared_mem_rc_upstream_frame_open_read() t_packet_header_rc_full_frame_upstream* shared_mem_rc_upstream_frame_open_write(); void shared_mem_rc_upstream_frame_close(t_packet_header_rc_full_frame_upstream* pRCFrame); -void update_shared_mem_video_info_stats(shared_mem_video_info_stats* pSMVIStats, u32 uTimeNow); +void update_shared_mem_video_frames_stats(shared_mem_video_frames_stats* pSMVIStats, u32 uTimeNow); +void update_shared_mem_video_frames_stats_on_new_frame(shared_mem_video_frames_stats* pSMVFStats, u32 uLastFrameSizeBytes, int iFrameType, int iDetectedSlices, int iDetectedFPS, u32 uTimeNow); void reset_radio_tx_timers(type_radio_tx_timers* pRadioTxTimers); diff --git a/code/base/shared_mem_controller_only.c b/code/base/shared_mem_controller_only.c index c556f05f..284b9adb 100644 --- a/code/base/shared_mem_controller_only.c +++ b/code/base/shared_mem_controller_only.c @@ -223,20 +223,6 @@ shared_mem_video_stream_stats* get_shared_mem_video_stream_stats_for_vehicle(sha return NULL; } -shared_mem_video_stream_stats_history_rx_processors* shared_mem_video_stream_stats_history_rx_processors_open(int readOnly) -{ - void *retVal = open_shared_mem(SHARED_MEM_VIDEO_STREAM_STATS_HISTORY, sizeof(shared_mem_video_stream_stats_history_rx_processors), readOnly); - shared_mem_video_stream_stats_history_rx_processors *tretval = (shared_mem_video_stream_stats_history_rx_processors*)retVal; - return tretval; -} - -void shared_mem_video_stream_stats_history_rx_processors_close(shared_mem_video_stream_stats_history_rx_processors* pAddress) -{ - if ( NULL != pAddress ) - munmap(pAddress, sizeof(shared_mem_video_stream_stats_history_rx_processors)); - //shm_unlink(SHARED_MEM_VIDEO_STREAM_STATS_HISTORY); -} - shared_mem_radio_rx_queue_info* shared_mem_radio_rx_queue_info_open_for_read() { void *retVal = open_shared_mem(SHARED_MEM_RADIO_RX_QUEUE_INFO_STATS, sizeof(shared_mem_radio_rx_queue_info), 1); diff --git a/code/base/shared_mem_controller_only.h b/code/base/shared_mem_controller_only.h index 1115c036..794c33d1 100644 --- a/code/base/shared_mem_controller_only.h +++ b/code/base/shared_mem_controller_only.h @@ -7,7 +7,6 @@ #define SHARED_MEM_CONTROLLER_RADIO_INTERFACES_RX_GRAPHS "R_SHARED_MEM_CONTROLLER_RADIO_INTERFACES_RX_GRAPHS" #define SHARED_MEM_AUDIO_DECODE_STATS "/SYSTEM_SHARED_MEM_AUDIO_DECODE_STATS" #define SHARED_MEM_VIDEO_STREAM_STATS "/SYSTEM_SHARED_MEM_STATION_VIDEO_STREAM_STATS" -#define SHARED_MEM_VIDEO_STREAM_STATS_HISTORY "/SYSTEM_SHARED_MEM_STATION_VIDEO_STREAM_STATS_HISTORY" #define SHARED_MEM_RADIO_RX_QUEUE_INFO_STATS "/SYSTEM_SHARED_MEM_RADIO_RX_QUEUE_STATS" #define MAX_HISTORY_VIDEO_INTERVALS 50 @@ -80,33 +79,6 @@ typedef struct shared_mem_video_stream_stats video_streams[MAX_VIDEO_PROCESSORS]; } ALIGN_STRUCT_SPEC_INFO shared_mem_video_stream_stats_rx_processors; -typedef struct -{ - u32 uVehicleId; - u8 uVideoStreamIndex; - u8 outputHistoryIntervalMs; - u8 outputHistoryReceivedVideoPackets[MAX_HISTORY_VIDEO_INTERVALS]; - u8 outputHistoryReceivedVideoRetransmittedPackets[MAX_HISTORY_VIDEO_INTERVALS]; - - u8 outputHistoryMaxGoodBlocksPendingPerPeriod[MAX_HISTORY_VIDEO_INTERVALS]; - u8 outputHistoryBlocksOkPerPeriod[MAX_HISTORY_VIDEO_INTERVALS]; - u8 outputHistoryBlocksReconstructedPerPeriod[MAX_HISTORY_VIDEO_INTERVALS]; - u8 outputHistoryMaxECPacketsUsedPerPeriod[MAX_HISTORY_VIDEO_INTERVALS]; - u8 outputHistoryBlocksBadPerPeriod[MAX_HISTORY_VIDEO_INTERVALS]; - u8 outputHistoryBlocksMissingPerPeriod[MAX_HISTORY_VIDEO_INTERVALS]; - u8 outputHistoryBlocksRetrasmitedPerPeriod[MAX_HISTORY_VIDEO_INTERVALS]; - u8 outputHistoryBlocksMaxPacketsGapPerPeriod[MAX_HISTORY_VIDEO_INTERVALS]; - u8 outputHistoryPacketsRetrasmitedPerPeriod[MAX_HISTORY_VIDEO_INTERVALS]; - u8 outputHistoryBlocksDiscardedPerPeriod[MAX_HISTORY_VIDEO_INTERVALS]; - u16 missingTotalPacketsAtPeriod[MAX_HISTORY_VIDEO_INTERVALS]; - u16 totalCurrentlyMissingPackets; -} ALIGN_STRUCT_SPEC_INFO shared_mem_video_stream_stats_history; - -typedef struct -{ - shared_mem_video_stream_stats_history video_streams[MAX_VIDEO_PROCESSORS]; -} ALIGN_STRUCT_SPEC_INFO shared_mem_video_stream_stats_history_rx_processors; - #define MAX_CONTROLLER_ADAPTIVE_VIDEO_INFO_INTERVALS 80 // sampled every 40 ms #define CONTROLLER_ADAPTIVE_VIDEO_SAMPLE_INTERVAL 40 @@ -204,9 +176,6 @@ shared_mem_video_stream_stats_rx_processors* shared_mem_video_stream_stats_rx_pr void shared_mem_video_stream_stats_rx_processors_close(shared_mem_video_stream_stats_rx_processors* pAddress); shared_mem_video_stream_stats* get_shared_mem_video_stream_stats_for_vehicle(shared_mem_video_stream_stats_rx_processors* pSM, u32 uVehicleId); -shared_mem_video_stream_stats_history_rx_processors* shared_mem_video_stream_stats_history_rx_processors_open(int readOnly); -void shared_mem_video_stream_stats_history_rx_processors_close(shared_mem_video_stream_stats_history_rx_processors* pAddress); - shared_mem_audio_decode_stats* shared_mem_controller_audio_decode_stats_open_for_read(); shared_mem_audio_decode_stats* shared_mem_controller_audio_decode_stats_open_for_write(); void shared_mem_controller_audio_decode_stats_close(shared_mem_audio_decode_stats* pAddress); diff --git a/code/base/shared_mem_radio.h b/code/base/shared_mem_radio.h index fd0f4868..4b93ff7d 100644 --- a/code/base/shared_mem_radio.h +++ b/code/base/shared_mem_radio.h @@ -223,8 +223,8 @@ typedef struct u32 all_downlinks_tx_time_per_sec; u32 tmp_all_downlinks_tx_time_per_sec; - u32 timeLastRxPacket; + u32 uLastTimeReceivedAckFromAVehicle; int iMaxRxQuality; shared_mem_radio_stats_stream radio_streams[MAX_CONCURENT_VEHICLES][MAX_RADIO_STREAMS]; diff --git a/code/base/tx_powers.cpp b/code/base/tx_powers.cpp new file mode 100644 index 00000000..f1d9cf65 --- /dev/null +++ b/code/base/tx_powers.cpp @@ -0,0 +1,285 @@ +/* + Ruby Licence + Copyright (c) 2024 Petru Soroaga + All rights reserved. + + Redistribution and use in source and/or binary forms, with or without + modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Copyright info and developer info must be preserved as is in the user + interface, additions could be made to that info. + * Neither the name of the organization nor the + names of its contributors may be used to endorse or promote products + derived from this software without specific prior written permission. + * Military use is not permited. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE AUTHOR (PETRU SOROAGA) BE LIABLE FOR ANY + DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#include "base.h" +#include "config.h" +#include "hardware.h" +#include "tx_powers.h" +#include + +/* +static int s_iTxBoosterGainTable4W[][2] = +{ + {2, 100}, + {5, 230}, + {10, 420}, + {20, 800}, + {30, 1100}, + {40, 1300}, + {50, 1400}, + {60, 1500}, + {70, 1600}, + {80, 1700}, + {100, 4000} +}; +*/ + +static int s_iRawTxRadioValues[] = {1,5,10,15,20,23,26,30,35,40,45,50,53,56,60,63,65,68,70}; + +static int s_iTxUIPowerLevelsMw[] = +{ 1, 5, 10, 25, 50, 75, 100, + 150, 200, 250, 300, 350, 400, 450, 500, 600, 700, 800, 900, 1000}; + +static int s_iTxRawPowerLevelMeasurementsValues[] = + { 1, 10, 20, 30, 40, 45, 50, 53, 56, 60, 63, 68, 70}; +//------------------------------------------------------------------------ + +static int s_iTxInfo722N[] = + { 1, 1, 2, 3, 10, 25, 35, 60, 80, 90, 0, 0, 0}; +static int s_iTxInfoBlueStick[] = + { 1, 2, 4, 8, 28, 50, 80, 110, 280, 1000, 0, 0, 0}; +static int s_iTxInfoAWUS036NH[] = + { 1, 10, 20, 30, 40, 50, 60, 0, 0, 0, 0, 0, 0}; +static int s_iTxInfoAWUS036NHA[] = + { 1, 1, 2, 6, 17, 70, 120, 180, 215, 310, 460, 0, 0}; + +// { 1, 10, 20, 30, 40, 45, 50, 53, 56, 60, 63, 68, 70}; +//------------------------------------------------------------------------ +static int s_iTxInfo58Generic[] = + { 1, 5, 17, 50, 150, 170, 190, 210, 261, 310, 0, 0, 0}; +static int s_iTxInfoAWUS036ACH[] = + { 1, 2, 5, 20, 50, 90, 160, 250, 300, 420, 500, 0, 0}; +static int s_iTxInfoASUSUSB56[] = + { 1, 4, 13, 42, 116, 190, 280, 360, 420, 490, 540, 0, 0}; // measured 08.dec.2024, ruby 10.1 +static int s_iTxInfoRTLDualAnt[] = + { 1, 1, 2, 4, 15, 25, 40, 45, 55, 70, 80, 80, 0}; // measured 23.dec.2024, ruby 10.1 +static int s_iTxInfoAli1W[] = + { 1, 1, 2, 5, 10, 20, 30, 50, 100, 300, 450, 0, 0}; +static int s_iTxInfoA6100[] = + { 1, 1, 3, 10, 17, 19, 22, 23, 25, 0, 0, 0, 0}; // measured 08.dec.2024, ruby 10.1 +static int s_iTxInfoAWUS036ACS[] = + { 1, 1, 2, 3, 10, 25, 35, 50, 60, 90, 110, 0, 0}; +static int s_iTxInfoArcherT2UP[] = + { 1, 3, 10, 25, 55, 75, 110, 120, 140, 150, 0, 0, 0}; + +// { 1, 10, 20, 30, 40, 45, 50, 53, 56, 60, 63, 68, 70}; +//------------------------------------------------------------------------ +static int s_iTxInfoRTL8812EU[] = + { 6, 7, 15, 45, 110, 160, 230, 270, 320, 380, 430, 500, 550}; // measured 08.dec.2024, ruby 10.1 + + +// { 1, 10, 20, 30, 40, 45, 50, 53, 56, 60, 63, 68, 70}; +//------------------------------------------------------------------------ +static int s_iTxInfoOIPCUSight[] = + { 550, 600, 650, 670, 0, 0, 0, 0, 0, 0, 0, 0, 0}; // measured 23.dec.2024, ruby 10.1 + + + +bool _tx_powers_is_card_serial_radio(int iDriverType, int iCardModel) +{ + if ( (iDriverType == RADIO_HW_DRIVER_SERIAL_SIK) || (iDriverType == RADIO_HW_DRIVER_SERIAL) ) + return true; + if ( (iCardModel == CARD_MODEL_SIK_RADIO) || (iCardModel == CARD_MODEL_SERIAL_RADIO) || (iCardModel == CARD_MODEL_SERIAL_RADIO_ELRS) ) + return true; + return false; +} + +const int* _tx_powers_get_mw_table_for_card(int iDriverType, int iCardModel) +{ + int* piMwPowers = s_iTxInfo58Generic; + switch (iCardModel) + { + case CARD_MODEL_TPLINK722N: piMwPowers = s_iTxInfo722N; break; + case CARD_MODEL_ATHEROS_GENERIC: piMwPowers = s_iTxInfo722N; break; + case CARD_MODEL_BLUE_STICK: piMwPowers = s_iTxInfoBlueStick; break; + case CARD_MODEL_ALFA_AWUS036NH: piMwPowers = s_iTxInfoAWUS036NH; break; + case CARD_MODEL_ALFA_AWUS036NHA: piMwPowers = s_iTxInfoAWUS036NHA; break; + + case CARD_MODEL_RTL8812AU_GENERIC: piMwPowers = s_iTxInfoRTLDualAnt; break; + case CARD_MODEL_RTL8812AU_DUAL_ANTENNA: piMwPowers = s_iTxInfoRTLDualAnt; break; + case CARD_MODEL_ASUS_AC56: piMwPowers = s_iTxInfoASUSUSB56; break; + case CARD_MODEL_ALFA_AWUS036ACH: piMwPowers = s_iTxInfoAWUS036ACH; break; + case CARD_MODEL_ALFA_AWUS036ACS: piMwPowers = s_iTxInfoAWUS036ACS; break; + case CARD_MODEL_ZIPRAY: piMwPowers = s_iTxInfoAli1W; break; + case CARD_MODEL_NETGEAR_A6100: piMwPowers = s_iTxInfoA6100; break; + case CARD_MODEL_TENDA_U12: piMwPowers = s_iTxInfo58Generic; break; + case CARD_MODEL_ARCHER_T2UPLUS: piMwPowers = s_iTxInfoArcherT2UP; break; + case CARD_MODEL_RTL8814AU: piMwPowers = s_iTxInfo58Generic; break; + case CARD_MODEL_RTL8812AU_OIPC_USIGHT: piMwPowers = s_iTxInfoOIPCUSight; break; + + case CARD_MODEL_BLUE_8812EU: piMwPowers = s_iTxInfoRTL8812EU; break; + } + return piMwPowers; +} + +const int* tx_powers_get_raw_radio_power_values(int* piOutputCount) +{ + if ( NULL != piOutputCount ) + *piOutputCount = sizeof(s_iRawTxRadioValues)/sizeof(s_iRawTxRadioValues[0]); + return s_iRawTxRadioValues; +} + +const int* tx_powers_get_ui_levels_mw(int* piOutputCount) +{ + if ( NULL != piOutputCount ) + *piOutputCount = sizeof(s_iTxUIPowerLevelsMw)/sizeof(s_iTxUIPowerLevelsMw[0]); + return s_iTxUIPowerLevelsMw; +} + +const int* tx_powers_get_raw_measurement_intervals(int* piOutputCount) +{ + if ( NULL != piOutputCount ) + *piOutputCount = sizeof(s_iTxRawPowerLevelMeasurementsValues)/sizeof(s_iTxRawPowerLevelMeasurementsValues[0]); + return s_iTxRawPowerLevelMeasurementsValues; +} + +const int* tx_powers_get_mw_measured_values_for_card(int iDriverType, int iCardModel, int* piOutputCount) +{ + const int* piMwPowers = _tx_powers_get_mw_table_for_card(iDriverType, iCardModel); + int iCount = sizeof(s_iTxRawPowerLevelMeasurementsValues)/sizeof(s_iTxRawPowerLevelMeasurementsValues[0]); + if ( NULL != piOutputCount ) + *piOutputCount = iCount; + return piMwPowers; +} + +int tx_powers_get_max_usable_power_mw_for_card(int iDriverType, int iCardModel) +{ + if ( _tx_powers_is_card_serial_radio(iDriverType, iCardModel) ) + return 100; + const int* piMwPowers = _tx_powers_get_mw_table_for_card(iDriverType, iCardModel); + int iCount = sizeof(s_iTxRawPowerLevelMeasurementsValues)/sizeof(s_iTxRawPowerLevelMeasurementsValues[0]); + for( int i=0; i= s_iTxRawPowerLevelMeasurementsValues[i] ) + if ( iRawPower <= s_iTxRawPowerLevelMeasurementsValues[i+1] ) + { + return piMwPowers[i] + ((piMwPowers[i+1] - piMwPowers[i]) * (iRawPower - s_iTxRawPowerLevelMeasurementsValues[i])) / (s_iTxRawPowerLevelMeasurementsValues[i+1] - s_iTxRawPowerLevelMeasurementsValues[i]); + } + } + + return piMwPowers[0]; +} + +int tx_powers_convert_mw_to_raw(int iDriverType, int iCardModel, int imWPower) +{ + if ( _tx_powers_is_card_serial_radio(iDriverType, iCardModel) ) + return 10*log10((float)imWPower); + const int* piMwPowers = _tx_powers_get_mw_table_for_card(iDriverType, iCardModel); + int iCount = sizeof(s_iTxRawPowerLevelMeasurementsValues)/sizeof(s_iTxRawPowerLevelMeasurementsValues[0]); + + if ( imWPower <= piMwPowers[0] ) + { + int iRaw = (s_iTxRawPowerLevelMeasurementsValues[0]*imWPower)/piMwPowers[0]; + if ( iRaw < 1 ) + iRaw = 1; + return iRaw; + } + for( int i=0; i= piMwPowers[i] ) + if ( imWPower <= piMwPowers[i+1] ) + { + return s_iTxRawPowerLevelMeasurementsValues[i] + ((s_iTxRawPowerLevelMeasurementsValues[i+1] - s_iTxRawPowerLevelMeasurementsValues[i]) * (imWPower - piMwPowers[i])) / (piMwPowers[i+1] - piMwPowers[i]); + } + } + + return s_iTxRawPowerLevelMeasurementsValues[0]; +} + +int tx_powers_get_max_usable_power_mw_for_model(Model* pModel) +{ + if ( NULL == pModel ) + return 1; + + // Select the max mw power for any present card + int iMaxPowerMw = 10; + for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) + { + int iDriver = (pModel->radioInterfacesParams.interface_radiotype_and_driver[i] >> 8) & 0xFF; + int iCardModel = pModel->radioInterfacesParams.interface_card_model[i]; + if ( _tx_powers_is_card_serial_radio(iDriver, iCardModel) ) + continue; + int iPowerMaxRaw = tx_powers_get_max_usable_power_raw_for_card(iDriver, iCardModel); + int iPowerMw = tx_powers_convert_raw_to_mw(iDriver, iCardModel, iPowerMaxRaw); + if ( iPowerMw > iMaxPowerMw ) + iMaxPowerMw = iPowerMw; + } + return iMaxPowerMw; +} + +void tx_power_get_current_mw_powers_for_model(Model* pModel, int* piOutputArray) +{ + if ( (NULL == pModel) || (NULL == piOutputArray) ) + return; + + for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) + { + int iDriver = (pModel->radioInterfacesParams.interface_radiotype_and_driver[i] >> 8) & 0xFF; + int iCardModel = pModel->radioInterfacesParams.interface_card_model[i]; + piOutputArray[i] = tx_powers_convert_raw_to_mw(iDriver, iCardModel, pModel->radioInterfacesParams.interface_raw_power[i]); + } +} \ No newline at end of file diff --git a/code/base/tx_powers.h b/code/base/tx_powers.h new file mode 100644 index 00000000..b06162a2 --- /dev/null +++ b/code/base/tx_powers.h @@ -0,0 +1,20 @@ +#pragma once + +#include "hardware_radio.h" +#include "models.h" + +// Max deviation to show a value in ui as a standard tx value, in percentages +#define MAX_TX_POWER_UI_DEVIATION_FROM_STANDARD 12 + +const int* tx_powers_get_raw_radio_power_values(int* piOutputCount); +const int* tx_powers_get_ui_levels_mw(int* piOutputCount); +const int* tx_powers_get_raw_measurement_intervals(int* piOutputCount); +const int* tx_powers_get_mw_measured_values_for_card(int iDriverType, int iCardModel, int* piOutputCount); + +int tx_powers_get_max_usable_power_mw_for_card(int iDriverType, int iCardModel); +int tx_powers_get_max_usable_power_raw_for_card(int iDriverType, int iCardModel); +int tx_powers_convert_raw_to_mw(int iDriverType, int iCardModel, int iRawPower); +int tx_powers_convert_mw_to_raw(int iDriverType, int iCardModel, int imWPower); + +int tx_powers_get_max_usable_power_mw_for_model(Model* pModel); +void tx_power_get_current_mw_powers_for_model(Model* pModel, int* piOutputArray); diff --git a/code/base/utils.cpp b/code/base/utils.cpp index 5a1fafd0..e6f0eb63 100644 --- a/code/base/utils.cpp +++ b/code/base/utils.cpp @@ -10,9 +10,9 @@ * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - * Copyright info and developer info must be preserved as is in the user + * Copyright info and developer info must be preserved as is in the user interface, additions could be made to that info. - * Neither the name of the organization nor the + * Neither the name of the organization nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. * Military use is not permited. @@ -932,14 +932,6 @@ bool radio_utils_set_interface_frequency(Model* pModel, int iRadioIndex, int iAs iEndIndex = iRadioIndex; } - #if defined(HW_PLATFORM_RASPBERRY) - log_line("Setting frequency for Pi method"); - #elif defined(HW_PLATFORM_RADXA_ZERO3) - log_line("Setting frequency for Radxa method"); - #else - log_line("Setting frequency for OpenIPC/Radxa method"); - #endif - char cmd[128]; char szOutput[512]; bool failed = false; diff --git a/code/common/radio_stats.c b/code/common/radio_stats.c index 4230d24f..05746be7 100644 --- a/code/common/radio_stats.c +++ b/code/common/radio_stats.c @@ -186,7 +186,7 @@ void radio_stats_reset(shared_mem_radio_stats* pSMRS, int graphRefreshInterval) pSMRS->all_downlinks_tx_time_per_sec = 0; pSMRS->tmp_all_downlinks_tx_time_per_sec = 0; - + pSMRS->uLastTimeReceivedAckFromAVehicle = 0; pSMRS->iMaxRxQuality = 0; for( int i=0; iradio_interfaces[iInterfaceIndex].signalInfo.dbmValuesAll, &(pRadioHWInfo->runtimeInterfaceInfoRx.radioHwRxInfo.nDbmLast[0]), &(pRadioHWInfo->runtimeInterfaceInfoRx.radioHwRxInfo.nDbmLastChange[0]), &(pRadioHWInfo->runtimeInterfaceInfoRx.radioHwRxInfo.nDbmNoiseLast[0]), pRadioHWInfo->runtimeInterfaceInfoRx.radioHwRxInfo.nAntennaCount); - if ( iIsVideo ) + if ( iIsVideoData ) { pSMRS->radio_interfaces[iInterfaceIndex].lastRecvDataRateVideo = pRadioHWInfo->runtimeInterfaceInfoRx.radioHwRxInfo.nDataRateBPSMCS; _radio_stats_update_dbm_values_from_hw_interfaces( &pSMRS->radio_interfaces[iInterfaceIndex].signalInfo.dbmValuesVideo, &(pRadioHWInfo->runtimeInterfaceInfoRx.radioHwRxInfo.nDbmLast[0]), &(pRadioHWInfo->runtimeInterfaceInfoRx.radioHwRxInfo.nDbmLastChange[0]), &(pRadioHWInfo->runtimeInterfaceInfoRx.radioHwRxInfo.nDbmNoiseLast[0]), pRadioHWInfo->runtimeInterfaceInfoRx.radioHwRxInfo.nAntennaCount); @@ -1133,20 +1133,24 @@ int radio_stats_update_on_new_radio_packet_received(shared_mem_radio_stats* pSMR { t_packet_header* pPH = (t_packet_header*)pPacketBuffer; - // Radio_packet_index is 0 for version 7.6 or older, skip gap calculation - if ( 0 != pPH->radio_link_packet_index ) - if ( pSMRS->radio_interfaces[iInterfaceIndex].lastReceivedRadioLinkPacketIndex != MAX_U32 ) - if ( pPH->radio_link_packet_index > pSMRS->radio_interfaces[iInterfaceIndex].lastReceivedRadioLinkPacketIndex + 1 ) + if ( (pPH->packet_type & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) { - u32 uLost = pPH->radio_link_packet_index - pSMRS->radio_interfaces[iInterfaceIndex].lastReceivedRadioLinkPacketIndex - 1; - pSMRS->radio_interfaces[iInterfaceIndex].hist_tmp_rxPacketsLostCount += uLost; - pSMRS->radio_interfaces[iInterfaceIndex].totalRxPacketsLost += uLost; - if ( NULL != pSMRXStats ) - pSMRXStats->interfaces[iInterfaceIndex].tmp_rxPacketsLost += uLost; - s_uControllerLinkStats_tmpRecvLost[iInterfaceIndex] += uLost; - } + // Radio_packet_index is 0 for version 7.6 or older and missing for compressed packets, + // skip gap calculation + if ( 0 != pPH->radio_link_packet_index ) + if ( pSMRS->radio_interfaces[iInterfaceIndex].lastReceivedRadioLinkPacketIndex != MAX_U32 ) + if ( pPH->radio_link_packet_index > pSMRS->radio_interfaces[iInterfaceIndex].lastReceivedRadioLinkPacketIndex + 1 ) + { + u32 uLost = pPH->radio_link_packet_index - pSMRS->radio_interfaces[iInterfaceIndex].lastReceivedRadioLinkPacketIndex - 1; + pSMRS->radio_interfaces[iInterfaceIndex].hist_tmp_rxPacketsLostCount += uLost; + pSMRS->radio_interfaces[iInterfaceIndex].totalRxPacketsLost += uLost; + if ( NULL != pSMRXStats ) + pSMRXStats->interfaces[iInterfaceIndex].tmp_rxPacketsLost += uLost; + s_uControllerLinkStats_tmpRecvLost[iInterfaceIndex] += uLost; + } - pSMRS->radio_interfaces[iInterfaceIndex].lastReceivedRadioLinkPacketIndex = pPH->radio_link_packet_index; + pSMRS->radio_interfaces[iInterfaceIndex].lastReceivedRadioLinkPacketIndex = pPH->radio_link_packet_index; + } } } // End - Update history and good/bad/lost packets for interface @@ -1181,14 +1185,30 @@ int radio_stats_update_on_unique_packet_received(shared_mem_radio_stats* pSMRS, } t_packet_header* pPH = (t_packet_header*)pPacketBuffer; + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pPacketBuffer; int nRadioLinkId = pSMRS->radio_interfaces[iInterfaceIndex].assignedLocalRadioLinkId; - u32 uVehicleId = pPH->vehicle_id_src; - u32 uStreamPacketIndex = (pPH->stream_packet_idx) & PACKET_FLAGS_MASK_STREAM_PACKET_IDX; - u32 uStreamIndex = (pPH->stream_packet_idx)>>PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + u32 uVehicleId = 0; + u32 uStreamPacketIndex = 0; + u32 uStreamIndex = 0; + u8 uPacketType = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + uVehicleId = pPHC->vehicle_id_src; + uStreamPacketIndex = (pPHC->stream_packet_idx) & PACKET_FLAGS_MASK_STREAM_PACKET_IDX; + uStreamIndex = (pPHC->stream_packet_idx)>>PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + uPacketType = pPHC->packet_type; + } + else + { + uVehicleId = pPH->vehicle_id_src; + uStreamPacketIndex = (pPH->stream_packet_idx) & PACKET_FLAGS_MASK_STREAM_PACKET_IDX; + uStreamIndex = (pPH->stream_packet_idx)>>PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + uPacketType = pPH->packet_type; + } if ( uStreamIndex >= MAX_RADIO_STREAMS ) { - log_softerror_and_alarm("Received invalid stream id %u, packet index %u, packet type: %s", uStreamIndex, uStreamPacketIndex, str_get_packet_type(pPH->packet_type)); + log_softerror_and_alarm("Received invalid stream id %u, packet index %u, packet type: %s", uStreamIndex, uStreamPacketIndex, str_get_packet_type(uPacketType)); uStreamIndex = 0; } @@ -1250,20 +1270,16 @@ int radio_stats_update_on_unique_packet_received(shared_mem_radio_stats* pSMRS, if ( uStreamPacketIndex > pSMRS->radio_streams[iStreamsVehicleIndex][uStreamIndex].uLastRecvStreamPacketIndex ) { + if ( pSMRS->radio_streams[iStreamsVehicleIndex][uStreamIndex].uLastRecvStreamPacketIndex != 0 ) if ( uStreamPacketIndex > pSMRS->radio_streams[iStreamsVehicleIndex][uStreamIndex].uLastRecvStreamPacketIndex + 1 ) - { - //if ( uStreamIndex == STREAM_ID_TELEMETRY ) - // log_line("DEBUG missed telemetry packet for vehicle index %d: [vid: %u / %u]. last recv telem packet index: %u, now received telem pack index: %u", - // iStreamsVehicleIndex, pPH->vehicle_id_src, - // pSMRS->radio_streams[iStreamsVehicleIndex][uStreamIndex].uVehicleId, - // pSMRS->radio_streams[iStreamsVehicleIndex][uStreamIndex].uLastRecvStreamPacketIndex, uStreamPacketIndex); pSMRS->radio_streams[iStreamsVehicleIndex][uStreamIndex].iHasMissingStreamPacketsFlag = 1; - } pSMRS->radio_streams[iStreamsVehicleIndex][uStreamIndex].uLastRecvStreamPacketIndex = uStreamPacketIndex; } if ( 0 == pSMRS->radio_streams[iStreamsVehicleIndex][uStreamIndex].totalRxPackets ) - log_line("[RadioStats] Start receiving radio stream %d (%s) from VID %u", (int)uStreamIndex, str_get_radio_stream_name(uStreamIndex), uVehicleId); + log_line("[RadioStats] Start receiving radio stream %d (%s) from VID %u, packet module: %d, packet length: %d,%d, type: %s", + (int)uStreamIndex, str_get_radio_stream_name(uStreamIndex), uVehicleId, + (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE), pPH->total_length, iPacketLength, str_get_packet_type(pPH->packet_type)); pSMRS->radio_streams[iStreamsVehicleIndex][uStreamIndex].totalRxBytes += iPacketLength; pSMRS->radio_streams[iStreamsVehicleIndex][uStreamIndex].tmpRxBytes += iPacketLength; diff --git a/code/common/radio_stats.h b/code/common/radio_stats.h index e968d2ef..1cad88fa 100644 --- a/code/common/radio_stats.h +++ b/code/common/radio_stats.h @@ -26,7 +26,7 @@ void radio_stats_set_tx_card_for_radio_link(shared_mem_radio_stats* pSMRS, int i void radio_stats_set_card_current_frequency(shared_mem_radio_stats* pSMRS, int iRadioInterface, u32 freqKhz); void radio_stats_set_bad_data_on_current_rx_interval(shared_mem_radio_stats* pSMRS, shared_mem_radio_stats_interfaces_rx_graph* pSMRXStats, int iRadioInterface); -int radio_stats_update_on_new_radio_packet_received(shared_mem_radio_stats* pSMRS, shared_mem_radio_stats_interfaces_rx_graph* pSMRXStats, u32 timeNow, int iInterfaceIndex, u8* pPacketBuffer, int iPacketLength, int iIsShortPacket, int iIsVideo, int iDataIsOk); +int radio_stats_update_on_new_radio_packet_received(shared_mem_radio_stats* pSMRS, shared_mem_radio_stats_interfaces_rx_graph* pSMRXStats, u32 timeNow, int iInterfaceIndex, u8* pPacketBuffer, int iPacketLength, int iIsShortPacket, int iIsVideoData, int iDataIsOk); int radio_stats_update_on_unique_packet_received(shared_mem_radio_stats* pSMRS, shared_mem_radio_stats_interfaces_rx_graph* pSMRXStats, u32 timeNow, int iInterfaceIndex, u8* pPacketBuffer, int iPacketLength); void radio_stats_update_on_packet_sent_on_radio_interface(shared_mem_radio_stats* pSMRS, u32 timeNow, int interfaceIndex, int iPacketLength); void radio_stats_update_on_packet_sent_on_radio_link(shared_mem_radio_stats* pSMRS, u32 timeNow, int iLocalLinkIndex, int iStreamIndex, int iPacketLength, int iChainedCount); diff --git a/code/common/string_utils.c b/code/common/string_utils.c index 50407aa4..eb81e982 100644 --- a/code/common/string_utils.c +++ b/code/common/string_utils.c @@ -10,9 +10,9 @@ * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - * Copyright info and developer info must be preserved as is in the user + * Copyright info and developer info must be preserved as is in the user interface, additions could be made to that info. - * Neither the name of the organization nor the + * Neither the name of the organization nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. * Military use is not permited. @@ -628,7 +628,7 @@ char* str_format_frequency_no_sufix(u32 uFrequencyKhz) const char* str_get_hardware_board_name(u32 board_type) { - static const char* s_szBoardTypeUnknown = "N/A"; + static const char* s_szBoardTypeUnknown = "Unknown"; #ifdef HW_PLATFORM_RASPBERRY static const char* s_szBoardTypePi0 = "Raspberry Pi Zero"; static const char* s_szBoardTypePi0W = "Raspberry Pi Zero W"; @@ -648,11 +648,13 @@ const char* str_get_hardware_board_name(u32 board_type) static const char* s_szBoardTypeOpenIPCGoke200 = "OpenIPC Goke200"; static const char* s_szBoardTypeOpenIPCGoke210 = "OpenIPC Goke210"; static const char* s_szBoardTypeOpenIPCGoke300 = "OpenIPC Goke300"; - static const char* s_szBoardTypeOpenIPCSigmaster338Q = "OpenIPC SSC338Q"; static const char* s_szBoardTypeOpenIPCSigmasterGeneric = "OpenIPC SSC338Q Generic"; + static const char* s_szBoardTypeOpenIPCSigmasterGeneric30KQ = "OpenIPC SSC30KQ Generic"; static const char* s_szBoardTypeOpenIPCSigmasterUltrasight = "Ultrasight AIO"; static const char* s_szBoardTypeOpenIPCSigmasterMario = "Mario AIO"; static const char* s_szBoardTypeOpenIPCSigmasterRuncam = "Runcam"; + static const char* s_szBoardTypeOpenIPCSigmasterEMax = "EMax"; + static const char* s_szBoardTypeOpenIPCSigmasterThinker = "OpenIPC Thinker"; #ifdef HW_PLATFORM_RASPBERRY if ( (board_type & BOARD_TYPE_MASK) == BOARD_TYPE_PIZERO ) @@ -690,25 +692,25 @@ const char* str_get_hardware_board_name(u32 board_type) return s_szBoardTypeOpenIPCGoke210; if ( (board_type & BOARD_TYPE_MASK) == BOARD_TYPE_OPENIPC_GOKE300 ) return s_szBoardTypeOpenIPCGoke300; - if ( (board_type & BOARD_TYPE_MASK) == BOARD_TYPE_OPENIPC_SIGMASTER_338Q ) + if ( (board_type & BOARD_TYPE_MASK) == BOARD_TYPE_OPENIPC_SIGMASTAR_338Q ) { - if ( (board_type & BOARD_SUBTYPE_MASK) == BOARD_SUBTYPE_OPENIPC_GENERIC ) - return s_szBoardTypeOpenIPCSigmasterGeneric; - else if ( (board_type & BOARD_SUBTYPE_MASK) == BOARD_SUBTYPE_OPENIPC_AIO_ULTRASIGHT ) - return s_szBoardTypeOpenIPCSigmasterUltrasight; - else if ( (board_type & BOARD_SUBTYPE_MASK) == BOARD_SUBTYPE_OPENIPC_AIO_MARIO ) - return s_szBoardTypeOpenIPCSigmasterMario; - else if ( (board_type & BOARD_SUBTYPE_MASK) == BOARD_SUBTYPE_OPENIPC_AIO_RUNCAM ) - return s_szBoardTypeOpenIPCSigmasterRuncam; - else - return s_szBoardTypeOpenIPCSigmaster338Q; + switch ( (board_type & BOARD_SUBTYPE_MASK) >> BOARD_SUBTYPE_SHIFT) + { + case BOARD_SUBTYPE_OPENIPC_GENERIC: return s_szBoardTypeOpenIPCSigmasterGeneric; + case BOARD_SUBTYPE_OPENIPC_GENERIC_30KQ: return s_szBoardTypeOpenIPCSigmasterGeneric30KQ; + case BOARD_SUBTYPE_OPENIPC_AIO_ULTRASIGHT: return s_szBoardTypeOpenIPCSigmasterUltrasight; + case BOARD_SUBTYPE_OPENIPC_AIO_MARIO: return s_szBoardTypeOpenIPCSigmasterMario; + case BOARD_SUBTYPE_OPENIPC_AIO_RUNCAM: return s_szBoardTypeOpenIPCSigmasterRuncam; + case BOARD_SUBTYPE_OPENIPC_AIO_EMAX: return s_szBoardTypeOpenIPCSigmasterEMax; + case BOARD_SUBTYPE_OPENIPC_AIO_THINKER: return s_szBoardTypeOpenIPCSigmasterThinker; + } } return s_szBoardTypeUnknown; } const char* str_get_hardware_board_name_short(u32 board_type) { - static const char* s_szBoardSTypeUnknown = "N/A"; + static const char* s_szBoardSTypeUnknown = "Unknown"; #ifdef HW_PLATFORM_RASPBERRY static const char* s_szBoardSTypePi0 = "Pi 0"; static const char* s_szBoardSTypePi0W = "Pi 0W"; @@ -730,11 +732,13 @@ const char* str_get_hardware_board_name_short(u32 board_type) static const char* s_szBoardSTypeOpenIPCGoke200 = "Goke200"; static const char* s_szBoardSTypeOpenIPCGoke210 = "Goke210"; static const char* s_szBoardSTypeOpenIPCGoke300 = "Goke300"; - static const char* s_szBoardSTypeOpenIPCSigmaster338Q = "SSC338Q"; - static const char* s_szBoardSTypeOpenIPCSigmasterGeneric = "SSC338Q Generic"; + static const char* s_szBoardSTypeOpenIPCSigmasterGeneric = "SSC338Q"; + static const char* s_szBoardSTypeOpenIPCSigmasterGeneric30KQ = "SSC30KQ"; static const char* s_szBoardSTypeOpenIPCSigmasterUltrasight = "Ultrasight"; static const char* s_szBoardSTypeOpenIPCSigmasterMario = "Mario"; static const char* s_szBoardSTypeOpenIPCSigmasterRuncam = "Runcam"; + static const char* s_szBoardSTypeOpenIPCSigmasterEMax = "EMax"; + static const char* s_szBoardSTypeOpenIPCSigmasterThinker = "Thinker"; #ifdef HW_PLATFORM_RASPBERRY if ( (board_type & BOARD_TYPE_MASK) == BOARD_TYPE_PIZERO ) @@ -772,18 +776,18 @@ const char* str_get_hardware_board_name_short(u32 board_type) return s_szBoardSTypeOpenIPCGoke210; if ( (board_type & BOARD_TYPE_MASK) == BOARD_TYPE_OPENIPC_GOKE300 ) return s_szBoardSTypeOpenIPCGoke300; - if ( (board_type & BOARD_TYPE_MASK) == BOARD_TYPE_OPENIPC_SIGMASTER_338Q ) + if ( (board_type & BOARD_TYPE_MASK) == BOARD_TYPE_OPENIPC_SIGMASTAR_338Q ) { - if ( (board_type & BOARD_SUBTYPE_MASK) == BOARD_SUBTYPE_OPENIPC_GENERIC ) - return s_szBoardSTypeOpenIPCSigmasterGeneric; - else if ( (board_type & BOARD_SUBTYPE_MASK) == BOARD_SUBTYPE_OPENIPC_AIO_ULTRASIGHT ) - return s_szBoardSTypeOpenIPCSigmasterUltrasight; - else if ( (board_type & BOARD_SUBTYPE_MASK) == BOARD_SUBTYPE_OPENIPC_AIO_MARIO ) - return s_szBoardSTypeOpenIPCSigmasterMario; - else if ( (board_type & BOARD_SUBTYPE_MASK) == BOARD_SUBTYPE_OPENIPC_AIO_RUNCAM ) - return s_szBoardSTypeOpenIPCSigmasterRuncam; - else - return s_szBoardSTypeOpenIPCSigmaster338Q; + switch ( (board_type & BOARD_SUBTYPE_MASK) >> BOARD_SUBTYPE_SHIFT) + { + case BOARD_SUBTYPE_OPENIPC_GENERIC: return s_szBoardSTypeOpenIPCSigmasterGeneric; + case BOARD_SUBTYPE_OPENIPC_GENERIC_30KQ: return s_szBoardSTypeOpenIPCSigmasterGeneric30KQ; + case BOARD_SUBTYPE_OPENIPC_AIO_ULTRASIGHT: return s_szBoardSTypeOpenIPCSigmasterUltrasight; + case BOARD_SUBTYPE_OPENIPC_AIO_MARIO: return s_szBoardSTypeOpenIPCSigmasterMario; + case BOARD_SUBTYPE_OPENIPC_AIO_RUNCAM: return s_szBoardSTypeOpenIPCSigmasterRuncam; + case BOARD_SUBTYPE_OPENIPC_AIO_EMAX: return s_szBoardSTypeOpenIPCSigmasterEMax; + case BOARD_SUBTYPE_OPENIPC_AIO_THINKER: return s_szBoardSTypeOpenIPCSigmasterThinker; + } } return s_szBoardSTypeUnknown; @@ -909,6 +913,11 @@ void str_get_supported_bands_string(u32 bands, char* szOut) iCount++; } + if ( (0 == szOut[0]) || (0 == iCount) ) + { + strcpy(szOut, "N/A"); + return; + } if ( hasGhz ) strcat(szOut, " Ghz"); @@ -972,6 +981,8 @@ const char* str_get_radio_card_model_string(int cardModel) s_szCardModelDescription[0] = 0; strcpy(s_szCardModelDescription, "Generic"); if ( cardModel == CARD_MODEL_TPLINK722N ) strcpy(s_szCardModelDescription, "TPLink 722N"); + if ( cardModel == CARD_MODEL_ATHEROS_GENERIC ) strcpy(s_szCardModelDescription, "Atheros Generic"); + if ( cardModel == CARD_MODEL_RTL8812AU_GENERIC ) strcpy(s_szCardModelDescription, "RTL8812AU Generic"); if ( cardModel == CARD_MODEL_ALFA_AWUS036NHA ) strcpy(s_szCardModelDescription, "Alfa AWUS036NHA"); if ( cardModel == CARD_MODEL_ALFA_AWUS036NH ) strcpy(s_szCardModelDescription, "Alfa AWUS036NH"); if ( cardModel == CARD_MODEL_ALFA_AWUS036ACH ) strcpy(s_szCardModelDescription, "Alfa AWUS036ACH"); @@ -987,6 +998,9 @@ const char* str_get_radio_card_model_string(int cardModel) if ( cardModel == CARD_MODEL_ARCHER_T2UPLUS ) strcpy(s_szCardModelDescription, "Archer T2U Plus"); if ( cardModel == CARD_MODEL_RTL8814AU ) strcpy(s_szCardModelDescription, "RTL8814AU"); if ( cardModel == CARD_MODEL_BLUE_8812EU ) strcpy(s_szCardModelDescription, "Blue RTL8812EU"); + if ( cardModel == CARD_MODEL_RTL8812AU_OIPC_USIGHT ) strcpy(s_szCardModelDescription, "RTL8812AU Ultrasight"); + if ( cardModel == CARD_MODEL_RTL8812AU_OIPC_USIGHT2 ) strcpy(s_szCardModelDescription, "RTL8812AU Ultrasight 2"); + if ( cardModel == CARD_MODEL_SIK_RADIO ) strcpy(s_szCardModelDescription, "SiK-Radio"); if ( cardModel == CARD_MODEL_SERIAL_RADIO ) strcpy(s_szCardModelDescription, "Serial-Radio"); if ( cardModel == CARD_MODEL_SERIAL_RADIO_ELRS ) strcpy(s_szCardModelDescription, "ELRS-Radio"); @@ -1002,6 +1016,8 @@ const char* str_get_radio_card_model_string_short(int cardModel) s_szCardModelDescription[0] = 0; strcpy(s_szCardModelDescription, "Generic"); if ( cardModel == CARD_MODEL_TPLINK722N ) strcpy(s_szCardModelDescription, "TPL-722N"); + if ( cardModel == CARD_MODEL_ATHEROS_GENERIC ) strcpy(s_szCardModelDescription, "Atheros"); + if ( cardModel == CARD_MODEL_RTL8812AU_GENERIC ) strcpy(s_szCardModelDescription, "RTL8812AU"); if ( cardModel == CARD_MODEL_ALFA_AWUS036NHA ) strcpy(s_szCardModelDescription, "AWUS036NHA"); if ( cardModel == CARD_MODEL_ALFA_AWUS036NH ) strcpy(s_szCardModelDescription, "AWUS036NH"); if ( cardModel == CARD_MODEL_ALFA_AWUS036ACH ) strcpy(s_szCardModelDescription, "AWUS036ACH"); @@ -1017,6 +1033,8 @@ const char* str_get_radio_card_model_string_short(int cardModel) if ( cardModel == CARD_MODEL_ARCHER_T2UPLUS ) strcpy(s_szCardModelDescription, "T2U+"); if ( cardModel == CARD_MODEL_RTL8814AU ) strcpy(s_szCardModelDescription, "RTL8814AU"); if ( cardModel == CARD_MODEL_BLUE_8812EU ) strcpy(s_szCardModelDescription, "RTL8812EU"); + if ( cardModel == CARD_MODEL_RTL8812AU_OIPC_USIGHT ) strcpy(s_szCardModelDescription, "RTL8812AU USight"); + if ( cardModel == CARD_MODEL_RTL8812AU_OIPC_USIGHT2 ) strcpy(s_szCardModelDescription, "RTL8812AU USight2"); if ( cardModel == CARD_MODEL_SIK_RADIO ) strcpy(s_szCardModelDescription, "SiK-Radio"); if ( cardModel == CARD_MODEL_SERIAL_RADIO ) strcpy(s_szCardModelDescription, "Serial-Radio"); @@ -1328,8 +1346,6 @@ char* str_get_component_id(int iComponentId) strcpy(s_szComponentIdString, "PACKET_COMPONENT_RUBY"); else if ( iComponentId == PACKET_COMPONENT_AUDIO ) strcpy(s_szComponentIdString, "PACKET_COMPONENT_AUDIO"); - else if ( iComponentId == PACKET_COMPONENT_DATA ) - strcpy(s_szComponentIdString, "PACKET_COMPONENT_DATA"); else strcpy(s_szComponentIdString, "INVALID"); diff --git a/code/r_central/menu/menu_tx_power_8812eu.cpp b/code/common/strings_table.c similarity index 58% rename from code/r_central/menu/menu_tx_power_8812eu.cpp rename to code/common/strings_table.c index 2b3d0e01..3923b38a 100644 --- a/code/r_central/menu/menu_tx_power_8812eu.cpp +++ b/code/common/strings_table.c @@ -10,9 +10,9 @@ * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - * Copyright info and developer info must be preserved as is in the user + * Copyright info and developer info must be preserved as is in the user interface, additions could be made to that info. - * Neither the name of the organization nor the + * Neither the name of the organization nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. * Military use is not permited. @@ -29,65 +29,29 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -#include "menu.h" -#include "menu_tx_power_8812eu.h" -#include "menu_objects.h" -#include "menu_item_text.h" -#include "menu_confirmation.h" -#include "menu_tx_power_max.h" +#include "../base/base.h" +#include +#include "strings_table.h" -MenuTXPower8812EU::MenuTXPower8812EU() -:MenuTXPower() -{ - m_MenuId = MENU_ID_TX_POWER_8812EU; - setTitle("Radio Output Power Levels (for RTL8812EU)"); - m_Width = 0.72; - m_Height = 0.61; - m_xPos = 0.05; - m_yPos = 0.16; - - m_xTable = m_RenderXPos + m_sfMenuPaddingY; - m_xTable += 0.15*m_sfScaleFactor; - m_xTableCellWidth = 0.05*m_sfScaleFactor; +static const char* s_szStringTableUnknown = "[Missing Text]"; - m_bShowThinLine = false; - - m_bShowVehicle = true; - m_bShowController = true; - - m_bValuesChangedVehicle = false; - m_bValuesChangedController = false; -} - -MenuTXPower8812EU::~MenuTXPower8812EU() +static const char* s_szStringTableEN[] = { -} +// 0 +"Firmware Instalation", +"Your controller needs to be fully flashed with the latest version of Ruby.", +"Your vehicle needs to be fully flashed with the latest version of Ruby.", +"Instead of a regular update, a full firmware instalation is required as there where changes in Ruby version 10.1 that require a complete update of the system", +"Computed based on current vehicle radio Tx power settings", +// 5 +"", +"Empty" +}; -void MenuTXPower8812EU::onShow() +const char* getString(u32 uStringId) { - -} - -void MenuTXPower8812EU::valuesToUI() -{ -} + if ( uStringId >= sizeof(s_szStringTableEN)/sizeof(s_szStringTableEN[0]) ) + return s_szStringTableUnknown; - -void MenuTXPower8812EU::Render() -{ + return s_szStringTableEN[uStringId]; } - -int MenuTXPower8812EU::onBack() -{ - return Menu::onBack(); -} - -void MenuTXPower8812EU::onReturnFromChild(int iChildMenuId, int returnValue) -{ - -} - -void MenuTXPower8812EU::onSelectItem() -{ - -} \ No newline at end of file diff --git a/code/common/strings_table.h b/code/common/strings_table.h new file mode 100644 index 00000000..8506654a --- /dev/null +++ b/code/common/strings_table.h @@ -0,0 +1,11 @@ +#pragma once + +#ifdef __cplusplus +extern "C" { +#endif + +const char* getString(u32 uStringId); + +#ifdef __cplusplus +} +#endif \ No newline at end of file diff --git a/code/r_central/events.cpp b/code/r_central/events.cpp index f753375c..61cb8f9e 100644 --- a/code/r_central/events.cpp +++ b/code/r_central/events.cpp @@ -10,9 +10,9 @@ * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - * Copyright info and developer info must be preserved as is in the user + * Copyright info and developer info must be preserved as is in the user interface, additions could be made to that info. - * Neither the name of the organization nor the + * Neither the name of the organization nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. * Military use is not permited. @@ -36,6 +36,7 @@ #include "../base/ctrl_preferences.h" #include "../radio/radiolink.h" #include "../common/string_utils.h" +#include "../common/strings_table.h" #include "events.h" #include "shared_vars.h" #include "timers.h" @@ -129,7 +130,6 @@ void onMainVehicleChanged(bool bRemovePreviousVehicleState) g_bHasVideoDataOverloadAlarm = false; g_bHasVideoTxOverloadAlarm = false; g_bIsVehicleLinkToControllerLost = false; - g_iDeltaVideoInfoBetweenVehicleController = 0; g_iVehicleCorePluginsCount = 0; g_bChangedOSDStatsFontSize = false; g_bFreezeOSD = false; @@ -515,25 +515,25 @@ bool onEventReceivedModelSettings(u32 uVehicleId, u8* pBuffer, int length, bool log_line("Currently received temp model osd layout: %d, enabled: %s", modelTemp.osd_params.layout, (modelTemp.osd_params.osd_flags2[modelTemp.osd_params.layout] & OSD_FLAG2_LAYOUT_ENABLED)?"yes":"no"); log_line("Currently received temp model developer flags: [%s]", str_get_developer_flags(modelTemp.uDeveloperFlags)); log_line("Received vehicle info has %d radio links.", modelTemp.radioLinksParams.links_count ); - + log_line("Currently received temp model has Ruby base version: %d.%d", (modelTemp.hwCapabilities.uRubyBaseVersion >> 8) & 0xFF, modelTemp.hwCapabilities.uRubyBaseVersion & 0xFF); bool bRadioChanged = false; bool bCameraChanged = false; - bool bMustNegociateRadioLinks = false; + g_bMustNegociateRadioLinksFlag = false; if ( (NULL != g_pCurrentModel) && (g_pCurrentModel->uVehicleId == pModel->uVehicleId) ) if ( !(pModel->radioLinksParams.uGlobalRadioLinksFlags & MODEL_RADIOLINKS_FLAGS_HAS_NEGOCIATED_LINKS) ) - bMustNegociateRadioLinks = true; + g_bMustNegociateRadioLinksFlag = true; if ( pModel->radioInterfacesParams.interfaces_count != modelTemp.radioInterfacesParams.interfaces_count ) - bMustNegociateRadioLinks = true; + g_bMustNegociateRadioLinksFlag = true; for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) { if ( pModel->radioInterfacesParams.interface_card_model[i] != modelTemp.radioInterfacesParams.interface_card_model[i] ) - bMustNegociateRadioLinks = true; + g_bMustNegociateRadioLinksFlag = true; if ( pModel->radioInterfacesParams.interface_radiotype_and_driver[i] != modelTemp.radioInterfacesParams.interface_radiotype_and_driver[i] ) - bMustNegociateRadioLinks = true; + g_bMustNegociateRadioLinksFlag = true; if ( 0 != strcmp(pModel->radioInterfacesParams.interface_szMAC[i], modelTemp.radioInterfacesParams.interface_szMAC[i]) ) - bMustNegociateRadioLinks = true; + g_bMustNegociateRadioLinksFlag = true; } if ( pModel->uVehicleId == modelTemp.uVehicleId ) @@ -620,6 +620,25 @@ bool onEventReceivedModelSettings(u32 uVehicleId, u8* pBuffer, int length, bool log_line("The vehicle has Ruby version %d.%d (b%d) (%u) and the controller %d.%d (b%d) (%u)", ((pModel->sw_version)>>8) & 0xFF, (pModel->sw_version) & 0xFF, ((pModel->sw_version)>>16), pModel->sw_version, SYSTEM_SW_VERSION_MAJOR, SYSTEM_SW_VERSION_MINOR, SYSTEM_SW_BUILD_NUMBER, (SYSTEM_SW_VERSION_MAJOR*256+SYSTEM_SW_VERSION_MINOR) | (SYSTEM_SW_BUILD_NUMBER<<16) ); + int iMajor = (pModel->hwCapabilities.uRubyBaseVersion>>8) & 0xFF; + int iMinor = pModel->hwCapabilities.uRubyBaseVersion & 0xFF; + bool bMustInstallFirmware = false; + if ( (iMajor < 10) || ((iMajor == 10) && (iMinor < 1)) ) + if ( ! pModel->isRunningOnOpenIPCHardware() ) + bMustInstallFirmware = true; + + if ( bMustInstallFirmware ) + { + pModel->b_mustSyncFromVehicle = false; + saveControllerModel(pModel); + log_line("[Event] Updated current local vehicle with received settings."); + MenuConfirmation* pMC = new MenuConfirmation(getString(0), getString(2), 0, true); + pMC->addTopLine(getString(3)); + pMC->setIconId(g_idIconWarning); + pMC->m_yPos = 0.3; + add_menu_to_stack(pMC); + } + bool bMustUpdate = false; if ( ((u32)SYSTEM_SW_VERSION_MAJOR)*(int)256 + (u32)SYSTEM_SW_VERSION_MINOR > (pModel->sw_version & 0xFFFF) ) bMustUpdate = true; @@ -639,7 +658,7 @@ bool onEventReceivedModelSettings(u32 uVehicleId, u8* pBuffer, int length, bool bMustUpdate = false; } - if ( bMustUpdate ) + if ( bMustUpdate && (!bMustInstallFirmware) ) { char szBuff[256]; char szBuff2[32]; @@ -661,18 +680,18 @@ bool onEventReceivedModelSettings(u32 uVehicleId, u8* pBuffer, int length, bool { add_menu_to_stack( new MenuUpdateVehiclePopup(-1) ); g_bMenuPopupUpdateVehicleShown = true; - bMustNegociateRadioLinks = false; + g_bMustNegociateRadioLinksFlag = false; } } if ( !bMustUpdate ) + if ( !bMustInstallFirmware ) if ( is_sw_version_atleast(g_pCurrentModel, 9, 7) ) if ( hardware_board_is_sigmastar(pModel->hwCapabilities.uBoardType) ) if ( (pModel->hwCapabilities.uBoardType & BOARD_SUBTYPE_MASK) == BOARD_SUBTYPE_OPENIPC_UNKNOWN ) if ( ! menu_has_menu(MENU_ID_VEHICLE_BOARD) ) { add_menu_to_stack( new MenuConfirmationVehicleBoard() ); - bMustNegociateRadioLinks = false; } pModel->is_spectator = is_spectator; @@ -773,7 +792,7 @@ bool onEventReceivedModelSettings(u32 uVehicleId, u8* pBuffer, int length, bool if ( pModel->uVehicleId == g_pCurrentModel->uVehicleId ) if ( pModel->audio_params.enabled != bOldAudioEnabled ) { - log_line("Audio enable flag changed. Must repair."); + log_line("Audio enable flag changed. Must re-pair."); bMustPair = true; } if ( pModel->uVehicleId == g_pCurrentModel->uVehicleId ) @@ -792,7 +811,7 @@ bool onEventReceivedModelSettings(u32 uVehicleId, u8* pBuffer, int length, bool hardware_sleep_ms(100); pairing_start_normal(); log_line("[Events] Handing of event OnReceivedModelSettings complete."); - bMustNegociateRadioLinks = false; + g_bMustNegociateRadioLinksFlag = false; return true; } @@ -817,14 +836,17 @@ bool onEventReceivedModelSettings(u32 uVehicleId, u8* pBuffer, int length, bool MenuConfirmation* pMC = new MenuConfirmation("Unsuppoerted video codec", szTextW, 0, true); pMC->m_yPos = 0.3; add_menu_to_stack(pMC); - bMustNegociateRadioLinks = false; + g_bMustNegociateRadioLinksFlag = false; } #endif if ( pModel->hasCamera() ) - if ( bMustNegociateRadioLinks ) + if ( g_bMustNegociateRadioLinksFlag ) if ( ! g_bDidAnUpdate ) + if ( ! bMustInstallFirmware ) if ( ! menu_has_menu(MENU_ID_NEGOCIATE_RADIO) ) + if ( ! menu_has_menu(MENU_ID_VEHICLE_BOARD) ) + if ( ! g_bAskedForNegociateRadioLink ) { add_menu_to_stack(new MenuNegociateRadio()); } diff --git a/code/r_central/forward_watch.cpp b/code/r_central/forward_watch.cpp index c883988a..33d89611 100644 --- a/code/r_central/forward_watch.cpp +++ b/code/r_central/forward_watch.cpp @@ -90,7 +90,7 @@ void _forward_on_usb_device_detected() } log_line("USB Device IP Address: %s", szIP); - bool bHasETH = hardware_has_eth(); + bool bHasETH = ((hardware_has_eth() != NULL)?true:false); if ( ! bHasETH ) log_line("No ETH port. No further action on USB tethering start."); @@ -124,7 +124,7 @@ void _forward_on_usb_device_unplugged() else strcpy(szSysType, "STATION"); - bool bHasETH = hardware_has_eth(); + bool bHasETH = ((hardware_has_eth() != NULL)?true:false); hw_stop_process("pump"); diff --git a/code/r_central/handle_commands.cpp b/code/r_central/handle_commands.cpp index 9e24efdf..6c3746df 100644 --- a/code/r_central/handle_commands.cpp +++ b/code/r_central/handle_commands.cpp @@ -34,6 +34,7 @@ #include "../base/ctrl_settings.h" #include "../common/models_connect_frequencies.h" #include "../common/string_utils.h" +#include "../utils/utils_controller.h" #include "handle_commands.h" #include "popup.h" #include "popup_log.h" @@ -753,7 +754,7 @@ bool handle_last_command_result() t_packet_header_command_response* pPHCR = (t_packet_header_command_response*)(s_CommandReplyBuffer + sizeof(t_packet_header)); char szBuff[1500]; - int tmp = 0, tmp1 = 0, tmp2 = 0; + int tmp = 0, tmp1 = 0; u32 *pTmp32 = NULL; u8* pBuffer = NULL; Model modelTemp; @@ -897,6 +898,15 @@ bool handle_last_command_result() send_model_changed_message_to_router(MODEL_CHANGED_GENERIC, 0); break; + case COMMAND_ID_SET_AUTO_TX_POWERS: + g_pCurrentModel->radioInterfacesParams.iAutoControllerTxPower = (int)((s_CommandParam >> 8) & 0xFF); + saveControllerModel(g_pCurrentModel); + apply_controller_radio_tx_powers(g_pCurrentModel, get_ControllerSettings()->iFixedTxPower, false); + save_ControllerInterfacesSettings(); + send_model_changed_message_to_router(MODEL_CHANGED_RADIO_POWERS, 0); + menu_invalidate_all(); + break; + case COMMAND_ID_FACTORY_RESET: { pairing_stop(); @@ -1025,7 +1035,7 @@ bool handle_last_command_result() s_pMenuVehicleHWInfo = new Menu(0,"Vehicle Hardware Info",NULL); s_pMenuVehicleHWInfo->m_xPos = 0.32; s_pMenuVehicleHWInfo->m_yPos = 0.17; s_pMenuVehicleHWInfo->m_Width = 0.6; - sprintf(szBuff, "Board type: %s, software version: %d.%d (b%d)", str_get_hardware_board_name(g_pCurrentModel->hwCapabilities.uBoardType), ((g_pCurrentModel->sw_version)>>8) & 0xFF, (g_pCurrentModel->sw_version) & 0xFF, ((g_pCurrentModel->sw_version)>>16)); + sprintf(szBuff, "Board type: %s (id: %d), software version: %d.%d (b%d)", str_get_hardware_board_name(g_pCurrentModel->hwCapabilities.uBoardType), g_pCurrentModel->hwCapabilities.uBoardType, ((g_pCurrentModel->sw_version)>>8) & 0xFF, (g_pCurrentModel->sw_version) & 0xFF, ((g_pCurrentModel->sw_version)>>16)); s_pMenuVehicleHWInfo->addTopLine(szBuff); s_pMenuVehicleHWInfo->addTopLine(" "); s_pMenuVehicleHWInfo->addTopLine(" "); @@ -1508,17 +1518,30 @@ bool handle_last_command_result() break; case COMMAND_ID_SET_RADIO_CARD_MODEL: - tmp1 = (s_CommandParam & 0xFF); - tmp2 = ((int)((s_CommandParam >> 8) & 0xFF)) - 128; + { + int iRadioInterface = (s_CommandParam & 0xFF); + int iCardModel = ((int)((s_CommandParam >> 8) & 0xFF)) - 128; - if ( (tmp1 >= 0) && (tmp1 < g_pCurrentModel->radioInterfacesParams.interfaces_count) ) + log_line("Received set radio card model response. Requested card model: %d (0x%X), received card model: %d", iCardModel, ((s_CommandParam>>8)&0xFF), (pPHCR->command_response_param & 0xFF)); + if ( 0xFF == ((s_CommandParam>>8) & 0xFF) ) { - g_pCurrentModel->radioInterfacesParams.interface_card_model[tmp1] = tmp2; + // requested autodetection from vehicle + iCardModel = (pPHCR->command_response_param & 0xFF); + char szMsg[128]; + sprintf(szMsg, "The vehicle radio interface was autodetected as: %s", str_get_radio_card_model_string(iCardModel)); + if ( NULL != menu_get_top_menu() ) + menu_get_top_menu()->addMessage2(34, szMsg, "The selected value was updated."); + } + + if ( (iRadioInterface >= 0) && (iRadioInterface < g_pCurrentModel->radioInterfacesParams.interfaces_count) ) + { + g_pCurrentModel->radioInterfacesParams.interface_card_model[tmp1] = iCardModel; saveControllerModel(g_pCurrentModel); send_model_changed_message_to_router(MODEL_CHANGED_GENERIC, 0); + menu_refresh_all_menus(); } break; - + } case COMMAND_ID_SET_RADIO_LINK_FREQUENCY: { warnings_remove_configuring_radio_link(true); @@ -1763,12 +1786,12 @@ bool handle_last_command_result() case COMMAND_ID_SET_SERIAL_PORTS_INFO: { type_vehicle_hardware_interfaces_info* pNewInfo = (type_vehicle_hardware_interfaces_info*)s_CommandBuffer; - g_pCurrentModel->hardwareInterfacesInfo.serial_bus_count = pNewInfo->serial_bus_count; - for( int i=0; iserial_bus_count; i++ ) + g_pCurrentModel->hardwareInterfacesInfo.serial_port_count = pNewInfo->serial_port_count; + for( int i=0; iserial_port_count; i++ ) { - strcpy(g_pCurrentModel->hardwareInterfacesInfo.serial_bus_names[i], pNewInfo->serial_bus_names[i]); - g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[i] = pNewInfo->serial_bus_speed[i]; - g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] = pNewInfo->serial_bus_supported_and_usage[i]; + strcpy(g_pCurrentModel->hardwareInterfacesInfo.serial_port_names[i], pNewInfo->serial_port_names[i]); + g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[i] = pNewInfo->serial_port_speed[i]; + g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] = pNewInfo->serial_port_supported_and_usage[i]; } saveControllerModel(g_pCurrentModel); send_model_changed_message_to_router(MODEL_CHANGED_GENERIC, 0); @@ -1790,72 +1813,21 @@ bool handle_last_command_result() case COMMAND_ID_SET_TX_POWERS: { u8* pData = &s_CommandBuffer[0]; + int iCount = *pData; + pData++; - if ( s_CommandBufferLength >= 11 ) + if ( iCount > MAX_RADIO_INTERFACES ) + iCount = MAX_RADIO_INTERFACES; + for( int i=0; i 0 && iSiKPower < 30 ) - if ( g_pCurrentModel->radioInterfacesParams.txPowerSiK != iSiKPower ) - { - log_line("[Commands] Updated current model's SiK radio power level to %d", iSiKPower); - g_pCurrentModel->radioInterfacesParams.txPowerSiK = iSiKPower; - } - } - else - log_softerror_and_alarm("[Commands] Received invalid power levels message response (for SiK radio interfaces). Ignoring it."); - saveControllerModel(g_pCurrentModel); - send_model_changed_message_to_router(MODEL_CHANGED_GENERIC, 0); - menu_refresh_all_menus(); - break; + g_pCurrentModel->radioInterfacesParams.interface_raw_power[i] = *pData; + pData++; } - u8 txPowerRTL8812AU = *pData; - pData++; - u8 txPowerRTL8812EU = *pData; - pData++; - u8 txPowerAtheros = *pData; - pData++; - u8 txMaxPowerRTL8812AU = *pData; - pData++; - u8 txMaxPowerRTL8812EU = *pData; - pData++; - u8 txMaxPowerAtheros = *pData; - pData++; - u8 cardIndex = *pData; - pData++; - u8 cardPower = *pData; - pData++; - - log_line("[Commands] Received set tx powers confirmation: set: %d, %d, %d / max: %d, %d, %d / card: %d %d", - txPowerRTL8812AU, txPowerRTL8812EU, txPowerAtheros, - txMaxPowerRTL8812AU, txMaxPowerRTL8812EU, txMaxPowerAtheros, cardIndex, cardPower); - - log_line("[Commands] Current model radio power levels: 8812AU: %d, 8812EU: %d, Atheros: %d, Max: %d, %d, %d", g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU, g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU, g_pCurrentModel->radioInterfacesParams.txPowerAtheros, - g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812AU, g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812EU, g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros); - - if ( (txMaxPowerRTL8812AU > 0) && (txMaxPowerRTL8812AU != 0xFF) ) - g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812AU = txMaxPowerRTL8812AU; - if ( (txMaxPowerRTL8812EU > 0) && (txMaxPowerRTL8812EU != 0xFF) ) - g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812EU = txMaxPowerRTL8812EU; - if ( (txMaxPowerAtheros > 0) && (txMaxPowerAtheros != 0xFF) ) - g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros = txMaxPowerAtheros; - - if ( (txPowerRTL8812EU > 0) && (txPowerRTL8812EU != 0xFF) ) - g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU = txPowerRTL8812EU; - if ( (txPowerRTL8812AU > 0) && (txPowerRTL8812AU != 0xFF) ) - g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU = txPowerRTL8812AU; - if ( (txPowerAtheros > 0) && (txPowerAtheros != 0xFF) ) - g_pCurrentModel->radioInterfacesParams.txPowerAtheros = txPowerAtheros; - - if ( (cardPower > 0) && (cardPower != 0xFF) ) - if ( cardIndex < g_pCurrentModel->radioInterfacesParams.interfaces_count ) - g_pCurrentModel->radioInterfacesParams.interface_power[cardIndex] = cardPower; - saveControllerModel(g_pCurrentModel); + save_ControllerInterfacesSettings(); + apply_controller_radio_tx_powers(g_pCurrentModel, get_ControllerSettings()->iFixedTxPower, false); + save_ControllerInterfacesSettings(); send_model_changed_message_to_router(MODEL_CHANGED_GENERIC, 0); menu_refresh_all_menus(); break; @@ -1913,16 +1885,6 @@ bool handle_last_command_result() log_line("[Commands] Vehicle TOP output (%d chars):\n%s", iDataLength, pBuffer); break; - case COMMAND_ID_SET_RADIO_SLOTTIME: - g_pCurrentModel->radioInterfacesParams.slotTime = s_CommandParam; - saveControllerModel(g_pCurrentModel); - break; - - case COMMAND_ID_SET_RADIO_THRESH62: - g_pCurrentModel->radioInterfacesParams.thresh62 = s_CommandParam; - saveControllerModel(g_pCurrentModel); - break; - case COMMAND_ID_DOWNLOAD_FILE: _handle_download_file_response(); break; diff --git a/code/r_central/launchers_controller.cpp b/code/r_central/launchers_controller.cpp index b38c448f..c034ba0a 100644 --- a/code/r_central/launchers_controller.cpp +++ b/code/r_central/launchers_controller.cpp @@ -310,7 +310,7 @@ void controller_wait_for_stop_all() static void * _thread_adjust_affinities(void *argument) { - log_line("Started background thread to adjust processes affinities..."); + log_line("[BGThread] Started background thread to adjust processes affinities..."); if ( s_iCPUCoresCount > 2 ) { hw_set_proc_affinity("ruby_rt_station", 1,1); @@ -329,7 +329,7 @@ static void * _thread_adjust_affinities(void *argument) hw_set_proc_affinity("ruby_rt_station", 1,1); hw_set_proc_affinity("ruby_central", 2,2); } - log_line("Background thread to adjust processes affinities completed."); + log_line("[BGThread] Background thread to adjust processes affinities completed."); return NULL; } @@ -349,4 +349,5 @@ void controller_check_update_processes_affinities() log_error_and_alarm("Failed to create thread for adjusting processes affinities."); return; } + log_line("Done launching worker thread to adjust affinities."); } diff --git a/code/r_central/link_watch.cpp b/code/r_central/link_watch.cpp index 1f01400e..7dcd22ed 100644 --- a/code/r_central/link_watch.cpp +++ b/code/r_central/link_watch.cpp @@ -426,6 +426,19 @@ void link_watch_check_link_lost() // Link is lost + if ( g_bVideoRecordingStarted && (!g_bVideoProcessing) ) + if ( NULL != g_pPopupLinkLost ) + { + Preferences* pP = get_Preferences(); + if ( NULL != pP ) + if ( pP->iStopRecordingAfterLinkLostSeconds > 0 ) + if ( g_TimeNow > g_pPopupLinkLost->getCreationTime() + pP->iStopRecordingAfterLinkLostSeconds*1000 ) + { + ruby_stop_recording(); + } + } + + if ( NULL != g_pPopupLinkLost ) return; @@ -620,25 +633,27 @@ void link_watch_loop_telemetry() } // FC source telemetry data present or lost ? - bool bHasTelemetryFromFC = vehicle_runtime_has_received_fc_telemetry(g_VehiclesRuntimeInfo[i].uVehicleId); - - if ( ! bHasTelemetryFromFC ) + if ( pairing_isStarted() ) + if ( g_VehiclesRuntimeInfo[i].pModel->is_spectator || g_VehiclesRuntimeInfo[i].bPairedConfirmed ) { - static bool s_bFirstTimeFCTelemetryWarning = true; - if ( g_VehiclesRuntimeInfo[i].bFCTelemetrySourcePresent || s_bFirstTimeFCTelemetryWarning ) + bool bHasTelemetryFromFC = vehicle_runtime_has_received_fc_telemetry(g_VehiclesRuntimeInfo[i].uVehicleId); + if ( ! bHasTelemetryFromFC ) { - warnings_add(g_VehiclesRuntimeInfo[i].uVehicleId, "Flight controller telemetry missing", g_idIconCPU, get_Color_IconError()); + static bool s_bFirstTimeFCTelemetryWarning = true; + if ( g_VehiclesRuntimeInfo[i].bFCTelemetrySourcePresent || s_bFirstTimeFCTelemetryWarning ) + { + warnings_add(g_VehiclesRuntimeInfo[i].uVehicleId, "Flight controller telemetry missing", g_idIconCPU, get_Color_IconError()); + } + g_VehiclesRuntimeInfo[i].bFCTelemetrySourcePresent = false; + s_bFirstTimeFCTelemetryWarning = false; + } + else + { + if ( ! g_VehiclesRuntimeInfo[i].bFCTelemetrySourcePresent ) + warnings_add(g_VehiclesRuntimeInfo[i].uVehicleId, "Flight controller telemetry recovered", g_idIconCPU, get_Color_IconSucces()); + g_VehiclesRuntimeInfo[i].bFCTelemetrySourcePresent = true; } - g_VehiclesRuntimeInfo[i].bFCTelemetrySourcePresent = false; - s_bFirstTimeFCTelemetryWarning = false; - } - else - { - if ( ! g_VehiclesRuntimeInfo[i].bFCTelemetrySourcePresent ) - warnings_add(g_VehiclesRuntimeInfo[i].uVehicleId, "Flight controller telemetry recovered", g_idIconCPU, get_Color_IconSucces()); - g_VehiclesRuntimeInfo[i].bFCTelemetrySourcePresent = true; } - // Check for Ruby telemetry lost or recovered state if ( g_VehiclesRuntimeInfo[i].bGotRubyTelemetryInfo ) @@ -684,8 +699,8 @@ void link_watch_loop_video() if ( NULL == g_pProcessStatsRouter ) return; - if ( s_LastRouterProcessCheckedAlarmFlags != g_ProcessStatsRouter.alarmFlags || - g_ProcessStatsRouter.alarmTime > s_TimeLastAlarmRouterProcess ) + if ( (s_LastRouterProcessCheckedAlarmFlags != g_ProcessStatsRouter.alarmFlags) || + (g_ProcessStatsRouter.alarmTime > s_TimeLastAlarmRouterProcess) ) { s_LastRouterProcessCheckedAlarmFlags = g_ProcessStatsRouter.alarmFlags; s_TimeLastAlarmRouterProcess = g_ProcessStatsRouter.alarmTime; diff --git a/code/r_central/menu/menu.cpp b/code/r_central/menu/menu.cpp index a8b506de..c715399a 100644 --- a/code/r_central/menu/menu.cpp +++ b/code/r_central/menu/menu.cpp @@ -658,7 +658,13 @@ void menu_refresh_all_menus() void menu_refresh_all_menus_except(Menu* pMenu) { - log_line("[Menu] Refresh all menus..."); + log_line("[Menu] Refresh all menus. Will refresh %d menus (except 0x%X):", g_iMenuStackTopIndex, pMenu); + for ( int i=0; igetId(), g_pMenuStack[i]->getTitle(), g_pMenuStack[i]->getRenderXPos()); + } + for ( int i=0; iresetRenderXPos(); + } + log_line("[Menu] Updated UI for all menus."); +} + u32 menu_get_loop_counter() { return s_uMenuLoopCounter; diff --git a/code/r_central/menu/menu.h b/code/r_central/menu/menu.h index 8263b683..950ec50c 100644 --- a/code/r_central/menu/menu.h +++ b/code/r_central/menu/menu.h @@ -40,6 +40,8 @@ void menu_loop_parse_input_events(); void menu_refresh_all_menus(); void menu_refresh_all_menus_except(Menu* pMenu); void menu_update_ui_all_menus(); +void menu_rearrange_all_menus_no_animation(); + void menu_render(); u32 menu_get_loop_counter(); diff --git a/code/r_central/menu/menu_about.cpp b/code/r_central/menu/menu_about.cpp new file mode 100644 index 00000000..006d30a2 --- /dev/null +++ b/code/r_central/menu/menu_about.cpp @@ -0,0 +1,187 @@ +/* + Ruby Licence + Copyright (c) 2024 Petru Soroaga petrusoroaga@yahoo.com + All rights reserved. + + Redistribution and use in source and/or binary forms, with or without + modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Copyright info and developer info must be preserved as is in the user + interface, additions could be made to that info. + * Neither the name of the organization nor the + names of its contributors may be used to endorse or promote products + derived from this software without specific prior written permission. + * Military use is not permited. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE AUTHOR (PETRU SOROAGA) BE LIABLE FOR ANY + DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#include "menu.h" +#include "menu_objects.h" +#include "menu_controller.h" +#include "menu_text.h" +#include "menu_item_section.h" +#include "menu_about.h" +#include "../osd/osd_common.h" + +extern u32 g_idIconOpenIPC; + +MenuAbout::MenuAbout(void) +:Menu(MENU_ID_ABOUT, "About", NULL) +{ + m_Width = 0.46; + m_xPos = menu_get_XStartPos(m_Width); m_yPos = 0.18; + + char szBuff[1024]; + char szOutput[1024]; + char szComm[256]; + char szTemp[128]; + char szFile[MAX_FILE_PATH_SIZE]; + + szBuff[0] = 0; + strcpy(szBuff, "Ruby base version: N/A"); + + FILE* fd = try_open_base_version_file(NULL); + + if ( NULL != fd ) + { + szOutput[0] = 0; + if ( 1 == fscanf(fd, "%s", szOutput) ) + { + strcpy(szBuff, "Ruby base version: "); + strcat(szBuff, szOutput); + } + fclose(fd); + } + + strcpy(szFile, FOLDER_CONFIG); + strcat(szFile, FILE_INFO_LAST_UPDATE); + fd = fopen(szFile, "r"); + if ( NULL == fd ) + { + strcpy(szFile, FOLDER_BINARIES); + strcat(szFile, FILE_INFO_LAST_UPDATE); + fd = fopen(szFile, "r"); + } + if ( NULL != fd ) + { + szOutput[0] = 0; + if ( 1 == fscanf(fd, "%s", szOutput) ) + { + strcat(szBuff, ", last update: "); + strcat(szBuff, szOutput); + } + fclose(fd); + } + + addTopLine(szBuff); + + addTopLine(" "); + + log_line("Menu About: create HW info."); + + hw_execute_bash_command_raw("cat /proc/device-tree/model", szOutput); + + snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "Board: %s, ", szOutput); + + int temp = 0; + fd = fopen("/sys/class/thermal/thermal_zone0/temp", "r"); + if ( NULL != fd ) + { + fscanf(fd, "%d", &temp); + fclose(fd); + fd = NULL; + } + int speed = hardware_get_cpu_speed(); + sprintf(szTemp, "CPU: %d Mhz, Temp: %d C", speed, temp/1000); + strcat(szBuff, szTemp); + addTopLine(szBuff); + + addTopLine(" "); + addTopLine(" "); + + + #ifdef HW_PLATFORM_RASPBERRY + sprintf(szComm, "df -m %s | grep root", FOLDER_BINARIES); + #endif + #ifdef HW_PLATFORM_RADXA_ZERO3 + sprintf(szComm, "df -m %s | grep mmc", FOLDER_BINARIES); + #endif + if ( 1 == hw_execute_bash_command_raw(szComm, szBuff) ) + { + char szTemp[1024]; + long lb, lu, lf; + sscanf(szBuff, "%s %ld %ld %ld", szTemp, &lb, &lu, &lf); + sprintf(szBuff, "System storage: %ld Mb free out of %ld Mb total.", lf, lu+lf); + addTopLine(szBuff); + } + + addTopLine(" "); + addTopLine("---"); + addTopLine(" "); + addTopLine("Ruby system developed by: Petru Soroaga"); + addTopLine(""); + addTopLine("IP cameras firmware support provided by:"); + addTopLine("OpenIPC: https://openipc.org"); + addTopLine("https://github.com/OpenIPC"); + addTopLine(""); + addTopLine("For info on the licence terms, check the license.txt file."); + addTopLine("For more info, questions and suggestions find us on www.rubyfpv.com"); + addTopLine("---"); + addTopLine(" "); + m_IndexOK = addMenuItem(new MenuItem("Ok", "Close the menu.")); +} + +void MenuAbout::valuesToUI() +{ +} + +void MenuAbout::Render() +{ + RenderPrepare(); + float yTop = RenderFrameAndTitle(); + float y = yTop; + + for( int i=0; itextHeight(g_idFontMenu); + float iconHeight = 2.0*height_text; + float iconWidth = iconHeight/g_pRenderEngine->getAspectRatio(); + g_pRenderEngine->drawIcon(m_RenderXPos + m_RenderWidth - m_sfMenuPaddingX - iconWidth - 0.02, yEnd - iconHeight - 10*g_pRenderEngine->textHeight(g_idFontMenu), iconWidth, iconHeight, g_idIconRuby); + g_pRenderEngine->drawIcon(m_RenderXPos + m_RenderWidth - m_sfMenuPaddingX - iconWidth - 0.02, yEnd - iconHeight - 7*g_pRenderEngine->textHeight(g_idFontMenu), iconWidth, iconHeight, g_idIconOpenIPC); + + RenderEnd(yTop); +} + +bool MenuAbout::periodicLoop() +{ + return false; +} + +void MenuAbout::onReturnFromChild(int iChildMenuId, int returnValue) +{ + Menu::onReturnFromChild(iChildMenuId, returnValue); +} + +void MenuAbout::onSelectItem() +{ + Menu::onSelectItem(); + if ( m_pMenuItems[m_SelectedIndex]->isEditing() ) + return; + + menu_stack_pop(0); +} diff --git a/code/r_central/menu/menu_tx_power_8812eu.h b/code/r_central/menu/menu_about.h similarity index 51% rename from code/r_central/menu/menu_tx_power_8812eu.h rename to code/r_central/menu/menu_about.h index 1f3d224e..c8e6e56c 100644 --- a/code/r_central/menu/menu_tx_power_8812eu.h +++ b/code/r_central/menu/menu_about.h @@ -1,18 +1,20 @@ #pragma once #include "menu_objects.h" #include "menu_item_select.h" -#include "menu_item_slider.h" -#include "menu_tx_power.h" -class MenuTXPower8812EU: public MenuTXPower +class MenuAbout: public Menu { public: - MenuTXPower8812EU(); - virtual ~MenuTXPower8812EU(); - virtual void onShow(); - virtual void valuesToUI(); - virtual int onBack(); - virtual void onReturnFromChild(int iChildMenuId, int returnValue); + MenuAbout(); virtual void Render(); + virtual void valuesToUI(); + virtual bool periodicLoop(); + virtual void onReturnFromChild(int iChildMenuId, int returnValue); virtual void onSelectItem(); + + private: + MenuItemSelect* m_pItemsSelect[15]; + MenuItemSlider* m_pItemsSlider[10]; + + int m_IndexOK; }; \ No newline at end of file diff --git a/code/r_central/menu/menu_confirmation.cpp b/code/r_central/menu/menu_confirmation.cpp index 668cb35a..7306553d 100644 --- a/code/r_central/menu/menu_confirmation.cpp +++ b/code/r_central/menu/menu_confirmation.cpp @@ -10,9 +10,9 @@ * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - * Copyright info and developer info must be preserved as is in the user + * Copyright info and developer info must be preserved as is in the user interface, additions could be made to that info. - * Neither the name of the organization nor the + * Neither the name of the organization nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. * Military use is not permited. @@ -41,7 +41,9 @@ MenuConfirmation::MenuConfirmation(const char* szTitle, const char* szText, int m_xPos = 0.35; m_yPos = 0.35; m_Width = 0.3; m_bSingleOption = false; - addTopLine(szText); + m_uIconId = 0; + if ( NULL != szText ) + addTopLine(szText); addMenuItem(new MenuItem("No")); addMenuItem(new MenuItem("Yes")); } @@ -53,7 +55,8 @@ MenuConfirmation::MenuConfirmation(const char* szTitle, const char* szText, int m_xPos = 0.35; m_yPos = 0.35; m_Width = 0.3; m_bSingleOption = singleOption; - addTopLine(szText); + if ( NULL != szText ) + addTopLine(szText); if ( m_bSingleOption ) { addMenuItem(new MenuItem("Ok")); @@ -70,6 +73,40 @@ MenuConfirmation::~MenuConfirmation() { } +void MenuConfirmation::setIconId(u32 uIconId) +{ + m_uIconId = uIconId; + invalidate(); +} + + +void MenuConfirmation::Render() +{ + RenderPrepare(); + + float height_text = g_pRenderEngine->textHeight(g_idFontMenu); + float iconHeight = 3.0*height_text; + float iconWidth = iconHeight/g_pRenderEngine->getAspectRatio(); + + if ( m_uIconId != 0 ) + m_RenderWidth += iconWidth + m_sfMenuPaddingX; + + float yTop = RenderFrameAndTitle(); + float y = yTop; + + if ( m_uIconId != 0 ) + m_RenderWidth -= iconWidth + m_sfMenuPaddingX; + + for( int i=0; isetColors(get_Color_MenuText(), 0.9); + g_pRenderEngine->setStrokeSize(MENU_OUTLINEWIDTH); + g_pRenderEngine->drawIcon(m_RenderXPos + m_RenderWidth, m_RenderYPos + 0.5*(m_RenderHeight-iconHeight), iconWidth, iconHeight, m_uIconId); + } +} void MenuConfirmation::onSelectItem() { diff --git a/code/r_central/menu/menu_confirmation.h b/code/r_central/menu/menu_confirmation.h index c837ab54..95990bec 100644 --- a/code/r_central/menu/menu_confirmation.h +++ b/code/r_central/menu/menu_confirmation.h @@ -8,8 +8,12 @@ class MenuConfirmation: public Menu MenuConfirmation(const char* szTitle, const char* szText, int id); MenuConfirmation(const char* szTitle, const char* szText, int id, bool singleOption); virtual ~MenuConfirmation(); + virtual void Render(); virtual void onSelectItem(); + void setIconId(u32 uIconId); + protected: bool m_bSingleOption; + u32 m_uIconId; }; \ No newline at end of file diff --git a/code/r_central/menu/menu_confirmation_import.cpp b/code/r_central/menu/menu_confirmation_import.cpp index 6dfe7074..80bb5d7f 100644 --- a/code/r_central/menu/menu_confirmation_import.cpp +++ b/code/r_central/menu/menu_confirmation_import.cpp @@ -35,7 +35,7 @@ #include "../../base/ctrl_settings.h" #include "../../base/hardware.h" #include "../../base/hw_procs.h" -#include "../../base/controller_utils.h" +#include "../../utils/utils_controller.h" #include "../local_stats.h" #include "menu.h" diff --git a/code/r_central/menu/menu_confirmation_vehicle_board.cpp b/code/r_central/menu/menu_confirmation_vehicle_board.cpp index 5f3b16db..a09fa6f2 100644 --- a/code/r_central/menu/menu_confirmation_vehicle_board.cpp +++ b/code/r_central/menu/menu_confirmation_vehicle_board.cpp @@ -37,6 +37,7 @@ #include "menu.h" #include "menu_confirmation_vehicle_board.h" +#include "menu_negociate_radio.h" #include "../ruby_central.h" #include "../events.h" @@ -53,10 +54,12 @@ MenuConfirmationVehicleBoard::MenuConfirmationVehicleBoard() sprintf(szText, "Select the type of your %s board:", g_pCurrentModel->getVehicleTypeString()); addTopLine(szText); addTopLine("(You can later change it from vehicle menu)"); - addMenuItem(new MenuItem("Generic Sigmastar SSC338Q board")); - addMenuItem(new MenuItem("Ultrasight AIO")); - addMenuItem(new MenuItem("Mario AIO")); - addMenuItem(new MenuItem("Runcam AIO")); + + for( u32 u=BOARD_SUBTYPE_OPENIPC_GENERIC; uhwCapabilities.uBoardType &BOARD_TYPE_MASK) | (u<hwCapabilities.uBoardType & BOARD_SUBTYPE_MASK); + { + uSubType = (g_pCurrentModel->hwCapabilities.uBoardType & BOARD_SUBTYPE_MASK) >> BOARD_SUBTYPE_SHIFT; + if ( (uSubType > BOARD_SUBTYPE_OPENIPC_UNKNOWN) && (uSubType < BOARD_SUBTYPE_OPENIPC_LAST) ) + m_SelectedIndex = ((int)uSubType) - 1; + } +} - if ( uBoardType == BOARD_SUBTYPE_OPENIPC_GENERIC ) - m_SelectedIndex = 0; - if ( uBoardType == BOARD_SUBTYPE_OPENIPC_AIO_ULTRASIGHT ) - m_SelectedIndex = 1; - if ( uBoardType == BOARD_SUBTYPE_OPENIPC_AIO_MARIO ) - m_SelectedIndex = 2; - if ( uBoardType == BOARD_SUBTYPE_OPENIPC_AIO_RUNCAM ) - m_SelectedIndex = 3; +int MenuConfirmationVehicleBoard::onBack() +{ + int iRet = Menu::onBack(); + if ( g_bMustNegociateRadioLinksFlag ) + if ( ! g_bAskedForNegociateRadioLink ) + { + add_menu_to_stack(new MenuNegociateRadio()); + } + return iRet; } + void MenuConfirmationVehicleBoard::onSelectItem() { log_line("Menu Confirmation Vehicle Board: selected item: %d", m_SelectedIndex); @@ -95,15 +105,8 @@ void MenuConfirmationVehicleBoard::onSelectItem() u32 uBoardType = g_pCurrentModel->hwCapabilities.uBoardType; uBoardType &= ~(u32)BOARD_SUBTYPE_MASK; - if ( 0 == m_SelectedIndex ) - uBoardType |= BOARD_SUBTYPE_OPENIPC_GENERIC; - if ( 1 == m_SelectedIndex ) - uBoardType |= BOARD_SUBTYPE_OPENIPC_AIO_ULTRASIGHT; - if ( 2 == m_SelectedIndex ) - uBoardType |= BOARD_SUBTYPE_OPENIPC_AIO_MARIO; - if ( 3 == m_SelectedIndex ) - uBoardType |= BOARD_SUBTYPE_OPENIPC_AIO_RUNCAM; - + uBoardType |= ((u32)m_SelectedIndex+1) << BOARD_SUBTYPE_SHIFT; + if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_VEHICLE_BOARD_TYPE, uBoardType, NULL, 0) ) valuesToUI(); } \ No newline at end of file diff --git a/code/r_central/menu/menu_confirmation_vehicle_board.h b/code/r_central/menu/menu_confirmation_vehicle_board.h index b54cf4b9..833a3e0f 100644 --- a/code/r_central/menu/menu_confirmation_vehicle_board.h +++ b/code/r_central/menu/menu_confirmation_vehicle_board.h @@ -8,6 +8,7 @@ class MenuConfirmationVehicleBoard: public Menu MenuConfirmationVehicleBoard(); virtual ~MenuConfirmationVehicleBoard(); virtual void onShow(); + virtual int onBack(); virtual void onSelectItem(); }; \ No newline at end of file diff --git a/code/r_central/menu/menu_controller.cpp b/code/r_central/menu/menu_controller.cpp index 53845f28..013a249c 100644 --- a/code/r_central/menu/menu_controller.cpp +++ b/code/r_central/menu/menu_controller.cpp @@ -47,6 +47,7 @@ #include "menu_preferences_buttons.h" #include "menu_preferences_ui.h" #include "menu_preferences.h" +#include "menu_controller_radio.h" #include "../../base/ctrl_settings.h" #include @@ -61,22 +62,22 @@ MenuController::MenuController(void) m_bShownHDMIChangeNotif = false; m_bWaitingForUserFinishUpdateConfirmation = false; m_iMustStartUpdate = 0; - - m_IndexPorts = addMenuItem(new MenuItem("Peripherals / Ports", "Change controller peripherals settings (serial ports, USB devices, HID, I2C devices, etc)")); - //m_pMenuItems[m_IndexPorts]->showArrow(); - + m_IndexVideo = addMenuItem(new MenuItem("Audio & Video Output", "Change Audio and Video Output Settings (HDMI, USB Tethering, Audio output device)")); //m_pMenuItems[m_IndexVideo]->showArrow(); m_IndexTelemetry = addMenuItem(new MenuItem("Telemetry Input/Output", "Change the Telemetry Input/Output settings on the controller ports.")); //m_pMenuItems[m_IndexTelemetry]->showArrow(); - m_IndexRecording = addMenuItem(new MenuItem("Recording", "Change the recording settings")); - //m_pMenuItems[m_IndexRecording]->showArrow(); + m_IndexRadio = addMenuItem(new MenuItem("Radio", "Configure the radio interfaces on the controller.")); + //m_pMenuItems[m_IndexTelemetry]->showArrow(); m_IndexCPU = addMenuItem(new MenuItem("CPU and Processes", "Set CPU Overclocking, Processes Priorities")); //m_pMenuItems[m_IndexCPU]->showArrow(); + m_IndexPorts = addMenuItem(new MenuItem("Peripherals / Ports", "Change controller peripherals settings (serial ports, USB devices, HID, I2C devices, etc)")); + //m_pMenuItems[m_IndexPorts]->showArrow(); + //m_pItemsSelect[1] = new MenuItemSelect("Show CPU Info in OSD", "Shows Controller CPU information (load, frequency, temperature) on the OSD, near the vehicle CPU info, when using OSD Full Layout."); //m_pItemsSelect[1]->addSelection("No"); //m_pItemsSelect[1]->addSelection("Yes"); @@ -92,7 +93,8 @@ MenuController::MenuController(void) m_IndexNetwork = addMenuItem(new MenuItem("Local Network Settings", "Change the local network settings on the controller (DHCP/Fixed IP)")); //m_pMenuItems[m_IndexNetwork]->showArrow(); - m_IndexEncryption = addMenuItem(new MenuItem("Encryption", "Change the encryption global settings")); + m_IndexEncryption = -1; + //m_IndexEncryption = addMenuItem(new MenuItem("Encryption", "Change the encryption global settings")); //m_pMenuItems[m_IndexEncryption]->showArrow(); //m_pMenuItems[m_IndexEncryption]->setEnabled(false); @@ -101,6 +103,9 @@ MenuController::MenuController(void) //m_IndexPreferences = addMenuItem(new MenuItem("Preferences", "Change preferences about messages.")); m_IndexPreferencesUI = addMenuItem(new MenuItem("User Interface", "Change user interface preferences.")); + m_IndexRecording = addMenuItem(new MenuItem("Recording Settings", "Change the recording settings")); + //m_pMenuItems[m_IndexRecording]->showArrow(); + ControllerSettings* pCS = get_ControllerSettings(); m_IndexDeveloper = -1; if ( (NULL != pCS) && pCS->iDeveloperMode ) @@ -280,6 +285,12 @@ void MenuController::onSelectItem() return; } + if ( m_IndexRadio == m_SelectedIndex ) + { + add_menu_to_stack(new MenuControllerRadio()); + return; + } + if ( m_IndexRecording == m_SelectedIndex ) { add_menu_to_stack(new MenuControllerRecording()); @@ -292,7 +303,7 @@ void MenuController::onSelectItem() return; } - if ( m_IndexEncryption == m_SelectedIndex ) + if ( (-1 != m_IndexEncryption) && (m_IndexEncryption == m_SelectedIndex) ) { add_menu_to_stack(new MenuControllerEncryption()); return; diff --git a/code/r_central/menu/menu_controller.h b/code/r_central/menu/menu_controller.h index 2f986528..db29f94d 100644 --- a/code/r_central/menu/menu_controller.h +++ b/code/r_central/menu/menu_controller.h @@ -21,7 +21,7 @@ class MenuController: public Menu int m_IndexButtons, m_IndexPreferences, m_IndexPreferencesUI, m_IndexPlugins, m_IndexReboot; int m_IndexUpdate; //int m_IndexShowCPUInfo, m_IndexShowVoltage; - int m_IndexNetwork, m_IndexEncryption; + int m_IndexNetwork, m_IndexEncryption, m_IndexRadio; int m_IndexVideo, m_IndexTelemetry, m_IndexRecording; bool m_bShownHDMIChangeNotif; int m_iMustStartUpdate; diff --git a/code/r_central/menu/menu_controller_dev.cpp b/code/r_central/menu/menu_controller_dev.cpp index e37671f8..6993a959 100644 --- a/code/r_central/menu/menu_controller_dev.cpp +++ b/code/r_central/menu/menu_controller_dev.cpp @@ -111,7 +111,7 @@ void MenuControllerDev::addItems() m_pItemsSlider[9]->setCurrentValue(pCS->iDevRxLoopTimeout); m_IndexRxLoopTimeout = addMenuItem(m_pItemsSlider[9]); - m_IndexDebugRTStatsGraphs = addMenuItem(new MenuItem("Real time debug stats graphs", "Show live monitor of Rx links and video stats")); + m_IndexDebugRTStatsGraphs = addMenuItem(new MenuItem("Show real time stats graphs", "Show live monitor of Rx links and video stats")); m_pMenuItems[m_IndexDebugRTStatsGraphs]->showArrow(); m_IndexDebugRTStatsConfig = addMenuItem(new MenuItem("Real time debug stats config", "Configure live monitor of Rx links and video stats")); diff --git a/code/r_central/menu/menu_controller_dev_stats.cpp b/code/r_central/menu/menu_controller_dev_stats.cpp index e4e7a7d9..4d243f30 100644 --- a/code/r_central/menu/menu_controller_dev_stats.cpp +++ b/code/r_central/menu/menu_controller_dev_stats.cpp @@ -72,12 +72,19 @@ void MenuControllerDevStatsConfig::addItems() m_pItemsSelect[0]->setIsEditable(); m_IndexQAButton = addMenuItem(m_pItemsSelect[0]); - m_pItemsSelect[1] = new MenuItemSelect("Show RX Video & Data packets", ""); + m_pItemsSelect[1] = new MenuItemSelect("Show RX/TX packets", ""); m_pItemsSelect[1]->addSelection("No"); m_pItemsSelect[1]->addSelection("Yes"); m_pItemsSelect[1]->setUseMultiViewLayout(); - m_pItemsSelect[1]->setSelectedIndex( (pP->uDebugStatsFlags & CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_VIDEO_DATA_PACKETS)?1:0); - m_IndexShowRXVideoDataPackets = addMenuItem(m_pItemsSelect[1]); + m_pItemsSelect[1]->setSelectedIndex( (pP->uDebugStatsFlags & CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_TX_PACKETS)?1:0); + m_IndexShowRXTXPackets = addMenuItem(m_pItemsSelect[1]); + + m_pItemsSelect[13] = new MenuItemSelect("Show Rx air gaps", ""); + m_pItemsSelect[13]->addSelection("No"); + m_pItemsSelect[13]->addSelection("Yes"); + m_pItemsSelect[13]->setUseMultiViewLayout(); + m_pItemsSelect[13]->setSelectedIndex( (pP->uDebugStatsFlags & CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_AIR_GAPS)?1:0); + m_IndexShowRXAirGaps = addMenuItem(m_pItemsSelect[13]); m_pItemsSelect[2] = new MenuItemSelect("Show RX H264/H265 frames", ""); m_pItemsSelect[2]->addSelection("No"); @@ -204,12 +211,20 @@ void MenuControllerDevStatsConfig::onSelectItem() pP->iDebugStatsQAButton = m_pItemsSelect[0]->getSelectedIndex(); } - if ( m_IndexShowRXVideoDataPackets == m_SelectedIndex ) + if ( m_IndexShowRXTXPackets == m_SelectedIndex ) { if ( m_pItemsSelect[1]->getSelectedIndex() != 0 ) - pP->uDebugStatsFlags |= CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_VIDEO_DATA_PACKETS; + pP->uDebugStatsFlags |= CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_TX_PACKETS; + else + pP->uDebugStatsFlags &= ~CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_TX_PACKETS; + } + + if ( m_IndexShowRXAirGaps == m_SelectedIndex ) + { + if ( m_pItemsSelect[13]->getSelectedIndex() != 0 ) + pP->uDebugStatsFlags |= CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_AIR_GAPS; else - pP->uDebugStatsFlags &= ~CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_VIDEO_DATA_PACKETS; + pP->uDebugStatsFlags &= ~CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_AIR_GAPS; } if ( m_IndexShowRxH264Frames == m_SelectedIndex ) diff --git a/code/r_central/menu/menu_controller_dev_stats.h b/code/r_central/menu/menu_controller_dev_stats.h index a66083af..3c74d7d0 100644 --- a/code/r_central/menu/menu_controller_dev_stats.h +++ b/code/r_central/menu/menu_controller_dev_stats.h @@ -19,7 +19,8 @@ class MenuControllerDevStatsConfig: public Menu MenuItemSlider* m_pItemsSlider[15]; int m_IndexQAButton; - int m_IndexShowRXVideoDataPackets; + int m_IndexShowRXTXPackets; + int m_IndexShowRXAirGaps; int m_IndexShowRxH264Frames; int m_IndexShowRxDBM; int m_IndexShowRxMissingPackets; diff --git a/code/r_central/menu/menu_controller_radio.cpp b/code/r_central/menu/menu_controller_radio.cpp new file mode 100644 index 00000000..162ac571 --- /dev/null +++ b/code/r_central/menu/menu_controller_radio.cpp @@ -0,0 +1,286 @@ +/* + Ruby Licence + Copyright (c) 2024 Petru Soroaga petrusoroaga@yahoo.com + All rights reserved. + + Redistribution and use in source and/or binary forms, with or without + modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Copyright info and developer info must be preserved as is in the user + interface, additions could be made to that info. + * Neither the name of the organization nor the + names of its contributors may be used to endorse or promote products + derived from this software without specific prior written permission. + * Military use is not permited. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE AUTHOR (PETRU SOROAGA) BE LIABLE FOR ANY + DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#include "menu.h" +#include "menu_objects.h" +#include "menu_controller_radio.h" +#include "menu_text.h" +#include "menu_item_section.h" +#include "menu_item_legend.h" +#include "menu_item_text.h" +#include "menu_confirmation.h" +#include "menu_radio_config.h" +#include "menu_tx_raw_power.h" +#include "../../base/ctrl_settings.h" +#include "../../base/tx_powers.h" +#include "../../utils/utils_controller.h" + +#include +#include + +MenuControllerRadio::MenuControllerRadio(void) +:Menu(MENU_ID_CONTROLLER_RADIO, "Controller Radio Settings", NULL) +{ + m_Width = 0.38; + m_xPos = menu_get_XStartPos(m_Width); m_yPos = 0.18; + m_iMaxPowerMw = 0; +} + +void MenuControllerRadio::onShow() +{ + int iTmp = getSelectedMenuItemIndex(); + + valuesToUI(); + Menu::onShow(); + invalidate(); + + m_SelectedIndex = iTmp; + if ( m_SelectedIndex >= m_ItemsCount ) + m_SelectedIndex = m_ItemsCount-1; +} + +void MenuControllerRadio::valuesToUI() +{ + ControllerSettings* pCS = get_ControllerSettings(); + + addItems(); + + int iMwPowers[MAX_RADIO_INTERFACES]; + int iCountPowers = 0; + for( int i=0; iisConfigurable) || (! pRadioHWInfo->isSupported) ) + continue; + + t_ControllerRadioInterfaceInfo* pCRII = controllerGetRadioCardInfo(pRadioHWInfo->szMAC); + if ( NULL == pCRII ) + continue; + int iDriver = pRadioHWInfo->iRadioDriver; + int iCardModel = pCRII->cardModel; + iMwPowers[iCountPowers] = tx_powers_convert_raw_to_mw(iDriver, iCardModel, pCRII->iRawPowerLevel); + log_line("MenuControllerRadio: Current radio interface %d tx raw power: %d (%d mW, index %d)", i+1, pCRII->iRawPowerLevel, iMwPowers[iCountPowers], iCountPowers); + + iCountPowers++; + } + + m_pItemsSelect[0]->setSelectedIndex(1-pCS->iFixedTxPower); + + if ( pCS->iFixedTxPower ) + { + m_iMaxPowerMw = tx_powers_get_max_usable_power_mw_for_controller(); + selectMenuItemTxPowersValue(m_pItemsSelect[1], false, &(iMwPowers[0]), iCountPowers, m_iMaxPowerMw); + } + else + { + m_pItemsSelect[1]->setSelectedIndex(0); + m_pItemsSelect[1]->setEnabled(false); + } +} + +void MenuControllerRadio::addItems() +{ + int iTmp = getSelectedMenuItemIndex(); + removeAllItems(); + + ControllerSettings* pCS = get_ControllerSettings(); + + int iMwPowers[MAX_RADIO_INTERFACES]; + int iCountPowers = 0; + for( int i=0; iisConfigurable) || (! pRadioHWInfo->isSupported) ) + continue; + + t_ControllerRadioInterfaceInfo* pCRII = controllerGetRadioCardInfo(pRadioHWInfo->szMAC); + if ( NULL == pCRII ) + continue; + + iMwPowers[iCountPowers] = pCRII->iRawPowerLevel; + iCountPowers++; + } + + m_pItemsSelect[0] = new MenuItemSelect("Controller Power Model", "Sets the transmission power mode for the controller side."); + m_pItemsSelect[0]->addSelection("Always use fixed power"); + m_pItemsSelect[0]->addSelection("Match current vehicle"); + m_pItemsSelect[0]->setIsEditable(); + m_IndexTxPowerMode = addMenuItem(m_pItemsSelect[0]); + + m_iMaxPowerMw = tx_powers_get_max_usable_power_mw_for_controller(); + m_pItemsSelect[1] = createMenuItemTxPowers("Radio Tx Power (mW)", pCS->iFixedTxPower?false:true, &(iMwPowers[0]), iCountPowers, m_iMaxPowerMw); + m_IndexTxPower = addMenuItem(m_pItemsSelect[1]); + + if ( (! pCS->iFixedTxPower) && (NULL != g_pCurrentModel) ) + { + int iCurrentMaxSetPowerMw = apply_controller_radio_tx_powers(g_pCurrentModel, pCS->iFixedTxPower, true); + char szText[128]; + sprintf(szText, "Current Tx Power: %d mW (%s)", iCurrentMaxSetPowerMw, getString(4)); + addMenuItem(new MenuItemText(szText, true)); + } + + MenuItemLegend* pLegend = NULL; + if ( pCS->iFixedTxPower ) + pLegend = new MenuItemLegend("Note", "Maximum selectable Tx power is computed based on detected radio interfaces on the controller.", 0, true); + else + pLegend = new MenuItemLegend("Note", "Maximum selectable Tx power is computed based on detected radio interfaces on the vehicle and controller.", 0, true); + + pLegend->setExtraHeight(0.4*g_pRenderEngine->textHeight(g_idFontMenu)); + addMenuItem(pLegend); + + m_IndexRadioConfig = addMenuItem(new MenuItem("Radio Links Config", "Full radio configuration")); + m_pMenuItems[m_IndexRadioConfig]->showArrow(); + + m_SelectedIndex = iTmp; + if ( m_SelectedIndex >= m_ItemsCount ) + m_SelectedIndex = m_ItemsCount-1; +} + +void MenuControllerRadio::Render() +{ + RenderPrepare(); + float yTop = RenderFrameAndTitle(); + float y = yTop; + + for( int i=0; iisEditing() ) + return; + + + ControllerSettings* pCS = get_ControllerSettings(); + if ( NULL == pCS ) + { + log_softerror_and_alarm("Failed to get pointer to controller settings structure"); + return; + } + + if ( m_IndexRadioConfig == m_SelectedIndex ) + { + MenuRadioConfig* pM = new MenuRadioConfig(); + add_menu_to_stack(pM); + return; + } + + if ( m_IndexTxPowerMode == m_SelectedIndex ) + { + ControllerSettings* pCS = get_ControllerSettings(); + pCS->iFixedTxPower = 1 - m_pItemsSelect[0]->getSelectedIndex(); + save_ControllerSettings(); + save_ControllerInterfacesSettings(); + apply_controller_radio_tx_powers(g_pCurrentModel, pCS->iFixedTxPower, false); + save_ControllerInterfacesSettings(); + valuesToUI(); + send_model_changed_message_to_router(MODEL_CHANGED_RADIO_POWERS, 0); + return; + } + + if ( m_IndexTxPower == m_SelectedIndex ) + { + ControllerSettings* pCS = get_ControllerSettings(); + int iIndex = m_pItemsSelect[1]->getSelectedIndex(); + if ( iIndex == m_pItemsSelect[1]->getSelectionsCount() -1 ) + { + MenuTXRawPower* pMenu = new MenuTXRawPower(); + pMenu->m_bShowVehicleSide = false; + add_menu_to_stack(pMenu); + return; + } + else + { + pCS->iFixedTxPower = 1; + + int iPowerLevelsCount = 0; + const int* piPowerLevelsMw = tx_powers_get_ui_levels_mw(&iPowerLevelsCount); + int iPowerMwToSet = piPowerLevelsMw[iIndex]; + log_line("MenuControllerRadio: Setting all cards mw tx power to: %d mw", iPowerMwToSet); + for( int i=0; iisConfigurable) || (! pRadioHWInfo->isSupported) ) + continue; + + t_ControllerRadioInterfaceInfo* pCRII = controllerGetRadioCardInfo(pRadioHWInfo->szMAC); + if ( NULL == pCRII ) + continue; + + int iDriver = pRadioHWInfo->iRadioDriver; + int iCardModel = pCRII->cardModel; + + int iCardMaxPowerMw = tx_powers_get_max_usable_power_mw_for_card(iDriver, iCardModel); + int iCardNewPowerMw = iPowerMwToSet; + if ( iCardNewPowerMw > iCardMaxPowerMw ) + iCardNewPowerMw = iCardMaxPowerMw; + int iTxPowerRawToSet = tx_powers_convert_mw_to_raw(iDriver, iCardModel, iCardNewPowerMw); + log_line("MenuControllerRadio: Setting tx raw power for card %d from %d to: %d (%d mw out of max %d mw for this card)", + i+1, pCRII->iRawPowerLevel, iTxPowerRawToSet, iCardNewPowerMw, iCardMaxPowerMw); + pCRII->iRawPowerLevel = iTxPowerRawToSet; + } + } + save_ControllerSettings(); + save_ControllerInterfacesSettings(); + apply_controller_radio_tx_powers(g_pCurrentModel, pCS->iFixedTxPower, false); + save_ControllerInterfacesSettings(); + valuesToUI(); + send_model_changed_message_to_router(MODEL_CHANGED_RADIO_POWERS, 0); + return; + } +} + diff --git a/code/r_central/menu/menu_controller_radio.h b/code/r_central/menu/menu_controller_radio.h new file mode 100644 index 00000000..cb76d587 --- /dev/null +++ b/code/r_central/menu/menu_controller_radio.h @@ -0,0 +1,28 @@ +#pragma once +#include "menu_objects.h" +#include "menu_item_select.h" +#include "menu_item_slider.h" + +class MenuControllerRadio: public Menu +{ + public: + MenuControllerRadio(); + virtual void Render(); + virtual void onShow(); + virtual void valuesToUI(); + virtual bool periodicLoop(); + virtual void onReturnFromChild(int iChildMenuId, int returnValue); + virtual void onSelectItem(); + + private: + void addItems(); + MenuItemSelect* m_pItemsSelect[15]; + MenuItemSlider* m_pItemsSlider[10]; + + int m_iMaxPowerMw; + + int m_IndexTxPowerMode; + int m_IndexTxPower; + int m_IndexRadioConfig; + +}; \ No newline at end of file diff --git a/code/r_central/menu/menu_controller_radio_interface.cpp b/code/r_central/menu/menu_controller_radio_interface.cpp index b08856f0..51f3ce53 100644 --- a/code/r_central/menu/menu_controller_radio_interface.cpp +++ b/code/r_central/menu/menu_controller_radio_interface.cpp @@ -32,10 +32,11 @@ #include "menu_objects.h" #include "menu_controller_radio_interface.h" #include "menu_text.h" -#include "menu_tx_power.h" +#include "menu_tx_raw_power.h" #include "menu_confirmation.h" #include "menu_item_section.h" #include "menu_item_text.h" +#include "../../base/tx_powers.h" #include #include @@ -169,12 +170,12 @@ void MenuControllerRadioInterface::valuesToUI() if ( pCardInfo->cardModel < 0 ) { - m_pItemsSelect[1]->setSelection(-pCardInfo->cardModel); + m_pItemsSelect[1]->setSelection(1-pCardInfo->cardModel); m_pItemsSelect[1]->setEnabled(true); } else { - m_pItemsSelect[1]->setSelection(pCardInfo->cardModel); + m_pItemsSelect[1]->setSelection(1+pCardInfo->cardModel); m_pItemsSelect[1]->setEnabled(true); } @@ -420,9 +421,19 @@ void MenuControllerRadioInterface::onSelectItem() t_ControllerRadioInterfaceInfo* pCardInfo = controllerGetRadioCardInfo(pNIC->szMAC); if ( NULL != pCardInfo ) { - pCardInfo->cardModel = m_pItemsSelect[1]->getSelectedIndex(); - if ( pCardInfo->cardModel > 0 ) - pCardInfo->cardModel = - pCardInfo->cardModel; + if ( 0 == m_pItemsSelect[1]->getSelectedIndex() ) + { + pCardInfo->cardModel = pNIC->iCardModel; + char szMsg[128]; + sprintf(szMsg, "The radio interface was autodetected as: %s", str_get_radio_card_model_string(pCardInfo->cardModel)); + addMessage2(0, szMsg, "The selected value was updated."); + } + else + { + pCardInfo->cardModel = m_pItemsSelect[1]->getSelectedIndex()-1; + if ( pCardInfo->cardModel > 0 ) + pCardInfo->cardModel = - pCardInfo->cardModel; + } save_ControllerInterfacesSettings(); valuesToUI(); } diff --git a/code/r_central/menu/menu_controller_radio_interface_sik.cpp b/code/r_central/menu/menu_controller_radio_interface_sik.cpp index 61444451..3835cac1 100644 --- a/code/r_central/menu/menu_controller_radio_interface_sik.cpp +++ b/code/r_central/menu/menu_controller_radio_interface_sik.cpp @@ -33,7 +33,7 @@ #include "menu_objects.h" #include "menu_controller_radio_interface_sik.h" #include "menu_text.h" -#include "menu_tx_power.h" +#include "menu_tx_raw_power.h" #include "menu_confirmation.h" #include "menu_item_section.h" #include "menu_item_text.h" diff --git a/code/r_central/menu/menu_controller_radio_interfaces.cpp b/code/r_central/menu/menu_controller_radio_interfaces.cpp index ecce581a..25649085 100644 --- a/code/r_central/menu/menu_controller_radio_interfaces.cpp +++ b/code/r_central/menu/menu_controller_radio_interfaces.cpp @@ -33,7 +33,6 @@ #include "menu_objects.h" #include "menu_controller_radio_interfaces.h" #include "menu_text.h" -#include "menu_txinfo.h" #include "menu_confirmation.h" #include "menu_item_section.h" #include "menu_item_text.h" diff --git a/code/r_central/menu/menu_controller_recording.cpp b/code/r_central/menu/menu_controller_recording.cpp index 05fe41ee..9ae364b4 100644 --- a/code/r_central/menu/menu_controller_recording.cpp +++ b/code/r_central/menu/menu_controller_recording.cpp @@ -39,7 +39,7 @@ MenuControllerRecording::MenuControllerRecording(void) :Menu(MENU_ID_CONTROLLER_RECORDING, "Video Recording Settings", NULL) { - m_Width = 0.29; + m_Width = 0.34; m_xPos = menu_get_XStartPos(m_Width); m_yPos = 0.12; int c = 0; @@ -88,6 +88,12 @@ MenuControllerRecording::MenuControllerRecording(void) m_pItemsSelect[c]->addSelection("Yes"); m_IndexRecordDisarm = addMenuItem(m_pItemsSelect[c]); c++; + + + float fSliderWidth = 0.12; + m_pItemsSlider[0] = new MenuItemSlider("Stop recording on link lost", "Sets a delay to automatically stop recording if link is lost for too long.", 10,100,20, fSliderWidth); + m_pItemsSlider[0]->setStep(1); + m_iIndexStopOnLinkLost = addMenuItem(m_pItemsSlider[0]); } void MenuControllerRecording::valuesToUI() @@ -117,6 +123,8 @@ void MenuControllerRecording::valuesToUI() m_pItemsSelect[5]->setSelection(p->iStartVideoRecOnArm); m_pItemsSelect[6]->setSelection(p->iStopVideoRecOnDisarm); + + m_pItemsSlider[0]->setCurrentValue(p->iStopRecordingAfterLinkLostSeconds); } void MenuControllerRecording::onShow() @@ -155,16 +163,13 @@ void MenuControllerRecording::onSelectItem() if ( m_IndexRecordIndicator == m_SelectedIndex ) { p->iShowBigRecordButton = m_pItemsSelect[2]->getSelectedIndex(); - save_Preferences(); } if ( m_IndexRecordLED == m_SelectedIndex ) { p->iRecordingLedAction = m_pItemsSelect[3]->getSelectedIndex(); - save_Preferences(); } - if ( m_IndexRecordButton == m_SelectedIndex ) { if ( 0 == m_pItemsSelect[4]->getSelectedIndex() ) @@ -200,21 +205,21 @@ void MenuControllerRecording::onSelectItem() if ( p->iActionQuickButton2 == quickActionVideoRecord ) p->iActionQuickButton2 = quickActionTakePicture; } - - save_Preferences(); } if ( m_IndexRecordArm == m_SelectedIndex ) { p->iStartVideoRecOnArm = m_pItemsSelect[5]->getSelectedIndex(); - save_Preferences(); } if ( m_IndexRecordDisarm == m_SelectedIndex ) { p->iStopVideoRecOnDisarm = m_pItemsSelect[6]->getSelectedIndex(); - save_Preferences(); } + if ( m_iIndexStopOnLinkLost == m_SelectedIndex ) + { + p->iStopRecordingAfterLinkLostSeconds = m_pItemsSlider[0]->getCurrentValue(); + } save_Preferences(); } diff --git a/code/r_central/menu/menu_controller_recording.h b/code/r_central/menu/menu_controller_recording.h index 1f87dfba..dff60511 100644 --- a/code/r_central/menu/menu_controller_recording.h +++ b/code/r_central/menu/menu_controller_recording.h @@ -12,7 +12,9 @@ class MenuControllerRecording: public Menu virtual void valuesToUI(); private: - MenuItemSelect* m_pItemsSelect[25]; + MenuItemSelect* m_pItemsSelect[10]; + MenuItemSlider* m_pItemsSlider[5]; int m_IndexRecordIndicator, m_IndexRecordArm, m_IndexRecordDisarm, m_IndexRecordButton, m_IndexRecordLED; int m_IndexVideoDestination; + int m_iIndexStopOnLinkLost; }; \ No newline at end of file diff --git a/code/r_central/menu/menu_item_legend.cpp b/code/r_central/menu/menu_item_legend.cpp index cf0d4d46..075fa81a 100644 --- a/code/r_central/menu/menu_item_legend.cpp +++ b/code/r_central/menu/menu_item_legend.cpp @@ -39,6 +39,24 @@ MenuItemLegend::MenuItemLegend(const char* szTitle, const char* szDesc, float ma { m_bEnabled = false; m_bIsEditable = false; + m_bSmall = false; + m_fMarginX = Menu::getMenuPaddingX(); + m_fMaxWidth = maxWidth; + m_pszTitle = (char*)malloc(strlen(szTitle)+7); + //strcpy(m_pszTitle, "• "); + //strcat(m_pszTitle, szTitle); + strcpy(m_pszTitle, szTitle); + if ( NULL != szDesc && 0 < strlen(szDesc) ) + strcat(m_pszTitle, ":"); +} + + +MenuItemLegend::MenuItemLegend(const char* szTitle, const char* szDesc, float maxWidth, bool bSmall) +:MenuItem(szTitle, szDesc) +{ + m_bEnabled = false; + m_bIsEditable = false; + m_bSmall = bSmall; m_fMarginX = Menu::getMenuPaddingX(); m_fMaxWidth = maxWidth; m_pszTitle = (char*)malloc(strlen(szTitle)+7); @@ -55,24 +73,47 @@ MenuItemLegend::~MenuItemLegend() float MenuItemLegend::getItemHeight(float maxWidth) { - MenuItem::getItemHeight(maxWidth); + int iFont = g_idFontMenu; + if ( m_bSmall ) + iFont = g_idFontMenuSmall; + + m_RenderTitleHeight = g_pRenderEngine->textHeight(iFont); + m_RenderHeight = m_RenderTitleHeight + m_fExtraHeight; + getTitleWidth(maxWidth); if ( maxWidth > 0.0001 ) getValueWidth(maxWidth-m_RenderTitleWidth-Menu::getMenuPaddingX()); else getValueWidth(0); - float h = g_pRenderEngine->getMessageHeight(m_pszTooltip, MENU_TEXTLINE_SPACING, m_RenderValueWidth, g_idFontMenu); + float h = 0.0; + if ( (NULL != m_pszTooltip) && (0 != m_pszTooltip[0]) ) + h = g_pRenderEngine->getMessageHeight(m_pszTooltip, MENU_TEXTLINE_SPACING, m_RenderValueWidth, iFont); if ( h > m_RenderHeight ) m_RenderHeight = h; + + m_RenderHeight += 0.3 * g_pRenderEngine->textHeight(iFont); return m_RenderHeight + m_fExtraHeight; } float MenuItemLegend::getTitleWidth(float maxWidth) { + int iFont = g_idFontMenu; + if ( m_bSmall ) + iFont = g_idFontMenuSmall; + if ( m_fMaxWidth > 0.001 ) - return MenuItem::getTitleWidth(m_fMaxWidth); + { + if ( m_RenderTitleWidth > 0.001 ) + return m_RenderTitleWidth; + + m_RenderTitleWidth = g_pRenderEngine->textWidth(iFont, m_pszTitle); - m_RenderTitleWidth = g_pRenderEngine->getMessageHeight(m_pszTitle, MENU_TEXTLINE_SPACING, maxWidth - m_fMarginX, g_idFontMenu); + if ( m_bShowArrow ) + m_RenderTitleWidth += 0.66*g_pRenderEngine->textHeight(iFont); + return m_RenderTitleWidth; + } + + m_RenderTitleWidth = g_pRenderEngine->getMessageHeight(m_pszTitle, MENU_TEXTLINE_SPACING, maxWidth - m_fMarginX, iFont); return m_RenderTitleWidth; } @@ -90,10 +131,15 @@ void MenuItemLegend::Render(float xPos, float yPos, bool bSelected, float fWidth g_pRenderEngine->setColors(get_Color_MenuText()); - g_pRenderEngine->drawText(xPos, yPos, g_idFontMenu, m_pszTitle); - //g_pRenderEngine->drawMessageLines(xPos, yPos, m_pszTitle, MENU_TEXTLINE_SPACING, m_RenderTitleWidth, g_idFontMenu); + int iFont = g_idFontMenu; + if ( m_bSmall ) + iFont = g_idFontMenuSmall; + + g_pRenderEngine->drawText(xPos, yPos, iFont, m_pszTitle); + //g_pRenderEngine->drawMessageLines(xPos, yPos, m_pszTitle, MENU_TEXTLINE_SPACING, m_RenderTitleWidth, iFont); xPos += m_RenderTitleWidth + Menu::getMenuPaddingX(); - g_pRenderEngine->drawMessageLines(xPos, yPos, m_pszTooltip, MENU_TEXTLINE_SPACING, m_RenderValueWidth, g_idFontMenu); + if ( (NULL != m_pszTooltip) && (0 != m_pszTooltip[0]) ) + g_pRenderEngine->drawMessageLines(xPos, yPos, m_pszTooltip, MENU_TEXTLINE_SPACING, m_RenderValueWidth, iFont); } diff --git a/code/r_central/menu/menu_item_legend.h b/code/r_central/menu/menu_item_legend.h index e88dd9b4..ce59b75e 100644 --- a/code/r_central/menu/menu_item_legend.h +++ b/code/r_central/menu/menu_item_legend.h @@ -5,6 +5,7 @@ class MenuItemLegend: public MenuItem { public: MenuItemLegend(const char* szTitle, const char* szDesc, float maxWidth); + MenuItemLegend(const char* szTitle, const char* szDesc, float maxWidth, bool bSmall); virtual ~MenuItemLegend(); virtual float getItemHeight(float maxWidth); @@ -16,6 +17,7 @@ class MenuItemLegend: public MenuItem protected: + bool m_bSmall; float m_fMarginX; float m_fMaxWidth; }; diff --git a/code/r_central/menu/menu_item_select.cpp b/code/r_central/menu/menu_item_select.cpp index 4b7ef2ab..e6dde696 100644 --- a/code/r_central/menu/menu_item_select.cpp +++ b/code/r_central/menu/menu_item_select.cpp @@ -383,8 +383,15 @@ void MenuItemSelect::RenderPopupSelections(float xPos, float yPos, bool bSelecte else { if ( ! m_bEnabledItems[i] ) - { g_pRenderEngine->setColors(get_Color_MenuItemDisabledText()); + if ( i == m_SelectedIndexBeforeEdit ) + { + g_pRenderEngine->setFill(0,0,0,0); + g_pRenderEngine->drawRoundRect(xValues-selectionPaddingH, y - selectionPaddingV + g_pRenderEngine->getPixelHeight(), width_text+2.0*selectionPaddingH , m_RenderHeight + 2.0*selectionPaddingV - 2.0 * g_pRenderEngine->getPixelHeight(), 0.2*Menu::getMenuPaddingY()); + if ( m_bCustomTextColor ) + g_pRenderEngine->setColors(&m_TextColor[0]); + else + g_pRenderEngine->setColors(get_Color_MenuText()); } g_pRenderEngine->drawText(xValues, y, g_idFontMenu, m_szSelections[i]); if ( m_bCustomTextColor ) diff --git a/code/r_central/menu/menu_item_select_base.cpp b/code/r_central/menu/menu_item_select_base.cpp index d792b4cb..7b935c4b 100644 --- a/code/r_central/menu/menu_item_select_base.cpp +++ b/code/r_central/menu/menu_item_select_base.cpp @@ -88,6 +88,19 @@ int MenuItemSelectBase::addSelection(const char* szText, bool bEnabled) return i; } +void MenuItemSelectBase::updateSelectionText(int iIndex, const char* szText) +{ + if ( (iIndex < 0) || (iIndex >= m_SelectionsCount) ) + return; + if ( NULL == szText ) + return; + + if ( NULL != m_szSelections[iIndex] ) + free(m_szSelections[iIndex]); + m_szSelections[iIndex] = (char*)malloc(strlen(szText)+1); + strcpy(m_szSelections[iIndex], szText); +} + void MenuItemSelectBase::setSelection(int index) { if ( index >= 0 && index < m_SelectionsCount ) @@ -126,6 +139,13 @@ void MenuItemSelectBase::restoreSelectedIndex() m_SelectedIndex = m_SelectedIndexBeforeEdit; } +char* MenuItemSelectBase::getSelectionIndexText(int iSelectionIndex) +{ + if ( (iSelectionIndex < 0) || (iSelectionIndex >= m_SelectionsCount) ) + return NULL; + return m_szSelections[iSelectionIndex]; +} + void MenuItemSelectBase::disableClick() { m_bDisabledClick = true; diff --git a/code/r_central/menu/menu_item_select_base.h b/code/r_central/menu/menu_item_select_base.h index 6d10bd75..4f6a603f 100644 --- a/code/r_central/menu/menu_item_select_base.h +++ b/code/r_central/menu/menu_item_select_base.h @@ -13,6 +13,7 @@ class MenuItemSelectBase: public MenuItem void removeAllSelections(); int addSelection(const char* szText); int addSelection(const char* szText, bool bEnabled); + void updateSelectionText(int iIndex, const char* szText); void setSelection(int index); void setSelectedIndex(int index); void setSelectionIndexDisabled(int index); @@ -22,6 +23,7 @@ class MenuItemSelectBase: public MenuItem int getSelectedIndex(); int getSelectionsCount(); void restoreSelectedIndex(); + char* getSelectionIndexText(int iSelectionIndex); virtual void beginEdit(); virtual void endEdit(bool bCanceled); virtual void onClick(); diff --git a/code/r_central/menu/menu_item_slider.cpp b/code/r_central/menu/menu_item_slider.cpp index bf4eb183..392f5465 100644 --- a/code/r_central/menu/menu_item_slider.cpp +++ b/code/r_central/menu/menu_item_slider.cpp @@ -45,6 +45,7 @@ MenuItemSlider::MenuItemSlider(const char* title, int min, int max, int mid, flo m_bIsEditable = true; m_Step = 1; m_HalfStepsEnabled = false; + m_szSufix[0] = 0; } MenuItemSlider::MenuItemSlider(const char* title, const char* tooltip, int min, int max, int mid, float sliderWidth) @@ -58,6 +59,7 @@ MenuItemSlider::MenuItemSlider(const char* title, const char* tooltip, int min, m_bIsEditable = true; m_Step = 1; m_HalfStepsEnabled = false; + m_szSufix[0] = 0; } MenuItemSlider::~MenuItemSlider() @@ -100,6 +102,16 @@ void MenuItemSlider::setMaxValue(int val) m_ValueMax = val; } +void MenuItemSlider::setSufix(const char* szSufix) +{ + if ( (NULL == szSufix) || (0 == szSufix[0]) ) + { + m_szSufix[0] = 0; + return; + } + strncpy(m_szSufix, szSufix, 31); +} + void MenuItemSlider::beginEdit() { m_ValuePrev = m_ValueCurrent; @@ -118,13 +130,25 @@ void MenuItemSlider::Render(float xPos, float yPos, bool bSelected, float fWidth { RenderBaseTitle(xPos, yPos, bSelected, fWidthSelection); - char szBuff[32]; - sprintf(szBuff, "%d", m_ValueCurrent); + char szValue[64]; + sprintf(szValue, "%d", m_ValueCurrent); if ( m_HalfStepsEnabled ) - sprintf(szBuff, "%.2f", m_ValueCurrent/4.0); + sprintf(szValue, "%.2f", m_ValueCurrent/4.0); + if ( 0 != m_szSufix[0] ) + { + strcat(szValue, " "); + strcat(szValue, m_szSufix); + } float height_text = g_pRenderEngine->textHeight(g_idFontMenu); float valueWidth = g_pRenderEngine->textWidth(g_idFontMenu, "AAA"); + if ( m_ValueMax > 999 ) + valueWidth += g_pRenderEngine->textWidth(g_idFontMenu, "A"); + if ( 0 != m_szSufix[0] ) + { + valueWidth += g_pRenderEngine->textWidth(g_idFontMenu, " "); + valueWidth += g_pRenderEngine->textWidth(g_idFontMenu, m_szSufix); + } float valueMargin = 0.4*height_text; float paddingV = Menu::getSelectionPaddingY(); float paddingH = Menu::getSelectionPaddingX(); @@ -179,7 +203,7 @@ void MenuItemSlider::Render(float xPos, float yPos, bool bSelected, float fWidth g_pRenderEngine->setStrokeSize(0); - g_pRenderEngine->drawTextLeft(xPosSlider-valueMargin, yPos, g_idFontMenu, szBuff); + g_pRenderEngine->drawTextLeft(xPosSlider-valueMargin, yPos, g_idFontMenu, szValue); g_pRenderEngine->setStrokeSize(1); g_pRenderEngine->drawRoundRect(xPosSelector, yTop, fSizeSelectorW, fSizeSelectorH, 0.1*Menu::getMenuPaddingY()); diff --git a/code/r_central/menu/menu_item_slider.h b/code/r_central/menu/menu_item_slider.h index 5bfdf73e..3301c0aa 100644 --- a/code/r_central/menu/menu_item_slider.h +++ b/code/r_central/menu/menu_item_slider.h @@ -13,6 +13,7 @@ class MenuItemSlider: public MenuItem void setCurrentValue(int val); void setMaxValue(int val); int getCurrentValue(); + void setSufix(const char* szSufix); virtual void beginEdit(); virtual void endEdit(bool bCanceled); @@ -33,4 +34,5 @@ class MenuItemSlider: public MenuItem int m_ValuePrev; int m_Step; bool m_HalfStepsEnabled; + char m_szSufix[32]; }; diff --git a/code/r_central/menu/menu_item_text.cpp b/code/r_central/menu/menu_item_text.cpp index 2e216a87..fd7f6fac 100644 --- a/code/r_central/menu/menu_item_text.cpp +++ b/code/r_central/menu/menu_item_text.cpp @@ -42,7 +42,7 @@ MenuItemText::MenuItemText(const char* title) m_bIsEditable = false; m_bUseSmallText = false; m_fScale = 1.0; - m_fMarginX = 0.5 * Menu::getMenuPaddingX(); + m_fMarginX = 0;// 0.5 * Menu::getMenuPaddingX(); } MenuItemText::MenuItemText(const char* title, bool bUseSmallText) @@ -53,7 +53,7 @@ MenuItemText::MenuItemText(const char* title, bool bUseSmallText) m_bIsEditable = false; m_bUseSmallText = bUseSmallText; m_fScale = 1.0; - m_fMarginX = 0.5 * Menu::getMenuPaddingX(); + m_fMarginX = 0; //0.5 * Menu::getMenuPaddingX(); } MenuItemText::MenuItemText(const char* title, bool bUseSmallText, float fMargin) diff --git a/code/r_central/menu/menu_negociate_radio.cpp b/code/r_central/menu/menu_negociate_radio.cpp index 8f0eecb0..3ab02c0b 100644 --- a/code/r_central/menu/menu_negociate_radio.cpp +++ b/code/r_central/menu/menu_negociate_radio.cpp @@ -67,6 +67,10 @@ MenuNegociateRadio::MenuNegociateRadio(void) m_iDataRateToApply = 0; m_iDataRateIndex = 0; m_iDataRateTestCount = 0; + m_iCountSucceededSteps = 0; + m_iCountFailedSteps = 0; + m_bWaitingCancelConfirmationFromUser = false; + g_bAskedForNegociateRadioLink = true; _switch_to_step(NEGOCIATE_RADIO_STEP_DATA_RATE); } @@ -233,33 +237,7 @@ void MenuNegociateRadio::_switch_to_step(int iStep) if ( m_iStep == NEGOCIATE_RADIO_STEP_END ) { strcpy(m_szStatusMessage, "Done. Saving parameters."); - - m_iDataRateToApply = 0; - - _computeQualities(); - float fQuality18 = m_fQualities[0]; - float fQuality24 = m_fQualities[1]; - float fQuality48 = m_fQualities[3]; - float fQualityMCS2 = m_fQualities[6]; - float fQualityMCS3 = m_fQualities[7]; - float fQualityMCS4 = m_fQualities[8]; - - if ( fQualityMCS4 > 0.99 ) - m_iDataRateToApply = -5; - else if ( fQualityMCS3 > 0.99 ) - m_iDataRateToApply = -4; - else if ( fQualityMCS2 > fQuality18 ) - m_iDataRateToApply = -3; - else if ( fQuality48 > 0.99 ) - m_iDataRateToApply = 48000000; - else if ( fQuality24 > 0.99 ) - m_iDataRateToApply = 24000000; - else - m_iDataRateToApply = 18000000; - - log_line("Computed Q: 18: %.3f, 24: %.3f, 48: %.3f, MCS2: %.3f, MCS3: %.3f, MCS4: %.3f ", - fQuality18, fQuality24, fQuality48, fQualityMCS2, fQualityMCS3, fQualityMCS4); - log_line("Appling datarate: %d", m_iDataRateToApply); + _apply_new_settings(); } if ( m_iStep == NEGOCIATE_RADIO_STEP_CANCEL ) strcpy(m_szStatusMessage, "Canceling, please wait."); @@ -270,6 +248,80 @@ void MenuNegociateRadio::_switch_to_step(int iStep) } +void MenuNegociateRadio::_advance_to_next_step() +{ + if ( m_iStep != NEGOCIATE_RADIO_STEP_DATA_RATE ) + return; + + if ( m_iCountFailedSteps >= 6 ) + { + log_softerror_and_alarm("Failed 6 data steps. Aborting operation."); + _switch_to_step(NEGOCIATE_RADIO_STEP_CANCEL); + return; + } + + if ( m_iDataRateIndex >= g_ArrayTestRadioRatesCount ) + { + _switch_to_step(NEGOCIATE_RADIO_STEP_END); + return; + } + + m_iDataRateTestCount++; + if ( m_iDataRateTestCount > 2 ) + { + m_iDataRateIndex++; + m_iDataRateTestCount = 0; + } + if ( m_iDataRateIndex >= g_ArrayTestRadioRatesCount ) + m_iStep = NEGOCIATE_RADIO_STEP_END; + _switch_to_step(m_iStep); +} + +void MenuNegociateRadio::_apply_new_settings() +{ + m_iDataRateToApply = 0; + + _computeQualities(); + float fQuality18 = m_fQualities[0]; + float fQuality24 = m_fQualities[1]; + float fQuality48 = m_fQualities[3]; + float fQualityMCS2 = m_fQualities[6]; + float fQualityMCS3 = m_fQualities[7]; + float fQualityMCS4 = m_fQualities[8]; + + if ( fQualityMCS4 > 0.99 ) + m_iDataRateToApply = -5; + else if ( fQualityMCS3 > 0.99 ) + m_iDataRateToApply = -4; + else if ( fQualityMCS2 > fQuality18 ) + m_iDataRateToApply = -3; + else if ( fQuality48 > 0.99 ) + m_iDataRateToApply = 48000000; + else if ( fQuality24 > 0.99 ) + m_iDataRateToApply = 24000000; + else + m_iDataRateToApply = 18000000; + + log_line("Computed Q: 18: %.3f, 24: %.3f, 48: %.3f, MCS2: %.3f, MCS3: %.3f, MCS4: %.3f ", + fQuality18, fQuality24, fQuality48, fQualityMCS2, fQualityMCS3, fQualityMCS4); + log_line("Appling datarate: %d (%u bps)", m_iDataRateToApply, getRealDataRateFromRadioDataRate(m_iDataRateToApply, 0)); + log_line("Max/Min video bitrate interval to set: %u / %u bps", + (getRealDataRateFromRadioDataRate(m_iDataRateToApply, 0) / 100 ) * DEFAULT_VIDEO_LINK_LOAD_PERCENT, + (getRealDataRateFromRadioDataRate(m_iDataRateToApply, 0) / 100 ) * 30 ); + + if ( NULL != g_pCurrentModel ) + { + for( int i=0; ivideo_link_profiles[i].bitrate_fixed_bps / 100) * DEFAULT_VIDEO_LINK_LOAD_PERCENT > getRealDataRateFromRadioDataRate(m_iDataRateToApply, 0) ) + g_pCurrentModel->video_link_profiles[i].bitrate_fixed_bps = (getRealDataRateFromRadioDataRate(m_iDataRateToApply, 0) / 100 )* DEFAULT_VIDEO_LINK_LOAD_PERCENT; + + if ( (i == VIDEO_PROFILE_USER) || (i == VIDEO_PROFILE_HIGH_QUALITY) ) + if ( (g_pCurrentModel->video_link_profiles[i].bitrate_fixed_bps / 100) * 30 < getRealDataRateFromRadioDataRate(m_iDataRateToApply, 0) ) + g_pCurrentModel->video_link_profiles[i].bitrate_fixed_bps = (getRealDataRateFromRadioDataRate(m_iDataRateToApply, 0) / 100 ) * 30; + } + } +} bool MenuNegociateRadio::periodicLoop() { @@ -287,9 +339,30 @@ bool MenuNegociateRadio::periodicLoop() if ( m_bWaitingVehicleConfirmation ) { - if ( g_TimeNow > m_uLastTimeSendCommandToVehicle + 100 ) - { + if ( (g_TimeNow > m_uLastTimeSendCommandToVehicle + 100) && (!m_bWaitingCancelConfirmationFromUser) && (g_TimeNow < m_uStepStartTime + 3000) ) _send_command_to_vehicle(); + if ( (g_TimeNow > m_uStepStartTime + 3000) && (!m_bWaitingCancelConfirmationFromUser) ) + { + m_iCountFailedSteps++; + if ( (m_iStep == NEGOCIATE_RADIO_STEP_CANCEL) || (m_iStep == NEGOCIATE_RADIO_STEP_END) ) + { + if ( m_iCountFailedSteps >= 6 ) + { + setModal(false); + menu_stack_pop(0); + m_bWaitingCancelConfirmationFromUser = true; + log_line("Timing out operation with 6 failed steps."); + addMessage2(0, "Failed to negociate radio links.", "You radio links quality is very poor. Please fix the physical radio links quality and try again later."); + } + else + { + setModal(false); + menu_stack_pop(0); + } + return false; + } + else + _advance_to_next_step(); } } else @@ -305,18 +378,8 @@ bool MenuNegociateRadio::periodicLoop() } if ( g_TimeNow > m_uStepStartTime + 2000 ) { - if ( m_iDataRateIndex < g_ArrayTestRadioRatesCount ) - { - m_iDataRateTestCount++; - if ( m_iDataRateTestCount > 2 ) - { - m_iDataRateIndex++; - m_iDataRateTestCount = 0; - } - if ( m_iDataRateIndex >= g_ArrayTestRadioRatesCount ) - m_iStep = NEGOCIATE_RADIO_STEP_END; - _switch_to_step(m_iStep); - } + m_iCountSucceededSteps++; + _advance_to_next_step(); } } return false; @@ -360,16 +423,36 @@ void MenuNegociateRadio::onReceivedVehicleResponse(u8* pPacketData, int iPacketL g_pCurrentModel->radioLinksParams.uGlobalRadioLinksFlags |= MODEL_RADIOLINKS_FLAGS_HAS_NEGOCIATED_LINKS; saveControllerModel(g_pCurrentModel); send_model_changed_message_to_router(MODEL_CHANGED_GENERIC, 0); + g_bMustNegociateRadioLinksFlag = false; + } + if ( (uCommand == NEGOCIATE_RADIO_STEP_CANCEL) && (m_iCountFailedSteps >= 6) ) + { + setModal(false); + menu_stack_pop(0); + m_bWaitingCancelConfirmationFromUser = true; + log_line("Finishing up operation with 6 failed steps."); + addMessage2(0, "Failed to negociate radio links.", "You radio links quality is very poor. Please fix the physical radio links quality and try again later."); + } + else + { + setModal(false); + menu_stack_pop(0); } - setModal(false); - menu_stack_pop(0); } + m_bWaitingVehicleConfirmation = false; } void MenuNegociateRadio::onReturnFromChild(int iChildMenuId, int returnValue) { Menu::onReturnFromChild(iChildMenuId, returnValue); + if ( m_bWaitingCancelConfirmationFromUser ) + { + log_line("User confirmed canceled operation. Close menu."); + //setModal(false); + menu_stack_pop(0); + menu_rearrange_all_menus_no_animation(); + } } void MenuNegociateRadio::_onCancel() diff --git a/code/r_central/menu/menu_negociate_radio.h b/code/r_central/menu/menu_negociate_radio.h index da6ccebc..0aed0ac1 100644 --- a/code/r_central/menu/menu_negociate_radio.h +++ b/code/r_central/menu/menu_negociate_radio.h @@ -20,6 +20,8 @@ class MenuNegociateRadio: public Menu void _computeQualities(); void _send_command_to_vehicle(); void _switch_to_step(int iStep); + void _advance_to_next_step(); + void _apply_new_settings(); void _onCancel(); MenuItemSelect* m_pItemsSelect[10]; int m_MenuIndexCancel; @@ -29,10 +31,13 @@ class MenuNegociateRadio: public Menu u32 m_uStepStartTime; u32 m_uLastTimeSendCommandToVehicle; bool m_bWaitingVehicleConfirmation; + bool m_bWaitingCancelConfirmationFromUser; int m_iStep; int m_iDataRateIndex; int m_iDataRateTestCount; int m_iDataRateToApply; + int m_iCountSucceededSteps; + int m_iCountFailedSteps; int m_iRXPackets[20][MAX_RADIO_INTERFACES][3]; int m_iRxLostPackets[20][MAX_RADIO_INTERFACES][3]; diff --git a/code/r_central/menu/menu_objects.cpp b/code/r_central/menu/menu_objects.cpp index b9415e72..65db4800 100644 --- a/code/r_central/menu/menu_objects.cpp +++ b/code/r_central/menu/menu_objects.cpp @@ -45,6 +45,7 @@ #include "../process_router_messages.h" #include "../render_commands.h" #include "../keyboard.h" +#include "../../base/tx_powers.h" #define MENU_ALFA_WHEN_IN_BG 0.5 @@ -186,6 +187,17 @@ float Menu::getScaleFactor() return m_sfScaleFactor; } +int Menu::getId() +{ + return m_MenuId; +} + +void Menu::setId(int iId) +{ + m_MenuId = iId; +} + + void Menu::setParent(Menu* pParent) { m_pParent = pParent; @@ -216,6 +228,11 @@ void Menu::disableScrolling() invalidate(); } +char* Menu::getTitle() +{ + return m_szTitle; +} + void Menu::setTitle(const char* szTitle) { if ( NULL == szTitle ) @@ -247,7 +264,7 @@ void Menu::removeAllTopLines() void Menu::addTopLine(const char* szLine, float dx) { - if ( m_TopLinesCount >= MENU_MAX_TOP_LINES-1 || NULL == szLine ) + if ( (m_TopLinesCount >= MENU_MAX_TOP_LINES-1) || (NULL == szLine) ) return; m_fTopLinesDX[m_TopLinesCount] = dx; m_szTopLines[m_TopLinesCount] = (char*)malloc(strlen(szLine)+1); @@ -434,12 +451,21 @@ float Menu::getRenderXPos() return m_RenderXPos; } +void Menu::resetRenderXPos() +{ + m_RenderXPos = m_xPos; + m_fAnimationTargetXPos = m_xPos; + m_uAnimationStartTime = 0; + m_bIsAnimationInProgress = false; +} + void Menu::onShow() { - log_line("[Menu] (loop %u) [%s] on show (%s): xPos: %.2f, xRenderPos: %.2f", - menu_get_loop_counter()%1000, m_szTitle, m_bFirstShow? "first show":"not first show", m_xPos, m_RenderXPos); if ( m_bDisableStacking ) m_RenderXPos = m_xPos; + log_line("[Menu] (loop %u) [%s] on show (id: %d, title: %s, ptr: 0x%X): xPos: %.2f, xRenderPos: %.2f", + menu_get_loop_counter()%1000, m_bFirstShow? "first show":"not first show", + m_MenuId, m_szTitle, this, m_xPos, m_RenderXPos); m_bFirstShow = false; if ( 0 == m_uOnShowTime ) @@ -1852,11 +1878,11 @@ bool Menu::checkIsArmed() void Menu::addMessageWithTitle(int iId, const char* szTitle, const char* szMessage) { - Menu* pm = new Menu(MENU_ID_SIMPLE_MESSAGE + iId*1000, szTitle,NULL); + Menu* pm = new MenuConfirmation(szTitle, szMessage, MENU_ID_SIMPLE_MESSAGE + iId*1000, true); + pm->setId(MENU_ID_SIMPLE_MESSAGE + iId*1000); pm->m_xPos = 0.32; pm->m_yPos = 0.4; pm->m_Width = 0.36; pm->m_bDisableStacking = true; - pm->addTopLine(szMessage); add_menu_to_stack(pm); } @@ -1867,22 +1893,23 @@ void Menu::addMessage(const char* szMessage) void Menu::addMessage(int iId, const char* szMessage) { - Menu* pm = new Menu(MENU_ID_SIMPLE_MESSAGE + iId*1000, "Info",NULL); + Menu* pm = new MenuConfirmation("Info", szMessage, MENU_ID_SIMPLE_MESSAGE + iId*1000, true); + pm->setId(MENU_ID_SIMPLE_MESSAGE + iId*1000); pm->m_xPos = 0.32; pm->m_yPos = 0.4; pm->m_Width = 0.36; pm->m_bDisableStacking = true; - pm->addTopLine(szMessage); add_menu_to_stack(pm); } void Menu::addMessage2(int iId, const char* szMessage, const char* szLine2) { - Menu* pm = new Menu(MENU_ID_SIMPLE_MESSAGE + iId*1000, "Info",NULL); + Menu* pm = new MenuConfirmation("Info", szMessage, MENU_ID_SIMPLE_MESSAGE + iId*1000, true); + pm->setId(MENU_ID_SIMPLE_MESSAGE + iId*1000); pm->m_xPos = 0.32; pm->m_yPos = 0.4; pm->m_Width = 0.36; pm->m_bDisableStacking = true; - pm->addTopLine(szMessage); - pm->addTopLine(szLine2); + if ( NULL != szLine2 ) + pm->addTopLine(szLine2); add_menu_to_stack(pm); } @@ -1955,14 +1982,6 @@ static void * _thread_generate_upload(void *argument) } // Done - Check and create update info file if missing - bool bVersion82Older = false; - if ( NULL == g_pCurrentModel ) - bVersion82Older = true; - else if ( ((g_pCurrentModel->sw_version>>8) & 0xFF) < 8 ) - bVersion82Older = true; - else if ( (((g_pCurrentModel->sw_version>>8) & 0xFF) == 8) && (((g_pCurrentModel->sw_version & 0xFF) <= 30)) ) - bVersion82Older = true; - char szFullPathOutputArchive[MAX_FILE_PATH_SIZE]; strcpy(szFullPathOutputArchive, FOLDER_UPDATES); strcat(szFullPathOutputArchive, szFileNameArchive); @@ -1997,15 +2016,6 @@ static void * _thread_generate_upload(void *argument) return NULL; } - // Generate dummy ruby_vehicle binary for older versions of vehicles - if ( bVersion82Older ) - { - sprintf(szComm, "echo 'dummy' > %s/ruby_vehicle", szFolderLocalUpdateBinaries); - hw_execute_bash_command(szComm, NULL); - sprintf(szComm, "chmod 777 %s/ruby_vehicle", szFolderLocalUpdateBinaries); - hw_execute_bash_command(szComm, NULL); - } - snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "chmod 777 %s* 2>/dev/null", szPathTempUpload); hw_execute_bash_command(szComm, NULL); @@ -2020,6 +2030,9 @@ static void * _thread_generate_upload(void *argument) snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %s* %s 2>/dev/null", szFolderLocalUpdateBinaries, szPathTempUpload); hw_execute_bash_command(szComm, NULL); + snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %s %s 2>/dev/null", FOLDER_DRIVERS, szPathTempUpload); + hw_execute_bash_command(szComm, NULL); + if ( hardware_board_is_sigmastar(g_pCurrentModel->hwCapabilities.uBoardType) ) { snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %smaj* %s 2>/dev/null", szFolderLocalUpdateBinaries, szPathTempUpload); @@ -2030,8 +2043,6 @@ static void * _thread_generate_upload(void *argument) if ( hardware_board_is_sigmastar(g_pCurrentModel->hwCapabilities.uBoardType) ) sprintf(szComm, "tar -C %s -cf %s . 2>&1", szPathTempUpload, szFullPathOutputArchive); - else if ( bVersion82Older ) - sprintf(szComm, "tar -czf %s ruby_* 2>&1", szFullPathOutputArchive); else sprintf(szComm, "tar -czf %s -C %s . 2>&1", szFullPathOutputArchive, szPathTempUpload); hw_execute_bash_command(szComm, NULL); @@ -2296,9 +2307,10 @@ bool Menu::uploadSoftware() return true; } -MenuItemSelect* Menu::createMenuItemCardModelSelector(const char* szName) +MenuItemSelect* Menu::createMenuItemCardModelSelector(const char* szTitle) { - MenuItemSelect* pItem = new MenuItemSelect(szName, "Sets the radio interface model."); + MenuItemSelect* pItem = new MenuItemSelect(szTitle, "Sets the radio interface model."); + pItem->addSelection("Autodetected"); pItem->addSelection("Generic"); for( int i=1; i<50; i++ ) { @@ -2312,6 +2324,129 @@ MenuItemSelect* Menu::createMenuItemCardModelSelector(const char* szName) return pItem; } +MenuItemSelect* Menu::createMenuItemTxPowers(const char* szTitle, bool bAddAutoOption, int* piCardsCurrentPowerLevelsMw, int iNumCards, int iMaxUsablePowerMw) +{ + int iPowerLevelsCount = 0; + const int* piPowerLevelsMw = tx_powers_get_ui_levels_mw(&iPowerLevelsCount); + + MenuItemSelect* pItem = new MenuItemSelect(szTitle, "Sets the radio Tx power level."); + + char szText[128]; + szText[0] = 0; + /* + if ( NULL == piCardsCurrentPowerLevelsMw ) + strcpy(szText, "Custom"); + else + strcpy(szText, "Custom"); + pItem->addSelection(szText); + */ + + if ( bAddAutoOption ) + pItem->addSelection("Auto"); + + int iPrevValue = 0; + for( int i=0; i (iMaxUsablePowerMw * (100 + MAX_TX_POWER_UI_DEVIATION_FROM_STANDARD)) / 100 ) + break; + if ( (piPowerLevelsMw[i] >= 100) && (iPrevValue < 100) ) + pItem->addSeparator(); + sprintf(szText, "%d mW", piPowerLevelsMw[i]); + pItem->addSelection(szText); + + iPrevValue = piPowerLevelsMw[i]; + } + pItem->addSelection("Custom"); + pItem->setIsEditable(); + return pItem; +} + +void Menu::selectMenuItemTxPowersValue(MenuItemSelect* pMenuItem, bool bHasAutoOption, int* piCardsCurrentPowerLevelsMw, int iNumCards, int iMaxUsablePowerMw) +{ + if ( (NULL == pMenuItem) || (NULL == piCardsCurrentPowerLevelsMw) || (0 == iNumCards) ) + return; + + int iPowerLevelsUICount = 0; + const int* piPowerLevelsUIMw = tx_powers_get_ui_levels_mw(&iPowerLevelsUICount); + + int iMaxCurrentPowerMw = 0; + for( int i=0; i iMaxCurrentPowerMw ) + iMaxCurrentPowerMw = piCardsCurrentPowerLevelsMw[i]; + } + if ( iMaxCurrentPowerMw > iMaxUsablePowerMw ) + iMaxCurrentPowerMw = iMaxUsablePowerMw; + log_line("Menu: Current controller max set tx power for all cards: %d mw", iMaxCurrentPowerMw); + + int iMinDiffMw = 10000; + int iMinDiffMwIndexUI = -1; + for( int i=0; i (iMaxUsablePowerMw * (100 + MAX_TX_POWER_UI_DEVIATION_FROM_STANDARD))/100 ) + break; + int iDiffMw = piPowerLevelsUIMw[i] - iMaxCurrentPowerMw; + if ( iDiffMw < 0 ) + iDiffMw = -iDiffMw; + if ( iDiffMw < iMinDiffMw ) + { + iMinDiffMw = iDiffMw; + iMinDiffMwIndexUI = i; + } + } + + log_line("Menu: Matching tx power mw index: %d (value: %d mW), diff: %d mW (has auto option: %d)", iMinDiffMwIndexUI, (iMinDiffMwIndexUI != -1)?(piPowerLevelsUIMw[iMinDiffMwIndexUI]):-1, iMinDiffMw, bHasAutoOption); + if ( iMinDiffMwIndexUI == -1 ) + { + pMenuItem->setSelectedIndex(0); + return; + } + + if ( bHasAutoOption ) + pMenuItem->setSelectedIndex(iMinDiffMwIndexUI+1); + else + pMenuItem->setSelectedIndex(iMinDiffMwIndexUI); + + bool bBigDeviation = false; + + if ( iMinDiffMw > (piPowerLevelsUIMw[iMinDiffMwIndexUI] * MAX_TX_POWER_UI_DEVIATION_FROM_STANDARD) / 100 ) + //if ( piPowerLevelsUIMw[iMinDiffMwIndexUI] >= 20 ) + bBigDeviation = true; + + log_line("Menu: Matching tx power is big deviation: %d", bBigDeviation); + + if ( bBigDeviation ) + { + int iIndex = pMenuItem->getSelectionsCount()-1; + char szText[128]; + sprintf(szText, "Custom (%d mW)", iMaxCurrentPowerMw); + pMenuItem->updateSelectionText(iIndex, szText); + pMenuItem->setSelectedIndex(iIndex); + } + else + { + bBigDeviation = false; + if ( piPowerLevelsUIMw[iMinDiffMwIndexUI] < 10 ) + if ( iMinDiffMw > 2 ) + bBigDeviation = true; + + if ( piPowerLevelsUIMw[iMinDiffMwIndexUI] >= 20 ) + if ( iMinDiffMw > (piPowerLevelsUIMw[iMinDiffMwIndexUI] * 5) / 100 ) + bBigDeviation = true; + log_line("Menu: Matching tx power is big deviation (2): %d", bBigDeviation); + if ( bBigDeviation ) + { + int iIndex = iMinDiffMwIndexUI; + if ( bHasAutoOption ) + iIndex++; + char szText[128]; + strcpy(szText, "~"); + strcat(szText, pMenuItem->getSelectionIndexText(iIndex)); + pMenuItem->updateSelectionText(iIndex, szText); + } + } +} + bool Menu::_uploadVehicleUpdate(const char* szArchiveToUpload) { command_packet_sw_package cpswp_cancel; diff --git a/code/r_central/menu/menu_objects.h b/code/r_central/menu/menu_objects.h index c3dc0267..d82ee2fb 100644 --- a/code/r_central/menu/menu_objects.h +++ b/code/r_central/menu/menu_objects.h @@ -3,6 +3,7 @@ #include "menu_item_select.h" #include "../../base/base.h" #include "../../base/models.h" +#include "../../common/strings_table.h" #include "../handle_commands.h" @@ -95,7 +96,7 @@ #define MENU_ID_IMPORT_ENC_KEY 107 #define MENU_ID_PREFERENCES_BUTTONS 108 #define MENU_ID_TEXT 110 -#define MENU_ID_TXINFO 111 +#define MENU_ID_TX_RAW_POWER 111 #define MENU_ID_VEHICLE_RADIO_LINK_ELRS 112 #define MENU_ID_OSD_PLUGINS 113 #define MENU_ID_VEHICLE_OSD_WIDGET 114 @@ -107,6 +108,8 @@ #define MENU_ID_VEHICLE_BOARD 120 #define MENU_ID_CONTROLLER_DEV_STATS 121 #define MENU_ID_NEGOCIATE_RADIO 122 +#define MENU_ID_ABOUT 123 +#define MENU_ID_CONTROLLER_RADIO 124 #define MAX_MENU_ITEMS 150 @@ -157,11 +160,14 @@ class Menu bool m_bDisableStacking; bool m_bIsModal; + int getId(); + void setId(int iId); void setParent(Menu* pParent); void invalidate(); void setModal(bool bModal); bool isModal(); void disableScrolling(); + char* getTitle(); void setTitle(const char* szTitle); void setSubTitle(const char* szSubTitle); void removeAllTopLines(); @@ -211,7 +217,7 @@ class Menu float getUsableWidth(); float getRenderWidth(); float getRenderXPos(); - + void resetRenderXPos(); void startAnimationOnChildMenuAdd(); void startAnimationOnChildMenuClosed(); @@ -241,8 +247,10 @@ class Menu bool _uploadVehicleUpdate(const char* szArchiveToUpload); bool checkCancelUpload(); - MenuItemSelect* createMenuItemCardModelSelector(const char* szName); - + MenuItemSelect* createMenuItemCardModelSelector(const char* szTitle); + MenuItemSelect* createMenuItemTxPowers(const char* szTitle, bool bAddAutoOption, int* piCardsCurrentPowerLevelsMw, int iNumCards, int iMaxUsablePowerMw); + void selectMenuItemTxPowersValue(MenuItemSelect* pMenuItem, bool bHasAutoOption, int* piCardsCurrentPowerLevelsMw, int iNumCards, int iMaxUsablePowerMw); + static int m_siRenderMode; static float m_sfMenuPaddingX; static float m_sfMenuPaddingY; diff --git a/code/r_central/menu/menu_radio_config.cpp b/code/r_central/menu/menu_radio_config.cpp index 6c390579..31fb7351 100644 --- a/code/r_central/menu/menu_radio_config.cpp +++ b/code/r_central/menu/menu_radio_config.cpp @@ -30,7 +30,7 @@ */ #include "../render_commands.h" -#include "../../base/controller_utils.h" +#include "../../utils/utils_controller.h" #include "osd.h" #include "osd_common.h" #include "../popup.h" @@ -38,7 +38,6 @@ #include "menu_radio_config.h" #include "menu_confirmation.h" #include "menu_item_text.h" -#include "menu_tx_power.h" #include "menu_controller_radio_interface.h" #include "menu_controller_radio_interface_sik.h" #include "menu_vehicle_radio_link.h" @@ -53,25 +52,16 @@ #include "../pairing.h" #define MRC_ID_SET_PREFFERED_TX 1 -#define MRC_ID_SET_TX_POWER_CONTROLLER_58 2 -#define MRC_ID_SET_TX_POWER_CONTROLLER_24 3 -#define MRC_ID_SET_TX_POWER_CONTROLLER_2458 4 -#define MRC_ID_SET_TX_POWER_CONTROLLER_SIK 5 -#define MRC_ID_SET_TX_POWER_VEHICLE_58 6 -#define MRC_ID_SET_TX_POWER_VEHICLE_24 7 -#define MRC_ID_SET_TX_POWER_VEHICLE_2458 8 -#define MRC_ID_SET_TX_POWER_VEHICLE_SIK 9 -#define MRC_ID_CONFIGURE_RADIO_LINK 10 -#define MRC_ID_CONFIGURE_RADIO_INTERFACE_CONTROLLER 11 -#define MRC_ID_CONFIGURE_RADIO_INTERFACE_VEHICLE 12 -#define MRC_ID_SWITCH_RADIO_LINK 14 -#define MRC_ID_SWAP_VEHICLE_RADIO_INTERFACES 15 -#define MRC_ID_ROTATE_RADIO_LINKS 16 -#define MRC_ID_DISABLE_UPLINKS 17 -#define MRC_ID_DIAGNOSE_RADIO_LINK 20 - - -static int s_iListSiKPowers[] = {1, 2, 5, 8, 11, 14, 17, 20}; + + +#define MRC_ID_CONFIGURE_RADIO_LINK 30 +#define MRC_ID_CONFIGURE_RADIO_INTERFACE_CONTROLLER 31 +#define MRC_ID_CONFIGURE_RADIO_INTERFACE_VEHICLE 32 +#define MRC_ID_SWITCH_RADIO_LINK 34 +#define MRC_ID_SWAP_VEHICLE_RADIO_INTERFACES 35 +#define MRC_ID_ROTATE_RADIO_LINKS 36 +#define MRC_ID_DISABLE_UPLINKS 37 +#define MRC_ID_DIAGNOSE_RADIO_LINK 40 MenuRadioConfig::MenuRadioConfig(void) :Menu(MENU_ID_RADIO_CONFIG, "Radio Configuration", NULL) @@ -97,11 +87,7 @@ MenuRadioConfig::MenuRadioConfig(void) m_szTooltips[i][0] = 0; m_bShowOnlyControllerUnusedInterfaces = false; - m_bConfigSiKPowerVehicle = false; - m_pItemSiKTxPower = NULL; m_pItemSelectTxCard = NULL; - m_fXPosSiKTxPowerController = 0.1; - m_fXPosSiKTxPowerVehicle = 0.1; m_iIndexCurrentItem = 0; m_iIdFontRegular = g_idFontMenu; @@ -169,10 +155,22 @@ void MenuRadioConfig::onShow() } if ( ! (menu_is_menu_on_top(this)) ) - if ( ! (menu_has_menu(MENU_ID_TXINFO)) ) + if ( ! (menu_has_menu(MENU_ID_TX_RAW_POWER)) ) { - log_line("Menu radio config is not on top, close the top menu."); - menu_stack_pop(0); + Menu* pTopMenu = menu_get_top_menu(); + + // Do not close radio interface card model autodetect confirmation message + bool bDoNotClose = false; + if ( (NULL != pTopMenu) && (pTopMenu->getId() == (MENU_ID_SIMPLE_MESSAGE + 34*1000)) ) + bDoNotClose = true; + if ( (NULL != pTopMenu) && (pTopMenu->getId() == MENU_ID_VEHICLE_RADIO_INTERFACE) ) + bDoNotClose = true; + + if ( ! bDoNotClose ) + { + log_line("Menu radio config is not on top, close the top menu."); + menu_stack_pop(0); + } } log_line("Entered menu radio config."); } @@ -198,22 +196,12 @@ void MenuRadioConfig::setTooltipText() void MenuRadioConfig::computeMenuItems() { log_line("MenuRadioConfig: Compute Menu Items..."); - if ( NULL != m_pItemSiKTxPower ) - removeMenuItem(m_pItemSiKTxPower); if ( NULL != m_pItemSelectTxCard ) removeMenuItem(m_pItemSelectTxCard); - m_pItemSiKTxPower = NULL; m_pItemSelectTxCard = NULL; - m_bHas58PowerVehicle = false; - m_bHas24PowerVehicle = false; - m_bHasSiKPowerVehicle = false; - m_bHas58PowerController = false; - m_bHas24PowerController = false; - m_bHasSiKPowerController = false; - m_bHasSwapInterfacesCommand = false; m_bHasRotateRadioLinksOrderCommand = false; @@ -227,8 +215,6 @@ void MenuRadioConfig::computeMenuItems() m_bHasRotateRadioLinksOrderCommand = true; m_iHeaderItemsCount = 0; - m_iCountItemsTxPowerVehicle = 0; - m_iCountItemsTxPowerController = 0; // Check controller interfaces @@ -238,17 +224,9 @@ void MenuRadioConfig::computeMenuItems() log_line("MenuRadio: Detected controller radio interface %d type: %s", i+1, str_get_radio_type_description(pRadioHWInfo->iRadioType)); if ( hardware_radio_index_is_sik_radio(i) ) { - m_bHasSiKPowerController = true; if ( NULL != pRadioHWInfo ) m_uBandsSiKController |= pRadioHWInfo->supportedBands; } - else - { - if ( (NULL != pRadioHWInfo) && ((pRadioHWInfo->iRadioType == RADIO_TYPE_ATHEROS) || ((pRadioHWInfo->iRadioType == RADIO_TYPE_RALINK))) ) - m_bHas24PowerController = true; - else - m_bHas58PowerController = true; - } } if ( (NULL != g_pCurrentModel) && g_bFirstModelPairingDone && (!m_bShowOnlyControllerUnusedInterfaces) ) @@ -258,15 +236,7 @@ void MenuRadioConfig::computeMenuItems() log_line("MenuRadio: Detected vehicle radio interface %d type: %s", i+1, str_get_radio_type_description(g_pCurrentModel->radioInterfacesParams.interface_radiotype_and_driver[i])); if ( (g_pCurrentModel->radioInterfacesParams.interface_radiotype_and_driver[i] & 0xFF) == RADIO_TYPE_SIK ) - { - m_bHasSiKPowerVehicle = true; m_uBandsSiKVehicle |= g_pCurrentModel->radioInterfacesParams.interface_supported_bands[i]; - } - else if ( ((g_pCurrentModel->radioInterfacesParams.interface_radiotype_and_driver[i] & 0xFF) == RADIO_TYPE_ATHEROS) || ((g_pCurrentModel->radioInterfacesParams.interface_radiotype_and_driver[i] & 0xFF) == RADIO_TYPE_RALINK) ) - m_bHas24PowerVehicle = true; - else - m_bHas58PowerVehicle = true; - } } @@ -342,9 +312,50 @@ void MenuRadioConfig::Render() computeMaxItemIndexAndCommands(); } + float xStart = 0.05; + float xEnd = 0.72; + float fWidth = xEnd - xStart; + + float yStart = 0.04; + if ( m_fTotalHeightRadioConfig < 0.8 ) + yStart += 0.1; + + g_pRenderEngine->setColors(get_Color_MenuBg()); + g_pRenderEngine->drawRoundRect(xStart, yStart, fWidth, m_fTotalHeightRadioConfig, MENU_ROUND_MARGIN*m_sfMenuPaddingY); + + g_pRenderEngine->setStrokeSize(MENU_OUTLINEWIDTH); + g_pRenderEngine->setFill(0,0,0,0); + g_pRenderEngine->setStroke(get_Color_MenuBorder()); + g_pRenderEngine->drawRoundRect(xStart, yStart, fWidth, m_fTotalHeightRadioConfig, MENU_ROUND_MARGIN*m_sfMenuPaddingY); + g_pRenderEngine->setColors(get_Color_MenuText()); + + if ( 1 ) + { + g_pRenderEngine->setColors(get_Color_MenuBgTooltip()); + float yTooltip = yStart + m_fTotalHeightRadioConfig - m_fFooterHeight; + g_pRenderEngine->drawRoundRect(xStart, yTooltip, fWidth, m_fFooterHeight, MENU_ROUND_MARGIN*m_sfMenuPaddingY); + + g_pRenderEngine->setColors(get_Color_MenuBg()); + g_pRenderEngine->setStroke(get_Color_MenuBorder()); + g_pRenderEngine->drawLine(xStart, yTooltip, xStart+fWidth, yTooltip); + + yTooltip += 0.4*m_sfMenuPaddingY; + + g_pRenderEngine->setColors(get_Color_MenuText()); + g_pRenderEngine->drawMessageLines(xStart+m_sfMenuPaddingX, yTooltip, m_szCurrentTooltip, MENU_TEXTLINE_SPACING, fWidth-2.0*m_sfMenuPaddingX, m_iIdFontRegular); + } + + if ( m_iIndexCurrentItem < 0 ) + m_iIndexCurrentItem = 0; + + yStart += m_sfMenuPaddingY; + m_fHeaderHeight = drawRadioHeader(xStart, xEnd, yStart); + yStart += m_fHeaderHeight; + computeHeights(); + // Draw radio links - float yEnd = drawRadioLinks(0.05/g_pRenderEngine->getAspectRatio(), 0.68); + float yEnd = drawRadioLinks(xStart, xEnd, yStart); g_pRenderEngine->clearFontBackgroundBoundingBoxStrikeColor(); @@ -357,17 +368,6 @@ void MenuRadioConfig::Render() m_pItemSelectTxCard->Render(xPos, m_fYPosAutoTx[m_iCurrentRadioLink]-height_text, true, 0.0); } - if ( NULL != m_pItemSiKTxPower ) - { - float xPos = m_fXPosSiKTxPowerController; - if ( m_bConfigSiKPowerVehicle ) - xPos = m_fXPosSiKTxPowerVehicle; - - m_pItemSiKTxPower->setLastRenderPos(xPos, m_fHeaderHeight-height_text); - m_pItemSiKTxPower->getItemHeight(0.5); - m_pItemSiKTxPower->Render(xPos, m_fHeaderHeight-height_text, true, 0.0); - } - // Draw bottom items float xLeft = m_RenderXPos + m_RenderWidth - 2.0*m_sfMenuPaddingX; @@ -428,7 +428,7 @@ void MenuRadioConfig::onMoveUp(bool bIgnoreReversion) { if ( g_bSwitchingRadioLink ) return; - if ( (NULL != m_pItemSelectTxCard) || (NULL != m_pItemSiKTxPower) ) + if ( NULL != m_pItemSelectTxCard ) { Menu::onMoveUp(bIgnoreReversion); setTooltipText(); @@ -452,7 +452,7 @@ void MenuRadioConfig::onMoveDown(bool bIgnoreReversion) { if ( g_bSwitchingRadioLink ) return; - if ( (NULL != m_pItemSelectTxCard) || (NULL != m_pItemSiKTxPower) ) + if ( NULL != m_pItemSelectTxCard ) { Menu::onMoveDown(bIgnoreReversion); setTooltipText(); @@ -534,37 +534,6 @@ void MenuRadioConfig::onItemEndEdit(int itemIndex) pairing_start_normal(); hideProgressInfo(); } - - if ( NULL != m_pItemSiKTxPower ) - { - int iSelection = m_pItemSiKTxPower->getSelectedIndex(); - int iTxPower = 0; - if ( iSelection >= 0 && (iSelection < (int)sizeof(s_iListSiKPowers)/(int)sizeof(s_iListSiKPowers[0])) ) - iTxPower = s_iListSiKPowers[iSelection]; - log_line("Changed SiK Tx power to index: %d, power: %d", iSelection, iTxPower); - removeMenuItem(m_pItemSiKTxPower); - m_pItemSiKTxPower = NULL; - - if ( m_bConfigSiKPowerVehicle ) - { - u8 buffer[11]; - memset(&(buffer[0]), 0xFF, 11); - buffer[8] = 0x81; - buffer[9] = iTxPower; - buffer[10] = 0x81; - - if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_TX_POWERS, 0, buffer, 11) ) - valuesToUI(); - } - else - { - ControllerSettings* pCS = get_ControllerSettings(); - pCS->iTXPowerSiK = iTxPower; - save_ControllerSettings(); - send_model_changed_message_to_router(MODEL_CHANGED_RADIO_POWERS, 0); - } - valuesToUI(); - } } @@ -616,36 +585,6 @@ void MenuRadioConfig::onClickAutoTx(int iRadioLink) m_pItemSelectTxCard->beginEdit(); } -void MenuRadioConfig::onClickSiKTxPower(bool bVehicle) -{ - m_bConfigSiKPowerVehicle = bVehicle; - removeMenuItem(m_pItemSiKTxPower); - m_pItemSiKTxPower = new MenuItemSelect(""); - ControllerSettings* pCS = get_ControllerSettings(); - - // 1 2 5 8 11 14 17 20 - int iSelectedIndex = -1; - for( int i=0; i<(int)sizeof(s_iListSiKPowers)/(int)sizeof(s_iListSiKPowers[0]); i++ ) - { - char szBuff[256]; - sprintf(szBuff, "%d", s_iListSiKPowers[i]); - m_pItemSiKTxPower->addSelection(szBuff); - - if ( m_bConfigSiKPowerVehicle ) - if ( (NULL != g_pCurrentModel) && g_pCurrentModel->radioInterfacesParams.txPowerSiK == s_iListSiKPowers[i] ) - iSelectedIndex = i; - - if ( ! m_bConfigSiKPowerVehicle ) - if ( pCS->iTXPowerSiK == s_iListSiKPowers[i] ) - iSelectedIndex = i; - } - addMenuItem(m_pItemSiKTxPower); - - m_pItemSiKTxPower->setSelectedIndex(iSelectedIndex); - m_pItemSiKTxPower->setIsEditable(); - m_pItemSiKTxPower->setPopupSelectorToRight(); - m_pItemSiKTxPower->beginEdit(); -} void MenuRadioConfig::onSelectItem() { @@ -670,7 +609,7 @@ void MenuRadioConfig::onSelectItem() (int)(m_uCommandsIds[m_iIndexCurrentItem] >> 8), bConnectedToVehicle?"yes":"no"); - if ( (NULL != m_pItemSelectTxCard) || (NULL != m_pItemSiKTxPower) ) + if ( NULL != m_pItemSelectTxCard ) { if ( ! bConnectedToVehicle ) { @@ -731,67 +670,6 @@ void MenuRadioConfig::onSelectItem() return; } - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_24 ) - { - MenuTXPower* pMenu = new MenuTXPower(); - pMenu->m_bShowVehicle = false; - add_menu_to_stack(pMenu); - return; - } - - if ( ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_58) || - ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_2458) ) - { - MenuTXPower* pMenu = new MenuTXPower(); - pMenu->m_bShowVehicle = false; - add_menu_to_stack(pMenu); - return; - } - - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_SIK ) - { - onClickSiKTxPower(false); - return; - } - - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_24 ) - { - if ( ! bConnectedToVehicle ) - { - addMessage(szConnectMsg); - return; - } - MenuTXPower* pMenu = new MenuTXPower(); - pMenu->m_bShowController = false; - add_menu_to_stack(pMenu); - return; - } - - if ( ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_58) || - ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_2458) ) - { - if ( ! bConnectedToVehicle ) - { - addMessageWithTitle(0, szConnectTitle, szConnectMsg); - return; - } - MenuTXPower* pMenu = new MenuTXPower(); - pMenu->m_bShowController = false; - add_menu_to_stack(pMenu); - return; - } - - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_SIK ) - { - if ( ! bConnectedToVehicle ) - { - addMessageWithTitle(0, szConnectTitle, szConnectMsg); - return; - } - onClickSiKTxPower(true); - return; - } - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_CONFIGURE_RADIO_LINK ) { if ( ! bConnectedToVehicle ) @@ -821,9 +699,9 @@ void MenuRadioConfig::onSelectItem() } if ( 0 != iCountInterfacesAssignedToThisLink ) - pMenu->m_xPos = m_RenderXPos + m_RenderWidth*0.5; + pMenu->m_xPos = m_RenderXPos + m_RenderWidth*0.2; else - pMenu->m_xPos = m_RenderXPos + m_RenderWidth*0.8; + pMenu->m_xPos = m_RenderXPos + m_RenderWidth*0.3; pMenu->m_yPos = m_fYPosRadioLinks[iVehicleRadioLinkId] - 5.0*height_text; if ( pMenu->m_yPos < 0.03 ) pMenu->m_yPos = 0.03; @@ -912,6 +790,9 @@ float MenuRadioConfig::computeHeights() float hTotalHeight = 0.0; + hTotalHeight += m_fHeaderHeight; + hTotalHeight += 2.0 * m_sfMenuPaddingY; + if ( (0 < g_SM_RadioStats.countVehicleRadioLinks) || (0 < g_SM_RadioStats.countLocalRadioLinks) ) if ( (NULL != g_pCurrentModel) && g_bFirstModelPairingDone && (!m_bShowOnlyControllerUnusedInterfaces) ) { @@ -957,6 +838,15 @@ float MenuRadioConfig::computeHeights() hTotalHeight += (iCountUnusedControllerInterfaces-1)*height_text*1.5; } + if ( 0 == hardware_get_radio_interfaces_count() ) + hTotalHeight += height_text*1.5; + + hTotalHeight += m_fFooterHeight; + if ( m_iCountVehicleRadioLinks < 2 ) + hTotalHeight += height_text; + + if ( hTotalHeight > 1.0 - 2.0 * 0.02 ) + hTotalHeight = 1.0 - 2.0 * 0.02; //log_line("Menu radio config: computed heights."); m_bComputedHeights = true; m_fTotalHeightRadioConfig = hTotalHeight; @@ -968,73 +858,6 @@ void MenuRadioConfig::computeMaxItemIndexAndCommands() m_iHeaderItemsCount = 0; m_iIndexMaxItem = 0; - if ( m_bHas24PowerController ) - { - setTooltip(m_iIndexMaxItem, "Sets the Tx power for controller's radio interfaces on 2.4 Ghz band."); - m_uCommandsIds[m_iIndexMaxItem] = MRC_ID_SET_TX_POWER_CONTROLLER_24; - m_iCountItemsTxPowerController++; - m_iHeaderItemsCount++; - m_iIndexMaxItem++; - } - - if ( m_bHas58PowerController ) - { - setTooltip(m_iIndexMaxItem, "Sets the Tx power for controller's radio interfaces on 5.8 Ghz band."); - m_uCommandsIds[m_iIndexMaxItem] = MRC_ID_SET_TX_POWER_CONTROLLER_58; - if ( ! m_bHas24PowerController ) - { - setTooltip(m_iIndexMaxItem, "Sets the Tx power for controller's radio interfaces on 2.4 Ghz and 5.8 Ghz bands."); - m_uCommandsIds[m_iIndexMaxItem] = MRC_ID_SET_TX_POWER_CONTROLLER_2458; - } - m_iCountItemsTxPowerController++; - m_iHeaderItemsCount++; - m_iIndexMaxItem++; - } - - if ( m_bHasSiKPowerController ) - { - setTooltip(m_iIndexMaxItem, "Sets the Tx power for controller's SiK radio interfaces."); - m_uCommandsIds[m_iIndexMaxItem] = MRC_ID_SET_TX_POWER_CONTROLLER_SIK; - m_iCountItemsTxPowerController++; - m_iHeaderItemsCount++; - m_iIndexMaxItem++; - } - - if ( (NULL != g_pCurrentModel) && g_bFirstModelPairingDone && (! m_bShowOnlyControllerUnusedInterfaces) ) - if ( m_bHas24PowerVehicle ) - { - setTooltip(m_iIndexMaxItem, "Sets the Tx power for vehicle's radio interfaces on 2.4 Ghz band."); - m_uCommandsIds[m_iIndexMaxItem] = MRC_ID_SET_TX_POWER_VEHICLE_24; - m_iCountItemsTxPowerVehicle++; - m_iHeaderItemsCount++; - m_iIndexMaxItem++; - } - - if ( (NULL != g_pCurrentModel) && g_bFirstModelPairingDone && (! m_bShowOnlyControllerUnusedInterfaces) ) - if ( m_bHas58PowerVehicle ) - { - setTooltip(m_iIndexMaxItem, "Sets the Tx power for vehicle's radio interfaces on 5.8 Ghz band."); - m_uCommandsIds[m_iIndexMaxItem] = MRC_ID_SET_TX_POWER_VEHICLE_58; - if ( ! m_bHas24PowerVehicle ) - { - setTooltip(m_iIndexMaxItem, "Sets the Tx power for vehicle's radio interfaces on 2.4 Ghz and 5.8 Ghz bands."); - m_uCommandsIds[m_iIndexMaxItem] = MRC_ID_SET_TX_POWER_VEHICLE_2458; - } - m_iCountItemsTxPowerVehicle++; - m_iHeaderItemsCount++; - m_iIndexMaxItem++; - } - - if ( (NULL != g_pCurrentModel) && g_bFirstModelPairingDone && (! m_bShowOnlyControllerUnusedInterfaces) ) - if ( m_bHasSiKPowerVehicle ) - { - setTooltip(m_iIndexMaxItem, "Sets the Tx power for vehicle's SiK radio interfaces."); - m_uCommandsIds[m_iIndexMaxItem] = MRC_ID_SET_TX_POWER_VEHICLE_SIK; - m_iCountItemsTxPowerVehicle++; - m_iHeaderItemsCount++; - m_iIndexMaxItem++; - } - if ( (NULL == g_pCurrentModel) || (0 == g_SM_RadioStats.countVehicleRadioLinks) || m_bShowOnlyControllerUnusedInterfaces ) { for( int i=0; itextHeight(m_iIdFontRegular); - float height_text_large = g_pRenderEngine->textHeight(m_iIdFontLarge); - float fMarginY = 0.04; - float fPaddingY = 0.042; - float fPaddingX = fPaddingY/g_pRenderEngine->getAspectRatio(); - float yStart = fMarginY + fPaddingY; - float yEnd = 1.0 - fMarginY - fPaddingY; float fWidth = (xEnd - xStart); float fXMid = xStart + fWidth*0.5; - g_pRenderEngine->setColors(get_Color_MenuBg()); - - g_pRenderEngine->drawRoundRect(xStart, fMarginY, fWidth, 1.0-2.0*fMarginY, MENU_ROUND_MARGIN*m_sfMenuPaddingY); - - if ( 1 ) - { - g_pRenderEngine->setColors(get_Color_MenuBgTooltip()); - float yTooltip = 1.0-fMarginY-m_fFooterHeight; - g_pRenderEngine->drawRoundRect(xStart, yTooltip, fWidth, m_fFooterHeight, MENU_ROUND_MARGIN*m_sfMenuPaddingY); - - g_pRenderEngine->setColors(get_Color_MenuBg()); - g_pRenderEngine->setStroke(get_Color_MenuBorder()); - g_pRenderEngine->drawLine(xStart, 1.0-fMarginY-m_fFooterHeight, xStart+fWidth, 1.0-fMarginY-m_fFooterHeight); - - yTooltip += 0.4*m_sfMenuPaddingY; - - g_pRenderEngine->setColors(get_Color_MenuText()); - g_pRenderEngine->drawMessageLines( xStart+m_sfMenuPaddingX, yTooltip, m_szCurrentTooltip, MENU_TEXTLINE_SPACING, fWidth-2.0*fPaddingX, m_iIdFontRegular); - } - - xStart += fPaddingX; - xEnd -= fPaddingX; - fWidth -= 2.0 * fPaddingX; + xStart += m_sfMenuPaddingX; + xEnd -= m_sfMenuPaddingX; + fWidth -= 2.0 * m_sfMenuPaddingX; m_RenderXPos = xStart; m_RenderWidth = fWidth; @@ -1192,45 +989,6 @@ float MenuRadioConfig::drawRadioLinks(float xStart, float xEnd) return yPos; } - /* - if ( NULL == g_pCurrentModel ) - { - yPos += height_text*4.0; - g_pRenderEngine->drawText(xStart, yPos, m_iIdFontLarge, "No active vehicle. Nothing to configure."); - yPos += height_text*1.2; - g_pRenderEngine->drawText(xStart, yPos, m_iIdFontLarge, "Select a vehicle from your vehicle list or search and connect to a vehicle."); - return yPos; - } - */ - /* - if ( 0 == g_SM_RadioStats.countVehicleRadioLinks ) - { - yPos += height_text*4.0; - g_pRenderEngine->drawText(xStart, yPos, m_iIdFontLarge, "No radio configuration received yet from current active vehicle."); - yPos += height_text*1.2; - g_pRenderEngine->drawText(xStart, yPos, m_iIdFontLarge, "Nothing to configure."); - return yPos; - } - */ - - float yTmp = yPos; - m_fHeaderHeight = drawRadioPowersHeader(xStart, xEnd, yPos); - yPos += m_fHeaderHeight; - - float hTotalHeight = computeHeights(); - - yPos += 0.24*((yEnd-yPos) - hTotalHeight); - - - // ---------------------- - // Draw mid separator - - float fAlpha = g_pRenderEngine->setGlobalAlfa(0.5); - for( float fy = yTmp+height_text_large*1.2 ; fydrawLine(fXMid, fy, fXMid, fy+0.01); - g_pRenderEngine->setGlobalAlfa(fAlpha); - - // --------------------------------- // Draw each radio link @@ -1301,7 +1059,7 @@ float MenuRadioConfig::drawRadioLinks(float xStart, float xEnd) return yPos; } -float MenuRadioConfig::drawRadioPowersHeader(float xStart, float xEnd, float yStart) +float MenuRadioConfig::drawRadioHeader(float xStart, float xEnd, float yStart) { float height_text = g_pRenderEngine->textHeight(m_iIdFontRegular); float height_text_large = g_pRenderEngine->textHeight(m_iIdFontLarge); @@ -1309,16 +1067,14 @@ float MenuRadioConfig::drawRadioPowersHeader(float xStart, float xEnd, float ySt float yPos = yStart; float xMid = (xStart+xEnd)*0.5; float xMidMargin = 0.1/g_pRenderEngine->getAspectRatio(); - bool bBBox = false; - char szBuff[128]; - ControllerSettings* pCS = get_ControllerSettings(); - float ftw = g_pRenderEngine->textWidth(m_iIdFontLarge, "Current Radio Configuration"); - g_pRenderEngine->drawText(xStart + (xEnd-xStart - ftw)*0.5, yPos-height_text_large*0.5, m_iIdFontLarge, "Current Radio Configuration"); + g_pRenderEngine->drawText(xStart + (xEnd-xStart - ftw)*0.5, yPos, m_iIdFontLarge, "Current Radio Configuration"); yPos += height_text_large*1.2; + float yTmp = yPos; + u32 uIdIconVehicle = g_idIconDrone; if ( NULL != g_pCurrentModel ) uIdIconVehicle = osd_getVehicleIcon( g_pCurrentModel->vehicle_type ); @@ -1343,139 +1099,21 @@ float MenuRadioConfig::drawRadioPowersHeader(float xStart, float xEnd, float ySt szBuff[0] = toupper(szBuff[0]); g_pRenderEngine->drawText(xRight, yPos + (hIconBig-height_text)*0.5, m_iIdFontRegular, szBuff); - yPos += height_text*1.5; - - int iTotalLines = 0; - float dy = 0.0; - - if ( m_iIndexCurrentItem < 0 ) - m_iIndexCurrentItem = 0; - - m_fXPosSiKTxPowerController = xMid - xMidMargin*1.2 - 0.03; - if ( m_bHas24PowerController && m_bHas58PowerController ) - { - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_24 ) - bBBox = g_pRenderEngine->drawBackgroundBoundingBoxes(true); - sprintf(szBuff,"Tx Power 2.4Ghz: %d", pCS->iTXPowerAtheros); - g_pRenderEngine->drawTextLeft(xMid - xMidMargin*1.2, yPos + hIconBig, m_iIdFontRegular, szBuff); - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_24 ) - g_pRenderEngine->drawBackgroundBoundingBoxes(bBBox); - - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_58 ) - bBBox = g_pRenderEngine->drawBackgroundBoundingBoxes(true); - sprintf(szBuff,"Tx Power 5.8Ghz: %d", pCS->iTXPowerRTL8812AU); - g_pRenderEngine->drawTextLeft(xMid - xMidMargin*1.2, yPos + hIconBig + height_text*1.4, m_iIdFontRegular, szBuff); - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_58 ) - g_pRenderEngine->drawBackgroundBoundingBoxes(bBBox); - - iTotalLines += 2; - dy += 2.0*height_text*1.4; - } - else - { - if ( ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_24) || - ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_58) || - ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_2458) ) - bBBox = g_pRenderEngine->drawBackgroundBoundingBoxes(true); - if ( m_bHas58PowerController ) - sprintf(szBuff,"Tx Power (2.4/5.8 Ghz): %d", pCS->iTXPowerRTL8812AU); - else - sprintf(szBuff,"Tx Power (2.4/5.8 Ghz): %d", pCS->iTXPowerAtheros); - g_pRenderEngine->drawTextLeft(xMid - xMidMargin*1.2, yPos + hIconBig, m_iIdFontRegular, szBuff); - - if ( ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_24) || - ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_58) || - ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_2458) ) - g_pRenderEngine->drawBackgroundBoundingBoxes(bBBox); - - iTotalLines++; - dy += height_text*1.4; - } - - if ( m_bHasSiKPowerController ) - { - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_SIK ) - bBBox = g_pRenderEngine->drawBackgroundBoundingBoxes(true); - sprintf(szBuff,"Tx Power SiK (%s): %d", str_getBandName(m_uBandsSiKController), pCS->iTXPowerSiK); - g_pRenderEngine->drawTextLeft(xMid - xMidMargin*1.2, yPos + hIconBig + dy, m_iIdFontRegular, szBuff); - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_CONTROLLER_SIK ) - g_pRenderEngine->drawBackgroundBoundingBoxes(bBBox); - - iTotalLines++; - dy += height_text*1.4; - } - + yPos += hIconBig + height_text*2.0; + if ( m_iCountVehicleRadioLinks < 2 ) + yPos += height_text; + if ( (NULL == g_pCurrentModel) || (! g_bFirstModelPairingDone) || m_bShowOnlyControllerUnusedInterfaces ) { - yPos += height_text*1.1; g_pRenderEngine->drawMessageLines(xMid + xMidMargin*0.6, yPos, "You have no active model. No radio links are created.", MENU_TEXTLINE_SPACING, (xEnd - xMid) - m_sfMenuPaddingX - xMidMargin*0.6, m_iIdFontRegular); - yPos += iTotalLines*height_text*1.2; + yPos += height_text*1.2; return yPos - yStart; } - - int iLines = 0; - dy = 0.0; - - if ( m_bHas24PowerVehicle && m_bHas58PowerVehicle ) - { - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_24 ) - bBBox = g_pRenderEngine->drawBackgroundBoundingBoxes(true); - sprintf(szBuff,"Tx Power 2.4Ghz: %d", g_pCurrentModel->radioInterfacesParams.txPowerAtheros); - g_pRenderEngine->drawText(xMid + xMidMargin*1.2, yPos + hIconBig, m_iIdFontRegular, szBuff); - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_24 ) - g_pRenderEngine->drawBackgroundBoundingBoxes(bBBox); - - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_58 ) - bBBox = g_pRenderEngine->drawBackgroundBoundingBoxes(true); - sprintf(szBuff,"Tx Power 5.8Ghz: %d", g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU); - g_pRenderEngine->drawText(xMid + xMidMargin*1.2, yPos +hIconBig + height_text*1.4, m_iIdFontRegular, szBuff); - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_58 ) - g_pRenderEngine->drawBackgroundBoundingBoxes(bBBox); - - iLines += 2; - dy += 2.0*height_text*1.4; - } - else - { - if ( ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_24) || - ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_58) || - ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_2458) ) - bBBox = g_pRenderEngine->drawBackgroundBoundingBoxes(true); - if ( m_bHas58PowerVehicle ) - sprintf(szBuff,"Tx Power (2.4/5.8 Ghz): %d", g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU); - else - sprintf(szBuff,"Tx Power (2.4/5.8 Ghz): %d", g_pCurrentModel->radioInterfacesParams.txPowerAtheros); - g_pRenderEngine->drawText(xMid + xMidMargin*1.2, yPos + hIconBig, m_iIdFontRegular, szBuff); - - if ( ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_24) || - ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_58) || - ((m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_2458) ) - g_pRenderEngine->drawBackgroundBoundingBoxes(bBBox); - - iLines++; - dy += height_text*1.4; - } - - if ( m_bHasSiKPowerVehicle ) - { - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_SIK ) - bBBox = g_pRenderEngine->drawBackgroundBoundingBoxes(true); - sprintf(szBuff,"Tx Power SiK (%s): %d", str_getBandName(m_uBandsSiKVehicle), g_pCurrentModel->radioInterfacesParams.txPowerSiK); - g_pRenderEngine->drawText(xMid + xMidMargin*1.2, yPos + hIconBig + dy, m_iIdFontRegular, szBuff); - - m_fXPosSiKTxPowerVehicle = xMid + xMidMargin*1.2 - 0.03 + g_pRenderEngine->textWidth(m_iIdFontRegular, szBuff); - - if ( (m_uCommandsIds[m_iIndexCurrentItem] & 0xFF) == MRC_ID_SET_TX_POWER_VEHICLE_SIK ) - g_pRenderEngine->drawBackgroundBoundingBoxes(bBBox); - - iTotalLines++; - dy += height_text*1.4; - } - - if ( iLines > iTotalLines ) - iTotalLines = iLines; - yPos += hIconBig + iTotalLines*height_text*1.4; + float fAlpha = g_pRenderEngine->setGlobalAlfa(0.5); + for( float fy = yTmp; fydrawLine(xMid, fy, xMid, fy+0.01); + g_pRenderEngine->setGlobalAlfa(fAlpha); return yPos - yStart; } @@ -1571,8 +1209,6 @@ void MenuRadioConfig::drawVehicleRadioLinkCapabilities(float xStart, float xEnd, int adaptive = ((g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags) & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_LINK)?1:0; if ( adaptive ) strcpy(szAuto, " (Auto)"); - else - strcpy(szAuto, " (Fixed)"); } bool bShowLinkRed = false; @@ -1764,24 +1400,7 @@ float MenuRadioConfig::drawVehicleRadioLink(float xStart, float xEnd, float ySta } else { - /* - if ( ( g_pCurrentModel->radioLinksParams.link_capabilities_flags[iVehicleRadioLink] & RADIO_HW_CAPABILITY_FLAG_CAN_TX ) && - ( g_pCurrentModel->radioLinksParams.link_capabilities_flags[iVehicleRadioLink] & RADIO_HW_CAPABILITY_FLAG_CAN_RX ) ) - { - bRadioLinkHasUplink = true; - bRadioLinkHasDownlink = true; - } - if ( g_pCurrentModel->radioLinksParams.link_capabilities_flags[iVehicleRadioLink] & RADIO_HW_CAPABILITY_FLAG_CAN_TX ) - if ( ! (g_pCurrentModel->radioLinksParams.link_capabilities_flags[iVehicleRadioLink] & RADIO_HW_CAPABILITY_FLAG_CAN_RX) ) - { - bRadioLinkHasDownlink = true; - } - if ( g_pCurrentModel->radioLinksParams.link_capabilities_flags[iVehicleRadioLink] & RADIO_HW_CAPABILITY_FLAG_CAN_RX ) - if ( ! (g_pCurrentModel->radioLinksParams.link_capabilities_flags[iVehicleRadioLink] & RADIO_HW_CAPABILITY_FLAG_CAN_TX) ) - { - bRadioLinkHasUplink = true; - } - */ + } if ( ( g_pCurrentModel->radioLinksParams.link_capabilities_flags[iVehicleRadioLink] & RADIO_HW_CAPABILITY_FLAG_CAN_USE_FOR_VIDEO ) && diff --git a/code/r_central/menu/menu_radio_config.h b/code/r_central/menu/menu_radio_config.h index c99595e4..b8105eea 100644 --- a/code/r_central/menu/menu_radio_config.h +++ b/code/r_central/menu/menu_radio_config.h @@ -2,7 +2,6 @@ #include "menu_objects.h" #include "../popup.h" - class MenuRadioConfig: public Menu { public: @@ -33,13 +32,12 @@ class MenuRadioConfig: public Menu void computeMenuItems(); void onClickAutoTx(int iRadioLink); - void onClickSiKTxPower(bool bVehicle); float computeHeights(); void computeMaxItemIndexAndCommands(); - float drawRadioLinks(float xStart, float xEnd); - float drawRadioPowersHeader(float xStart, float xEnd, float yStart); + float drawRadioHeader(float xStart, float xEnd, float yStart); + float drawRadioLinks(float xStart, float xEnd, float yStart); float drawVehicleRadioLink(float xStart, float xEnd, float yStart, int iVehicleRadioLink); void drawVehicleRadioLinkCapabilities(float xStart, float xEnd, float yStart, int iVehicleRadioLink, bool bIsLinkActive, bool bIsRelayLink); float drawRadioInterfaceController(float xStart, float xEnd, float yStart, int iRadioLink, int iRadioInterface); @@ -51,7 +49,6 @@ class MenuRadioConfig: public Menu int m_iIdFontLarge; Popup* m_pPopupProgress; MenuItemSelect* m_pItemSelectTxCard; - MenuItemSelect* m_pItemSiKTxPower; int m_iCurrentRadioLink; float m_fHeaderHeight; float m_fYPosAutoTx[MAX_RADIO_INTERFACES]; @@ -59,8 +56,6 @@ class MenuRadioConfig: public Menu float m_fYPosVehicleRadioInterfaces[MAX_RADIO_INTERFACES]; float m_fYPosRadioLinks[MAX_RADIO_INTERFACES]; float m_fFooterHeight; - float m_fXPosSiKTxPowerController; - float m_fXPosSiKTxPowerVehicle; u32 m_uCommandsIds[50]; char m_szTooltips[50][256]; @@ -68,12 +63,6 @@ class MenuRadioConfig: public Menu bool m_bShowOnlyControllerUnusedInterfaces; - bool m_bHas58PowerVehicle; - bool m_bHas24PowerVehicle; - bool m_bHasSiKPowerVehicle; - bool m_bHas58PowerController; - bool m_bHas24PowerController; - bool m_bHasSiKPowerController; u32 m_uBandsSiKVehicle; u32 m_uBandsSiKController; int m_iCountVehicleRadioLinks; @@ -87,8 +76,6 @@ class MenuRadioConfig: public Menu int m_iIndexCurrentItem; int m_iIndexMaxItem; - int m_iCountItemsTxPowerVehicle; - int m_iCountItemsTxPowerController; int m_iHeaderItemsCount; float m_fHeightLinks[MAX_RADIO_INTERFACES]; @@ -96,5 +83,4 @@ class MenuRadioConfig: public Menu bool m_bTmpHasVideoStreamsEnabled; bool m_bTmpHasDataStreamsEnabled; - bool m_bConfigSiKPowerVehicle; -}; \ No newline at end of file +}; diff --git a/code/r_central/menu/menu_root.cpp b/code/r_central/menu/menu_root.cpp index 53db57e0..e0cda017 100644 --- a/code/r_central/menu/menu_root.cpp +++ b/code/r_central/menu/menu_root.cpp @@ -64,18 +64,19 @@ MenuRoot::MenuRoot(void) if ( 1 == Menu::getRenderMode() ) addExtraHeightAtStart(0.2); - addMenuItem(new MenuItem("Vehicle Settings","Change vehicle settings.")); - addMenuItem(new MenuItem("My Vehicles","Manage your vehicles.")); - addMenuItem(new MenuItem("Spectator Vehicles", "See the list of vehicles you recently connected to as a spectator.")); - addMenuItem(new MenuItem("Search", "Search for vehicles.")); + m_iIndexVehicle = addMenuItem(new MenuItem("Vehicle Settings","Change vehicle settings.")); + m_iIndexMyVehicles = addMenuItem(new MenuItem("My Vehicles","Manage your vehicles.")); + m_iIndexSpectator = addMenuItem(new MenuItem("Spectator Vehicles", "See the list of vehicles you recently connected to as a spectator.")); + m_iIndexSearch = addMenuItem(new MenuItem("Search", "Search for vehicles.")); //addSeparator(); - addMenuItem(new MenuItem("Radio Configuration", "Change the current radio configuration and radio settings.")); - addMenuItem(new MenuItem("Controller Settings", "Change controller settings and user interface preferences.")); + m_iIndexMedia = addMenuItem(new MenuItem("Media & Storage", "Manage saved logs, screenshots and videos.")); + + //addMenuItem(new MenuItem("Radio Configuration", "Change the current radio configuration and radio settings.")); + m_iIndexController = addMenuItem(new MenuItem("Controller Settings", "Change controller settings and user interface preferences.")); //addSeparator(); - addMenuItem(new MenuItem("Media & Storage", "Manage saved logs, screenshots and videos.")); - addMenuItem(new MenuItem("System", "Configure system options, shows detailed information about the system")); + m_iIndexSystem = addMenuItem(new MenuItem("System", "Configure system options, shows detailed information about the system")); m_pMenuItems[m_ItemsCount-1]->setExtraHeight(Menu::getSelectionPaddingY()); char szBuff[256]; @@ -304,136 +305,9 @@ void MenuRoot::Render() RenderEnd(yTop); } - -void MenuRoot::createAboutInfo(Menu* pm) -{ - pm->addTopLine(" "); - pm->addTopLine("---"); - pm->addTopLine(" "); - pm->addTopLine("Ruby system developed by: Petru Soroaga"); - pm->addTopLine(""); - pm->addTopLine("IP cameras firmware support provided by:"); - pm->addTopLine("OpenIPC: https://openipc.org"); - pm->addTopLine("https://github.com/OpenIPC"); - pm->addTopLine(""); - pm->addTopLine("For info on the licence terms, check the license.txt file."); - pm->addTopLine("For more info, questions and suggestions find us on www.rubyfpv.com"); - pm->addTopLine("---"); - pm->addTopLine(" "); -} - -void MenuRoot::createHWInfo(Menu* pm) -{ - FILE* fp = NULL; - char szBuff[512]; - char szTemp[256]; - char szOutput[256]; - - log_line("Menu System: create HW info."); - - hw_execute_bash_command_raw("cat /proc/device-tree/model", szOutput); - - sprintf(szBuff, "Board: %s, ", szOutput); - - int temp = 0; - fp = fopen("/sys/class/thermal/thermal_zone0/temp", "r"); - if ( NULL != fp ) - { - fscanf(fp, "%d", &temp); - fclose(fp); - fp = NULL; - } - int speed = hardware_get_cpu_speed(); - sprintf(szTemp, "CPU: %d Mhz, Temp: %d C", speed, temp/1000); - strcat(szBuff, szTemp); - pm->addTopLine(szBuff); - - pm->addTopLine(" "); - pm->addTopLine(" "); -} - - -void MenuRoot::show_MenuInfo() -{ - char szBuff[1024]; - char szOutput[1024]; - char szComm[256]; - - MenuSystem* pm = new MenuSystem(); - pm->m_xPos = menu_get_XStartPos(pm->m_Width); - pm->m_yPos = 0.14; - pm->m_Width = 0.52; - - szBuff[0] = 0; - strcpy(szBuff, "Ruby base version: N/A"); - - FILE* fd = try_open_base_version_file(NULL); - - if ( NULL != fd ) - { - szOutput[0] = 0; - if ( 1 == fscanf(fd, "%s", szOutput) ) - { - strcpy(szBuff, "Ruby base version: "); - strcat(szBuff, szOutput); - } - fclose(fd); - } - - char szFile[128]; - strcpy(szFile, FOLDER_CONFIG); - strcat(szFile, FILE_INFO_LAST_UPDATE); - fd = fopen(szFile, "r"); - if ( NULL != fd ) - { - szOutput[0] = 0; - if ( 1 == fscanf(fd, "%s", szOutput) ) - { - strcat(szBuff, ", last update: "); - strcat(szBuff, szOutput); - } - fclose(fd); - } - - pm->addTopLine(szBuff); - - pm->addTopLine(" "); - - createHWInfo(pm); - - #ifdef HW_PLATFORM_RASPBERRY - sprintf(szComm, "df -m %s | grep root", FOLDER_BINARIES); - #endif - #ifdef HW_PLATFORM_RADXA_ZERO3 - sprintf(szComm, "df -m %s | grep mmc", FOLDER_BINARIES); - #endif - if ( 1 == hw_execute_bash_command_raw(szComm, szBuff) ) - { - char szTemp[1024]; - long lb, lu, lf; - sscanf(szBuff, "%s %ld %ld %ld", szTemp, &lb, &lu, &lf); - sprintf(szBuff, "System storage: %ld Mb free out of %ld Mb total.", lf, lu+lf); - pm->addTopLine(szBuff); - } - /* - if ( 1 == hw_execute_bash_command_raw("free -m | grep Mem", szBuff) ) - { - char szTemp[1024]; - long lt, lu, lf; - sscanf(szBuff, "%s %ld %ld %ld", szTemp, <, &lu, &lf); - sprintf(szBuff, "System memory: %ld Mb free out of %ld Mb total.", lf, lt); - pm->addTopLine(szBuff); - } - */ - createAboutInfo(pm); - add_menu_to_stack(pm); - return; -} - - void MenuRoot::onSelectItem() { - if ( 0 == m_SelectedIndex ) + if ( m_iIndexVehicle == m_SelectedIndex ) { if ( (NULL == g_pCurrentModel) || (0 == g_uActiveControllerModelVID) || (g_bFirstModelPairingDone && (0 == getControllerModelsCount()) && (0 == getControllerModelsSpectatorCount())) ) @@ -445,24 +319,24 @@ void MenuRoot::onSelectItem() return; } - if ( 1 == m_SelectedIndex ) + if ( m_iIndexMyVehicles == m_SelectedIndex ) add_menu_to_stack(new MenuVehicles()); - if ( 2 == m_SelectedIndex ) + if ( m_iIndexSpectator == m_SelectedIndex ) add_menu_to_stack(new MenuSpectator()); - if ( 3 == m_SelectedIndex ) + if ( m_iIndexSearch == m_SelectedIndex ) add_menu_to_stack(new MenuSearch()); - if ( 4 == m_SelectedIndex ) - add_menu_to_stack(new MenuRadioConfig()); + //if ( 4 == m_SelectedIndex ) + // add_menu_to_stack(new MenuRadioConfig()); - if ( 5 == m_SelectedIndex ) + if ( m_iIndexController == m_SelectedIndex ) add_menu_to_stack(new MenuController()); - if ( 6 == m_SelectedIndex ) - add_menu_to_stack(new MenuStorage()); + if ( m_iIndexMedia == m_SelectedIndex ) + add_menu_to_stack(new MenuStorage()); - if ( 7 == m_SelectedIndex ) - show_MenuInfo(); + if ( m_iIndexSystem == m_SelectedIndex ) + add_menu_to_stack(new MenuSystem()); } diff --git a/code/r_central/menu/menu_root.h b/code/r_central/menu/menu_root.h index 8d32a1f4..451f660b 100644 --- a/code/r_central/menu/menu_root.h +++ b/code/r_central/menu/menu_root.h @@ -13,7 +13,10 @@ class MenuRoot: public Menu private: void RenderVehicleInfo(); - void createAboutInfo(Menu* pm); void createHWInfo(Menu* pm); - void show_MenuInfo(); + + int m_iIndexVehicle, m_iIndexMyVehicles; + int m_iIndexSpectator, m_iIndexSearch; + int m_iIndexController, m_iIndexMedia; + int m_iIndexSystem; }; \ No newline at end of file diff --git a/code/r_central/menu/menu_storage.cpp b/code/r_central/menu/menu_storage.cpp index e132f411..d6c1902c 100644 --- a/code/r_central/menu/menu_storage.cpp +++ b/code/r_central/menu/menu_storage.cpp @@ -33,6 +33,7 @@ #include "menu_objects.h" #include "menu_storage.h" #include "menu_confirmation.h" +#include "menu_controller_recording.h" #include #include @@ -51,7 +52,7 @@ MenuStorage::MenuStorage(void) :Menu(MENU_ID_STORAGE, "Media & Storage", NULL) { m_Width = 0.68; - m_Height = 0.62; + m_Height = 0.66; m_xPos = menu_get_XStartPos(m_Width); m_yPos = 0.12; m_VideoInfoFilesCount = 0; m_PicturesFilesCount = 0; @@ -63,6 +64,8 @@ MenuStorage::MenuStorage(void) m_ViewScreenShotIndex = -1; m_ScreenshotImageId = MAX_U32; m_pPopupProgress = NULL; + m_uMustRefreshTime = 0; + m_IndexRecordingOptions = -1; } MenuStorage::~MenuStorage() @@ -123,7 +126,7 @@ void MenuStorage::onShow() m_IndexCopy = -1; m_IndexMove = -1; m_IndexDelete = -1; - m_MainItemsCount = 4; + m_MainItemsCount = 5; #if defined(HW_PLATFORM_RASPBERRY) m_IndexExpand = addMenuItem(new MenuItem("Expand File System", "Expands the file system to occupy the entire available SD card space.")); @@ -136,6 +139,9 @@ void MenuStorage::onShow() if ( 0 == media_get_screenshots_count() ) m_pMenuItems[m_IndexViewPictures]->setEnabled(false); + m_IndexRecordingOptions = addMenuItem(new MenuItem("Recording Options", "Change recording options.")); + m_pMenuItems[m_IndexRecordingOptions]->showArrow(); + addMenuItem(new MenuItem("Prev Page","")); addMenuItem(new MenuItem("Next Page","")); @@ -159,6 +165,12 @@ void MenuStorage::onShow() m_ExtraItemsHeight += height_text * 1.5; */ Menu::onShow(); + + if ( g_bVideoRecordingStarted ) + { + MenuConfirmation* pMC = new MenuConfirmation("Recording in progress", "A recording is in progress. Do you want to stop it?", 1); + add_menu_to_stack(pMC); + } } @@ -303,7 +315,7 @@ void MenuStorage::Render() else maxMenuIndex += m_VideoInfoFilesCount - indexStartThisPage; - y += height_text*0.4; + //y += height_text*0.4; sprintf(szBuff, "Page %d of %d", m_UIFilesPage+1,1+(m_VideoInfoFilesCount/m_UIFilesPerPage)); g_pRenderEngine->drawTextLeft(x+maxWidth-2*m_sfMenuPaddingX, y, g_idFontMenu, szBuff); @@ -399,6 +411,16 @@ void MenuStorage::onReturnFromChild(int iChildMenuId, int returnValue) if ( 1 != returnValue ) return; + if ( 1 == iChildMenuId/1000 ) + { + if ( g_bVideoRecordingStarted ) + { + ruby_stop_recording(); + m_uMustRefreshTime = g_TimeNow + 5000; + } + return; + } + if ( 5 == iChildMenuId/1000 ) { log_line("Confirmed deletion of all media files."); @@ -858,6 +880,12 @@ bool MenuStorage::periodicLoop() } } + if ( m_uMustRefreshTime != 0 ) + if ( (g_TimeNow > m_uMustRefreshTime) || (! g_bVideoProcessing) ) + { + m_uMustRefreshTime = 0; + menu_refresh_all_menus(); + } return false; } @@ -911,6 +939,12 @@ void MenuStorage::onSelectItem() return; } + if ( m_IndexRecordingOptions == m_SelectedIndex ) + { + add_menu_to_stack(new MenuControllerRecording()); + return; + } + int maxMenuIndex = m_StaticMenuItemsCount-1; int indexStartThisPage = m_UIFilesPerPage * m_UIFilesPage; if ( m_VideoInfoFilesCount > indexStartThisPage + m_UIFilesPerPage ) diff --git a/code/r_central/menu/menu_storage.h b/code/r_central/menu/menu_storage.h index e7c6f8a0..c58cab92 100644 --- a/code/r_central/menu/menu_storage.h +++ b/code/r_central/menu/menu_storage.h @@ -51,11 +51,12 @@ class MenuStorage: public Menu int m_ViewScreenShotIndex; u32 m_ScreenshotImageId; Popup* m_pPopupProgress; - + u32 m_uMustRefreshTime; int m_IndexExpand; int m_IndexCopy; int m_IndexMove; int m_IndexDelete; + int m_IndexRecordingOptions; int m_MainItemsCount; void buildFilesListPictures(); diff --git a/code/r_central/menu/menu_system.cpp b/code/r_central/menu/menu_system.cpp index 28e6fcc0..9c404e12 100644 --- a/code/r_central/menu/menu_system.cpp +++ b/code/r_central/menu/menu_system.cpp @@ -37,11 +37,12 @@ #include "menu_confirmation.h" #include "menu_system_all_params.h" #include "menu_system_hardware.h" -#include "../../base/controller_utils.h" +#include "../../utils/utils_controller.h" #include "menu_system_dev_logs.h" #include "menu_system_alarms.h" #include "menu_controller_dev.h" #include "menu_vehicle_dev.h" +#include "menu_about.h" #include "../osd/osd_common.h" #include "../process_router_messages.h" #include "../pairing.h" @@ -51,13 +52,11 @@ #include #include -extern u32 g_idIconOpenIPC; - MenuSystem::MenuSystem(void) :Menu(MENU_ID_SYSTEM, "System Info", NULL) { - m_Width = 0.52; + m_Width = 0.34; m_xPos = menu_get_XStartPos(m_Width); m_yPos = 0.24; m_IndexAlarms = addMenuItem( new MenuItem("Alarms Settings") ); @@ -82,6 +81,7 @@ MenuSystem::MenuSystem(void) m_IndexAutoExport = addMenuItem(m_pItemsSelect[1]); m_IndexReset = addMenuItem(new MenuItem("Factory Reset", "Resets all the settings an files on the controller, as they where when the image was flashed.")); + m_IndexAbout = addMenuItem(new MenuItem("About", "Get info about Ruby system.")); m_pItemsSelect[0] = new MenuItemSelect("Enable Vehicle Developer Mode", "Used to debug issues and test experimental features. Disables fail safe checks, parameters consistency checks and other options. It's recommended to leave this [Off] as it will degrade your system performance."); m_pItemsSelect[0]->addSelection("Off"); @@ -141,13 +141,6 @@ void MenuSystem::Render() for( int i=0; itextHeight(g_idFontMenu); - float iconHeight = 2.0*height_text; - float iconWidth = iconHeight/g_pRenderEngine->getAspectRatio(); - g_pRenderEngine->drawIcon(m_RenderXPos + m_RenderWidth - m_sfMenuPaddingX - iconWidth - 0.16, yEnd - iconHeight - 8.5*g_pRenderEngine->textHeight(g_idFontMenu), iconWidth, iconHeight, g_idIconRuby); - g_pRenderEngine->drawIcon(m_RenderXPos + m_RenderWidth - m_sfMenuPaddingX - iconWidth - 0.16, yEnd - iconHeight - 5.5*g_pRenderEngine->textHeight(g_idFontMenu), iconWidth, iconHeight, g_idIconOpenIPC); - RenderEnd(yEnd); } @@ -389,6 +382,12 @@ void MenuSystem::onSelectItem() return; } + if ( m_IndexAbout == m_SelectedIndex ) + { + add_menu_to_stack(new MenuAbout()); + return; + } + if ( m_IndexDevOptionsVehicle == m_SelectedIndex ) { add_menu_to_stack(new MenuVehicleDev()); diff --git a/code/r_central/menu/menu_system.h b/code/r_central/menu/menu_system.h index 307499d4..7f882638 100644 --- a/code/r_central/menu/menu_system.h +++ b/code/r_central/menu/menu_system.h @@ -24,6 +24,7 @@ class MenuSystem: public Menu int m_IndexExport; int m_IndexImport; int m_IndexAutoExport; + int m_IndexAbout; int m_IndexDeveloperVehicle; int m_IndexDeveloperController; int m_IndexDevOptionsVehicle; diff --git a/code/r_central/menu/menu_system_alarms.cpp b/code/r_central/menu/menu_system_alarms.cpp index 6acea82d..5894c25c 100644 --- a/code/r_central/menu/menu_system_alarms.cpp +++ b/code/r_central/menu/menu_system_alarms.cpp @@ -32,7 +32,6 @@ #include "menu.h" #include "menu_objects.h" #include "menu_system_alarms.h" -#include "../../base/controller_utils.h" #include #include diff --git a/code/r_central/menu/menu_system_all_params.cpp b/code/r_central/menu/menu_system_all_params.cpp index b8baa66d..b3821c88 100644 --- a/code/r_central/menu/menu_system_all_params.cpp +++ b/code/r_central/menu/menu_system_all_params.cpp @@ -406,7 +406,7 @@ float MenuSystemAllParams::renderDataRates(float xPos, float yPos, float width, g_pRenderEngine->setColors(get_Color_MenuText()); - sprintf(szBuff, "Controller TX power: %d", pCS->iTXPowerRTL8812AU); + sprintf(szBuff, "Controller TX power: N/A"); yPos += g_pRenderEngine->drawMessageLines(xPos, yPos, szBuff, MENU_TEXTLINE_SPACING, width, g_idFontMenuSmall); yPos += MENU_TEXTLINE_SPACING * height_text; @@ -414,7 +414,7 @@ float MenuSystemAllParams::renderDataRates(float xPos, float yPos, float width, if ( NULL == g_pCurrentModel ) return 0.0; - sprintf(szBuff, "Vehicle TX power (RTL8812AU): %d", g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU); + sprintf(szBuff, "Vehicle TX power (RTL8812AU): %d", g_pCurrentModel->radioInterfacesParams.interface_raw_power[0]); yPos += g_pRenderEngine->drawMessageLines(xPos, yPos, szBuff, MENU_TEXTLINE_SPACING, width, g_idFontMenuSmall); yPos += MENU_TEXTLINE_SPACING * height_text; diff --git a/code/r_central/menu/menu_system_hardware.cpp b/code/r_central/menu/menu_system_hardware.cpp index 41464955..6d2b1011 100644 --- a/code/r_central/menu/menu_system_hardware.cpp +++ b/code/r_central/menu/menu_system_hardware.cpp @@ -209,15 +209,15 @@ float MenuSystemHardware::renderVehicleInfo(float xPos, float yPos, float width) // ---------------------- // Serial ports - sprintf(szBuff, "Serial Ports: %d found", g_pCurrentModel->hardwareInterfacesInfo.serial_bus_count); + sprintf(szBuff, "Serial Ports: %d found", g_pCurrentModel->hardwareInterfacesInfo.serial_port_count); yPos += g_pRenderEngine->drawMessageLines(xPos, yPos, szBuff, MENU_TEXTLINE_SPACING, width, g_idFontMenu); yPos += MENU_TEXTLINE_SPACING * height_text; - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) { - sprintf( szBuff, "%d. %s, Usage: %s, %d bps", i+1, g_pCurrentModel->hardwareInterfacesInfo.serial_bus_names[i], str_get_serial_port_usage((int)(g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF)), g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[i]); - if ( ( g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) == 0 ) - sprintf( szBuff, "%d. %s, Unsupported!", i+1, g_pCurrentModel->hardwareInterfacesInfo.serial_bus_names[i]); + sprintf( szBuff, "%d. %s, Usage: %s, %d bps", i+1, g_pCurrentModel->hardwareInterfacesInfo.serial_port_names[i], str_get_serial_port_usage((int)(g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF)), g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[i]); + if ( ( g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) == 0 ) + sprintf( szBuff, "%d. %s, Unsupported!", i+1, g_pCurrentModel->hardwareInterfacesInfo.serial_port_names[i]); yPos += g_pRenderEngine->drawMessageLines(xPos+xPad, yPos, szBuff, MENU_TEXTLINE_SPACING, width, g_idFontMenu); yPos += MENU_TEXTLINE_SPACING * height_text; } diff --git a/code/r_central/menu/menu_system_video_profiles.cpp b/code/r_central/menu/menu_system_video_profiles.cpp index 2ba14d90..0b8be384 100644 --- a/code/r_central/menu/menu_system_video_profiles.cpp +++ b/code/r_central/menu/menu_system_video_profiles.cpp @@ -38,8 +38,8 @@ #include "menu_confirmation.h" #include "../../radio/radiolink.h" #include "../../base/utils.h" -#include "../../base/controller_utils.h" #include "../process_router_messages.h" +#include "../../utils/utils_controller.h" #include #include diff --git a/code/r_central/menu/menu_tx_power.cpp b/code/r_central/menu/menu_tx_power.cpp deleted file mode 100644 index 42c20796..00000000 --- a/code/r_central/menu/menu_tx_power.cpp +++ /dev/null @@ -1,821 +0,0 @@ -/* - Ruby Licence - Copyright (c) 2024 Petru Soroaga petrusoroaga@yahoo.com - All rights reserved. - - Redistribution and use in source and/or binary forms, with or without - modification, are permitted provided that the following conditions are met: - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - * Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - * Copyright info and developer info must be preserved as is in the user - interface, additions could be made to that info. - * Neither the name of the organization nor the - names of its contributors may be used to endorse or promote products - derived from this software without specific prior written permission. - * Military use is not permited. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND - ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED - WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE AUTHOR (PETRU SOROAGA) BE LIABLE FOR ANY - DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES - (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND - ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT - (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS - SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*/ - -#include "menu.h" -#include "menu_tx_power.h" -#include "menu_objects.h" -#include "menu_item_text.h" -#include "menu_confirmation.h" -#include "menu_tx_power_max.h" - -#define TX_POWER_TABLE_COLUMNS 11 - -static const int s_iTxPowerLevelValues[TX_POWER_TABLE_COLUMNS] = { 10, 20, 30, 40, 50, 54, 56, 60, 63, 68, 72}; - -static int s_iTxBoosterGainTable4W[][2] = -{ - {2, 100}, - {5, 230}, - {10, 420}, - {20, 800}, - {30, 1100}, - {40, 1300}, - {50, 1400}, - {60, 1500}, - {70, 1600}, - {80, 1700}, - {100, 4000} -}; - -MenuTXPower::MenuTXPower() -:Menu(MENU_ID_TXINFO, "Radio Output Power Levels", NULL) -{ - m_Width = 0.72; - m_Height = 0.64; - m_xPos = 0.05; - m_yPos = 0.16; - - m_xTable = m_RenderXPos + m_sfMenuPaddingY; - m_xTable += 0.15*m_sfScaleFactor; - m_xTableCellWidth = 0.05*m_sfScaleFactor; - - m_bShowThinLine = false; - - m_bShowVehicle = true; - m_bShowController = true; - - m_bValuesChangedVehicle = false; - m_bValuesChangedController = false; - - m_IndexPowerVehicleRTL8812AU = -1; - m_IndexPowerVehicleRTL8812EU = -1; - m_IndexPowerVehicleAtheros = -1; - m_IndexPowerControllerRTL8812AU = -1; - m_IndexPowerControllerRTL8812EU = -1; - m_IndexPowerControllerAtheros = -1; -} - -MenuTXPower::~MenuTXPower() -{ -} - -void MenuTXPower::onShow() -{ - float fSliderWidth = 0.18; - ControllerSettings* pCS = get_ControllerSettings(); - - removeAllItems(); - - int iIndexSlider = 0; - if ( m_bShowVehicle && (NULL != g_pCurrentModel) ) - { - if ( g_pCurrentModel->hasRadioCardsRTL8812AU() ) - { - m_pItemsSlider[iIndexSlider] = new MenuItemSlider("Vehicle Tx Power (RTL8812AU)", "Sets the radio TX power used on the vehicle for RTL8812AU cards.", 1, g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812AU, g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812AU/2, fSliderWidth); - m_IndexPowerVehicleRTL8812AU = addMenuItem(m_pItemsSlider[iIndexSlider]); - iIndexSlider++; - } - if ( g_pCurrentModel->hasRadioCardsRTL8812EU() ) - { - m_pItemsSlider[iIndexSlider] = new MenuItemSlider("Vehicle Tx Power (RTL8812EU)", "Sets the radio TX power used on the vehicle for RTL8812EU cards.", 1, g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812EU, g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812EU/2, fSliderWidth); - m_IndexPowerVehicleRTL8812EU = addMenuItem(m_pItemsSlider[iIndexSlider]); - iIndexSlider++; - } - if ( g_pCurrentModel->hasRadioCardsAtheros() ) - { - m_pItemsSlider[iIndexSlider] = new MenuItemSlider("Vehicle Tx Power (Atheros)", "Sets the radio TX power used on the vehicle for Atheros cards.", 1, g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros, g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros/2, fSliderWidth); - m_IndexPowerVehicleAtheros = addMenuItem(m_pItemsSlider[iIndexSlider]); - iIndexSlider++; - } - } - - if ( m_bShowController ) - { - if ( hardware_radio_has_rtl8812au_cards() ) - { - m_pItemsSlider[iIndexSlider] = new MenuItemSlider("Controller Tx Power (RTL8812AU)", "Sets the radio TX power used on controller for RTL8812AU cards.", 1, pCS->iMaxTXPowerRTL8812AU, pCS->iMaxTXPowerRTL8812AU/2, fSliderWidth); - m_IndexPowerControllerRTL8812AU = addMenuItem(m_pItemsSlider[iIndexSlider]); - iIndexSlider++; - } - if ( hardware_radio_has_rtl8812eu_cards() ) - { - m_pItemsSlider[iIndexSlider] = new MenuItemSlider("Controller Tx Power (RTL8812EU)", "Sets the radio TX power used on controller for RTL8812EU cards.", 1, pCS->iMaxTXPowerRTL8812EU, pCS->iMaxTXPowerRTL8812EU/2, fSliderWidth); - m_IndexPowerControllerRTL8812EU = addMenuItem(m_pItemsSlider[iIndexSlider]); - iIndexSlider++; - } - if ( hardware_radio_has_atheros_cards() ) - { - m_pItemsSlider[iIndexSlider] = new MenuItemSlider("Controller Tx Power (Atheros)", "Sets the radio TX power used on controller for Atheros cards.", 1, pCS->iMaxTXPowerAtheros, pCS->iMaxTXPowerAtheros/2, fSliderWidth); - m_IndexPowerControllerAtheros = addMenuItem(m_pItemsSlider[iIndexSlider]); - iIndexSlider++; - } - } - - m_IndexPowerMax = addMenuItem(new MenuItem("Limit Maximum Radio Power Levels")); - m_pMenuItems[m_IndexPowerMax]->showArrow(); - - m_pItemsSelect[0] = new MenuItemSelect("Show All Card Types", "Shows all card types in the table below, not just the ones detected as present."); - m_pItemsSelect[0]->addSelection("No"); - m_pItemsSelect[0]->addSelection("Yes"); - m_pItemsSelect[0]->setIsEditable(); - m_IndexShowAllCards = addMenuItem(m_pItemsSelect[0]); - - m_pItemsSelect[1] = new MenuItemSelect("Show 2W/4W Boosters", "Shows the power output for current radio interfaces when connected to 2W or 4W power boosters."); - m_pItemsSelect[1]->addSelection("No"); - m_pItemsSelect[1]->addSelection("Yes"); - m_pItemsSelect[1]->setIsEditable(); - m_IndexShowBoosters = addMenuItem(m_pItemsSelect[1]); - - - addMenuItem( new MenuItemText("Here is a table with aproximative ouput power levels for different cards:")); - - Menu::onShow(); -} - -void MenuTXPower::valuesToUI() -{ - ControllerSettings* pCS = get_ControllerSettings(); - Preferences* pP = get_Preferences(); - - m_pItemsSelect[0]->setSelectedIndex(1 - pP->iShowOnlyPresentTxPowerCards); - m_pItemsSelect[1]->setSelectedIndex(pP->iShowTxBoosters); - - - int iIndexSlider = 0; - if ( m_bShowVehicle && (NULL != g_pCurrentModel) ) - { - if ( g_pCurrentModel->hasRadioCardsRTL8812AU() ) - { - m_pItemsSlider[iIndexSlider]->setCurrentValue(g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU); - iIndexSlider++; - } - if ( g_pCurrentModel->hasRadioCardsRTL8812EU() ) - { - m_pItemsSlider[iIndexSlider]->setCurrentValue(g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU); - iIndexSlider++; - } - if ( g_pCurrentModel->hasRadioCardsAtheros() ) - { - m_pItemsSlider[iIndexSlider]->setCurrentValue(g_pCurrentModel->radioInterfacesParams.txPowerAtheros); - iIndexSlider++; - } - } - - if ( m_bShowController ) - { - if ( hardware_radio_has_rtl8812au_cards() ) - { - m_pItemsSlider[iIndexSlider]->setCurrentValue(pCS->iTXPowerRTL8812AU); - iIndexSlider++; - } - if ( hardware_radio_has_rtl8812eu_cards() ) - { - m_pItemsSlider[iIndexSlider]->setCurrentValue(pCS->iTXPowerRTL8812EU); - iIndexSlider++; - } - if ( hardware_radio_has_atheros_cards() ) - { - m_pItemsSlider[iIndexSlider]->setCurrentValue(pCS->iTXPowerAtheros); - iIndexSlider++; - } - } -} - - -void MenuTXPower::RenderTableLine(int iCardModel, const char* szText, const int* piValues, bool bIsHeader, bool bIsBoosterLine) -{ - Preferences* pP = get_Preferences(); - - float height_text = g_pRenderEngine->textHeight(g_idFontMenuSmall); - float x = m_RenderXPos + m_sfMenuPaddingX; - float y = m_yTemp; - float hItem = (1.0 + MENU_ITEM_SPACING) * g_pRenderEngine->textHeight(g_idFontMenuSmall); - - bool bIsPresentOnVehicle = false; - bool bIsPresentOnController = false; - - if ( 0 != iCardModel ) - { - if ( m_bShowVehicle && (NULL != g_pCurrentModel) ) - { - for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) - { - if ( g_pCurrentModel->radioInterfacesParams.interface_card_model[i] == iCardModel ) - bIsPresentOnVehicle = true; - if ( g_pCurrentModel->radioInterfacesParams.interface_card_model[i] == -iCardModel ) - bIsPresentOnVehicle = true; - } - } - - if ( m_bShowController ) - { - for( int n=0; nszMAC); - if ( NULL == pCardInfo ) - continue; - if ( iCardModel == pCardInfo->cardModel ) - bIsPresentOnController = true; - if ( iCardModel == -(pCardInfo->cardModel) ) - bIsPresentOnController = true; - } - } - } - - if ( (!bIsHeader) && pP->iShowOnlyPresentTxPowerCards ) - { - if ( m_bShowVehicle && (! bIsPresentOnVehicle) ) - return; - if ( m_bShowController && (! bIsPresentOnController) ) - return; - } - - if ( 0 != iCardModel ) - if ( (!bIsHeader) && (! pP->iShowOnlyPresentTxPowerCards) ) - if ( bIsPresentOnController || bIsPresentOnVehicle ) - { - //g_pRenderEngine->setColors(get_Color_MenuText(), 0.2); - //g_pRenderEngine->setFill(250,200,50,0.1); - double pColor[4]; - memcpy(pColor,get_Color_MenuBgTooltip(), 4*sizeof(double)); - pColor[0] -= 20; - pColor[1] -= 20; - pColor[2] -= 20; - g_pRenderEngine->setFill(pColor); - g_pRenderEngine->setStroke(get_Color_MenuBorder()); - g_pRenderEngine->setStrokeSize(1); - - float h = hItem + 0.4 * m_sfMenuPaddingY; - if ( pP->iShowTxBoosters ) - if ( ! bIsBoosterLine ) - if ( bIsPresentOnController || bIsPresentOnVehicle ) - h += hItem; - g_pRenderEngine->drawRoundRect(x - m_sfMenuPaddingX*0.4, y - m_sfMenuPaddingY*0.2, m_RenderWidth - 2.0*m_sfMenuPaddingX + 0.8 * m_sfMenuPaddingX, h, MENU_ROUND_MARGIN * m_sfMenuPaddingY); - - g_pRenderEngine->setColors(get_Color_MenuText()); - //g_pRenderEngine->setStroke(get_Color_MenuBorder()); - g_pRenderEngine->setStrokeSize(0); - } - - g_pRenderEngine->drawText(x, y, g_idFontMenuSmall, const_cast(szText)); - - x = m_xTable; - if ( bIsHeader ) - x += 0.008*m_sfScaleFactor; - - char szLevel[128]; - char szValue[32]; - float yTop = m_yTemp - height_text*2.0; - float yBottom = m_yPos+m_RenderHeight - 3.0*m_sfMenuPaddingY - 1.2*height_text; - for( int i=0; i= 1000000 ) - sprintf(szValue, " !!!"); - else if ( piValues[i] < 1000 ) - sprintf(szValue, "%d mW", piValues[i]); - else - sprintf(szValue, "%.1f W", ((float)piValues[i])/1000.0); - g_pRenderEngine->drawText(x, y, g_idFontMenuSmall, szValue); - x += m_xTableCellWidth; - - if ( bIsHeader ) - if ( i == 2 || i == 5 || i == 7 || i == 10 ) - { - g_pRenderEngine->setColors(get_Color_MenuText(), 0.5); - g_pRenderEngine->setStrokeSize(1); - g_pRenderEngine->drawLine(x-0.018*m_sfScaleFactor, yTop+0.02*m_sfScaleFactor, x-0.018*m_sfScaleFactor, yBottom); - g_pRenderEngine->setColors(get_Color_MenuText()); - g_pRenderEngine->setStroke(get_Color_MenuBorder()); - g_pRenderEngine->setStrokeSize(0); - } - - if ( bIsHeader ) - { - szLevel[0] = 0; - if ( i == 2 ) - strcpy(szLevel, "Low Power"); - if ( i == 5 ) - strcpy(szLevel, "Normal Power"); - if ( i == 7 ) - strcpy(szLevel, "Max Power"); - if ( i == 10 ) - strcpy(szLevel, "Experimental"); - if ( 0 != szLevel[0] ) - g_pRenderEngine->drawTextLeft( x-0.026*m_sfScaleFactor, yTop+0.015*m_sfScaleFactor, g_idFontMenuSmall, szLevel); - } - } - - m_yTemp += hItem; - if ( bIsHeader ) - { - g_pRenderEngine->setColors(get_Color_MenuText(), 0.7); - g_pRenderEngine->setStrokeSize(1); - g_pRenderEngine->drawLine(m_xPos + 1.1*m_sfMenuPaddingX,m_yTemp-0.005*m_sfScaleFactor, m_xPos - 1.1*m_sfMenuPaddingX+m_RenderWidth, m_yTemp-0.005*m_sfScaleFactor); - g_pRenderEngine->setColors(get_Color_MenuText()); - g_pRenderEngine->setStroke(get_Color_MenuBorder()); - g_pRenderEngine->setStrokeSize(0); - m_yTemp += MENU_TEXTLINE_SPACING * g_pRenderEngine->textHeight(g_idFontMenuSmall); - } - - if ( m_bShowThinLine ) - { - g_pRenderEngine->setColors(get_Color_MenuText(), 0.5); - g_pRenderEngine->setStrokeSize(1); - float yLine = y-0.005*m_sfScaleFactor; - g_pRenderEngine->drawLine(m_xPos + 1.1*m_sfMenuPaddingX, yLine, m_xPos - 1.1*m_sfMenuPaddingX+m_RenderWidth, yLine); - g_pRenderEngine->setColors(get_Color_MenuText()); - g_pRenderEngine->setStroke(get_Color_MenuBorder()); - g_pRenderEngine->setStrokeSize(0); - } - m_bShowThinLine = false; - m_iLine++; - - if ( ! bIsHeader ) - if ( ! bIsBoosterLine ) - if ( pP->iShowTxBoosters ) - if ( bIsPresentOnController || bIsPresentOnVehicle ) - { - int iTotalPowerValues[TX_POWER_TABLE_COLUMNS]; - for( int i=0; i 100 ) - iTotalPowerValues[i] = 1000000; - else for( int k=0; k<(int)(sizeof(s_iTxBoosterGainTable4W)/sizeof(s_iTxBoosterGainTable4W[0][0])/2)-1; k++ ) - { - if ( piValues[i] >= s_iTxBoosterGainTable4W[k][0] ) - if ( piValues[i] <= s_iTxBoosterGainTable4W[k+1][0] ) - { - iTotalPowerValues[i] = s_iTxBoosterGainTable4W[k][1] + (s_iTxBoosterGainTable4W[k+1][1] - s_iTxBoosterGainTable4W[k][1]) * (float)((float)(piValues[i] - s_iTxBoosterGainTable4W[k][0])/(float)(s_iTxBoosterGainTable4W[k+1][0] - s_iTxBoosterGainTable4W[k][0])); - break; - } - } - } - RenderTableLine(iCardModel, " + 4W booster", iTotalPowerValues, false, true); - } -} - -void MenuTXPower::drawPowerLine(const char* szText, float yPos, int value) -{ - float height_text = g_pRenderEngine->textHeight(g_idFontMenuSmall); - float xPos = m_RenderXPos + m_sfMenuPaddingX; - char szBuff[64]; - - g_pRenderEngine->drawText( xPos, yPos, g_idFontMenuSmall, szText); - - float x = m_xTable; - float xEnd = x; - for( int i=0; isetColors(get_Color_MenuText(), 0.7); - g_pRenderEngine->setStrokeSize(1); - g_pRenderEngine->drawLine(x, yPos+0.6*height_text, x+width,yPos+0.6*height_text); - xEnd = x+width; - g_pRenderEngine->setColors(get_Color_MenuText()); - x += m_xTableCellWidth; - } - - sprintf(szBuff, "%d", value); - if ( value <= 0 ) - sprintf(szBuff, "N/A"); - g_pRenderEngine->drawText( xEnd+0.2*height_text, yPos, g_idFontMenuSmall, szBuff); -} - - -void MenuTXPower::Render() -{ - Preferences* pP = get_Preferences(); - RenderPrepare(); - float height_text = g_pRenderEngine->textHeight(g_idFontMenuSmall); - - float yTop = RenderFrameAndTitle(); - float y = yTop; - - m_xTable = m_RenderXPos + m_sfMenuPaddingX; - m_xTable += 0.15*m_sfScaleFactor; - m_xTableCellWidth = 0.05*m_sfScaleFactor; - - for( int i=0; i<=m_IndexPowerMax+2; i++ ) - y += RenderItem(i,y); - - y += 1.0*height_text; - - m_yTopRender = y - 0.01*m_sfScaleFactor; - m_yTemp = y+0.01*m_sfScaleFactor + 1.0*height_text; - m_yTemp += 1.3 * height_text * m_IndexPowerMax; - - //nst int infoH[TX_POWER_TABLE_COLUMNS] = { 10, 20, 30, 40, 50, 54, 56, 60, 63, 68, 72}; - - const int info722N[TX_POWER_TABLE_COLUMNS] = { 1, 2, 3, 10, 35, 60, 80, 90, 0, 0, 0}; - const int info722N2W[TX_POWER_TABLE_COLUMNS] = { 6, 20, 70, 205, 650, 900, 1000, 1900, 2000, 2000, 2000}; - const int info722N4W[TX_POWER_TABLE_COLUMNS] = { 10, 60, 200, 450, 1200, 1900, 2100, 2100, 2100, 2100, 2100}; - const int infoBlueStick[TX_POWER_TABLE_COLUMNS] = { 2, 4, 8, 28, 80, 110, 280, 1000, 0, 0, 0}; - //nst int infoGreenStick[TX_POWER_TABLE_COLUMNS] = { 2, 5, 5, 60, 75, 75, 0, 0, 0, 0, 0}; - const int infoAWUS036NH[TX_POWER_TABLE_COLUMNS] = { 10, 20, 30, 40, 60, 0, 0, 0, 0, 0, 0}; - const int infoAWUS036NHA[TX_POWER_TABLE_COLUMNS] = { 1, 2, 6, 17, 120, 180, 215, 310, 460, 0, 0}; - - //const int infoH[TX_POWER_TABLE_COLUMNS] = { 10, 20, 30, 40, 50, 54, 56, 60, 63, 68, 72}; - - const int infoGeneric[TX_POWER_TABLE_COLUMNS] = { 1, 2, 3, 10, 35, 60, 80, 90, 0, 0, 0}; - const int infoAWUS036ACH[TX_POWER_TABLE_COLUMNS] = { 2, 5, 20, 50, 160, 250, 300, 420, 500, 0, 0}; - const int infoASUSUSB56[TX_POWER_TABLE_COLUMNS] = { 2, 9, 30, 80, 200, 250, 300, 340, 370, 370, 150}; - const int infoRTLDualAnt[TX_POWER_TABLE_COLUMNS] = { 5, 17, 50, 150, 190, 210, 261, 310, 310, 310, 310}; - const int infoAli1W[TX_POWER_TABLE_COLUMNS] = { 1, 2, 5, 10, 30, 50, 100, 300, 450, 450, 450}; - const int infoA6100[TX_POWER_TABLE_COLUMNS] = { 1, 3, 9, 17, 30, 30, 35, 40, 0, 0, 0}; - const int infoAWUS036ACS[TX_POWER_TABLE_COLUMNS] = { 1, 2, 3, 10, 35, 50, 60, 90, 110, 0, 0}; - const int infoArcherT2UP[TX_POWER_TABLE_COLUMNS] = { 3, 10, 25, 55, 110, 120, 140, 150, 0, 0, 0}; - - const int infoRTL8812EU[TX_POWER_TABLE_COLUMNS] = { 3, 10, 25, 55, 110, 220, 340, 500, 0, 0, 0}; - - RenderTableLine(0, "Card / Power Level", s_iTxPowerLevelValues, true, false); - - m_yTemp += 0.3 * height_text; - if ( pP->iShowOnlyPresentTxPowerCards ) - m_yTemp += height_text; - - m_iLine = 0; - - bool bShowAtherosCards = false; - if ( m_bShowController && hardware_radio_has_atheros_cards() ) - bShowAtherosCards = true; - if ( m_bShowVehicle && (NULL != g_pCurrentModel) && g_pCurrentModel->hasRadioCardsAtheros() ) - bShowAtherosCards = true; - - bool bShowRTL8812AUCards = false; - if ( m_bShowController && hardware_radio_has_rtl8812au_cards() ) - bShowRTL8812AUCards = true; - if ( m_bShowVehicle && (NULL != g_pCurrentModel) && g_pCurrentModel->hasRadioCardsRTL8812AU() ) - bShowRTL8812AUCards = true; - - bool bShowRTL8812EUCards = false; - if ( m_bShowController && hardware_radio_has_rtl8812eu_cards() ) - bShowRTL8812EUCards = true; - if ( m_bShowVehicle && (NULL != g_pCurrentModel) && g_pCurrentModel->hasRadioCardsRTL8812EU() ) - bShowRTL8812EUCards = true; - - if ( bShowAtherosCards ) - { - RenderTableLine(CARD_MODEL_TPLINK722N, "TPLink WN722N", info722N, false, false); - RenderTableLine(CARD_MODEL_TPLINK722N, "WN722N + 2W Booster", info722N2W, false, false); - RenderTableLine(CARD_MODEL_TPLINK722N, "WN722N + 4W Booster", info722N4W, false, false); - RenderTableLine(CARD_MODEL_BLUE_STICK, "Blue Stick 2.4Ghz AR9271", infoBlueStick, false, false); - //RenderTableLine(CARD_MODEL_TPLINK722N, "Green Stick 2.4Ghz AR9271", infoGreenStick, false, false); - RenderTableLine(CARD_MODEL_ALFA_AWUS036NH, "Alfa AWUS036NH", infoAWUS036NH, false, false); - RenderTableLine(CARD_MODEL_ALFA_AWUS036NHA, "Alfa AWUS036NHA", infoAWUS036NHA, false, false); - } - if ( m_iLine != 0 ) - if ( (bShowRTL8812AUCards || bShowRTL8812EUCards) && bShowAtherosCards ) - m_bShowThinLine = true; - - if ( bShowRTL8812AUCards ) - { - RenderTableLine(CARD_MODEL_RTL8812AU_DUAL_ANTENNA, "RTLDualAntenna 5.8Ghz", infoRTLDualAnt, false, false); - RenderTableLine(CARD_MODEL_ASUS_AC56, "ASUS AC-56", infoASUSUSB56, false, false); - RenderTableLine(CARD_MODEL_ALFA_AWUS036ACH, "Alfa AWUS036ACH", infoAWUS036ACH, false, false); - RenderTableLine(CARD_MODEL_ALFA_AWUS036ACS, "Alfa AWUS036ACS", infoAWUS036ACS, false, false); - RenderTableLine(CARD_MODEL_ZIPRAY, "1 Watt 5.8Ghz", infoAli1W, false, false); - RenderTableLine(CARD_MODEL_NETGEAR_A6100, "Netgear A6100", infoA6100, false, false); - RenderTableLine(CARD_MODEL_TENDA_U12, "Tenda U12", infoGeneric, false, false); - RenderTableLine(CARD_MODEL_ARCHER_T2UPLUS, "Archer T2U Plus", infoArcherT2UP, false, false); - RenderTableLine(CARD_MODEL_RTL8814AU, "RTL8814AU", infoGeneric, false, false); - } - - if ( bShowRTL8812EUCards ) - { - RenderTableLine(CARD_MODEL_BLUE_8812EU, "RTL8812EU Blue", infoRTL8812EU, false, false); - } - - height_text = g_pRenderEngine->textHeight(g_idFontMenuSmall); - - if ( m_bShowVehicle && (NULL != g_pCurrentModel) ) - { - if ( g_pCurrentModel->hasRadioCardsRTL8812AU() ) - { - drawPowerLine("Vehicle TX Power (RTL8812AU):", m_yTopRender, g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU); - m_yTopRender += 1.4*height_text; - } - if ( g_pCurrentModel->hasRadioCardsRTL8812EU() ) - { - drawPowerLine("Vehicle TX Power (RTL8812EU):", m_yTopRender, g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU); - m_yTopRender += 1.4*height_text; - } - if ( g_pCurrentModel->hasRadioCardsAtheros() ) - { - drawPowerLine("Vehicle TX Power (Atheros):", m_yTopRender, g_pCurrentModel->radioInterfacesParams.txPowerAtheros); - m_yTopRender += 1.4*height_text; - } - } - - ControllerSettings* pCS = get_ControllerSettings(); - - if ( m_bShowController ) - { - if ( hardware_radio_has_rtl8812au_cards() ) - { - drawPowerLine("Controller TX Power (RTL8812AU):", m_yTopRender, pCS->iTXPowerRTL8812AU); - m_yTopRender += 1.4*height_text; - } - if ( hardware_radio_has_rtl8812eu_cards() ) - { - drawPowerLine("Controller TX Power (RTL8812EU):", m_yTopRender, pCS->iTXPowerRTL8812EU); - m_yTopRender += 1.4*height_text; - } - if ( hardware_radio_has_atheros_cards() ) - { - drawPowerLine("Controller TX Power (Atheros):", m_yTopRender, pCS->iTXPowerAtheros); - m_yTopRender += 1.4*height_text; - } - } - - g_pRenderEngine->drawText(m_xPos + Menu::getMenuPaddingX(), m_yTemp + 0.5*m_sfMenuPaddingY, g_idFontMenu, "* Power levels are measured at 5805 Mhz. Lower frequencies do increase the power a little bit."); -} - - -void MenuTXPower::sendPowerToVehicle(int txRTL8812AU, int txRTL8812EU, int txAtheros) -{ - u8 buffer[10]; - memset(&(buffer[0]), 0, 10); - buffer[0] = txRTL8812AU; - buffer[1] = txRTL8812EU; - buffer[2] = txAtheros; - buffer[3] = g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812AU; - buffer[4] = g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812EU; - buffer[5] = g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros; - - if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_TX_POWERS, 0, buffer, 8) ) - valuesToUI(); -} - - -int MenuTXPower::onBack() -{ - if ( m_bValuesChangedController ) - { - #if defined(HW_PLATFORM_RASPBERRY) - - MenuConfirmation* pMC = new MenuConfirmation("Restart Required","You need to restart the controller for the power changes to take effect.", 2); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - - if ( (NULL != g_pCurrentModel) && (g_pCurrentModel->rc_params.rc_enabled) ) - { - pMC->addTopLine("Warning! You have RC link enabled. RC link will be lost while the controller restarts."); - } - pMC->addTopLine("Do you want to restart your controller now?"); - add_menu_to_stack(pMC); - return 1; - #endif - } - - if ( m_bValuesChangedVehicle ) - if ( (g_pCurrentModel != NULL) && (! g_pCurrentModel->isRunningOnOpenIPCHardware() ) ) - { - char szTextW[256]; - sprintf(szTextW, "You need to restart the %s for the power changes to take effect.", g_pCurrentModel->getVehicleTypeString()); - MenuConfirmation* pMC = new MenuConfirmation("Restart Required",szTextW, 3); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - - if ( (NULL != g_pCurrentModel) && (g_pCurrentModel->rc_params.rc_enabled) ) - { - pMC->addTopLine("Warning! You have RC link enabled. RC link will be lost while the vehicle restarts."); - } - sprintf(szTextW, "Do you want to restart your %s now?", g_pCurrentModel->getVehicleTypeString()); - pMC->addTopLine(szTextW); - add_menu_to_stack(pMC); - return 1; - } - return Menu::onBack(); -} - -void MenuTXPower::onReturnFromChild(int iChildMenuId, int returnValue) -{ - Menu::onReturnFromChild(iChildMenuId, returnValue); - - if ( 2 == iChildMenuId/1000 ) - { - m_bValuesChangedController = false; - if ( 1 == returnValue ) - { - onEventReboot(); - hardware_reboot(); - return; - } - menu_stack_pop(0); - return; - } - - if ( 3 == iChildMenuId/1000 ) - { - m_bValuesChangedVehicle = false; - if ( 1 == returnValue ) - { - handle_commands_send_to_vehicle(COMMAND_ID_REBOOT, 0, NULL, 0); - valuesToUI(); - menu_discard_all(); - return; - } - return; - } - - valuesToUI(); -} - -void MenuTXPower::onSelectItem() -{ - Menu::onSelectItem(); - - if ( m_pMenuItems[m_SelectedIndex]->isEditing() ) - return; - - if ( handle_commands_is_command_in_progress() ) - { - handle_commands_show_popup_progress(); - return; - } - - ControllerSettings* pCS = get_ControllerSettings(); - Preferences* pP = get_Preferences(); - - if ( m_IndexShowAllCards == m_SelectedIndex ) - { - pP->iShowOnlyPresentTxPowerCards = 1- m_pItemsSelect[0]->getSelectedIndex(); - save_Preferences(); - valuesToUI(); - invalidate(); - return; - } - - if ( m_IndexShowBoosters == m_SelectedIndex ) - { - pP->iShowTxBoosters = m_pItemsSelect[1]->getSelectedIndex(); - save_Preferences(); - valuesToUI(); - invalidate(); - return; - } - - if ( m_IndexPowerControllerRTL8812AU == m_SelectedIndex ) - { - if ( pCS->iTXPowerRTL8812AU != m_pItemsSlider[m_SelectedIndex]->getCurrentValue() ) - m_bValuesChangedController = true; - pCS->iTXPowerRTL8812AU = m_pItemsSlider[m_SelectedIndex]->getCurrentValue(); - save_ControllerSettings(); - hardware_radio_set_txpower_rtl8812au(pCS->iTXPowerRTL8812AU); - - if ( m_pItemsSlider[m_SelectedIndex]->getCurrentValue() > 59 ) - { - MenuConfirmation* pMC = new MenuConfirmation("High Power Levels","Setting a card to a very high power level can fry it if it does not have proper cooling.", 1, true); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - pMC->addTopLine("Proceed with caution!"); - add_menu_to_stack(pMC); - } - return; - } - - if ( m_IndexPowerControllerRTL8812EU == m_SelectedIndex ) - { - if ( pCS->iTXPowerRTL8812EU != m_pItemsSlider[m_SelectedIndex]->getCurrentValue() ) - m_bValuesChangedController = true; - pCS->iTXPowerRTL8812EU = m_pItemsSlider[m_SelectedIndex]->getCurrentValue(); - save_ControllerSettings(); - hardware_radio_set_txpower_rtl8812eu(pCS->iTXPowerRTL8812EU); - - if ( m_pItemsSlider[m_SelectedIndex]->getCurrentValue() > 59 ) - { - MenuConfirmation* pMC = new MenuConfirmation("High Power Levels","Setting a card to a very high power level can fry it if it does not have proper cooling.", 1, true); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - pMC->addTopLine("Proceed with caution!"); - add_menu_to_stack(pMC); - } - return; - } - - if ( m_IndexPowerControllerAtheros == m_SelectedIndex ) - { - if ( pCS->iTXPowerAtheros != m_pItemsSlider[m_SelectedIndex]->getCurrentValue() ) - m_bValuesChangedController = true; - pCS->iTXPowerAtheros = m_pItemsSlider[m_SelectedIndex]->getCurrentValue(); - save_ControllerSettings(); - hardware_radio_set_txpower_atheros(pCS->iTXPowerAtheros); - - if ( m_pItemsSlider[m_SelectedIndex]->getCurrentValue() > 59 ) - { - MenuConfirmation* pMC = new MenuConfirmation("High Power Levels","Setting a card to a very high power level can fry it if it does not have proper cooling.", 1, true); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - pMC->addTopLine("Proceed with caution!"); - add_menu_to_stack(pMC); - } - return; - } - - if ( (m_IndexPowerVehicleRTL8812AU == m_SelectedIndex) && menu_check_current_model_ok_for_edit() ) - { - int val = m_pItemsSlider[m_SelectedIndex]->getCurrentValue(); - if ( g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU != val ) - m_bValuesChangedVehicle = true; - - sendPowerToVehicle(val, g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU, g_pCurrentModel->radioInterfacesParams.txPowerAtheros); - - if ( val > 59 ) - { - MenuConfirmation* pMC = new MenuConfirmation("High Power Levels","Setting a card to a very high power level can fry it if it does not have proper cooling.", 1, true); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - pMC->addTopLine("Proceed with caution!"); - add_menu_to_stack(pMC); - } - return; - } - - if ( (m_IndexPowerVehicleRTL8812EU == m_SelectedIndex) && menu_check_current_model_ok_for_edit() ) - { - int val = m_pItemsSlider[m_SelectedIndex]->getCurrentValue(); - if ( g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU != val ) - m_bValuesChangedVehicle = true; - - sendPowerToVehicle(g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU, val, g_pCurrentModel->radioInterfacesParams.txPowerAtheros); - - if ( val > 59 ) - { - MenuConfirmation* pMC = new MenuConfirmation("High Power Levels","Setting a card to a very high power level can fry it if it does not have proper cooling.", 1, true); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - pMC->addTopLine("Proceed with caution!"); - add_menu_to_stack(pMC); - } - return; - } - - if ( (m_IndexPowerVehicleAtheros == m_SelectedIndex) && menu_check_current_model_ok_for_edit() ) - { - int val = m_pItemsSlider[m_SelectedIndex]->getCurrentValue(); - if ( g_pCurrentModel->radioInterfacesParams.txPowerAtheros != val ) - m_bValuesChangedVehicle = true; - - sendPowerToVehicle(g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU, g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU, val); - - if ( val > 59 ) - { - MenuConfirmation* pMC = new MenuConfirmation("High Power Levels","Setting a card to a very high power level can fry it if it does not have proper cooling.", 1, true); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - pMC->addTopLine("Proceed with caution!"); - add_menu_to_stack(pMC); - } - return; - } - - if ( m_IndexPowerMax == m_SelectedIndex ) - { - MenuTXPowerMax* pMenu = new MenuTXPowerMax(); - pMenu->m_bShowVehicle = m_bShowVehicle; - pMenu->m_bShowController = m_bShowController; - add_menu_to_stack(pMenu); - } -} diff --git a/code/r_central/menu/menu_tx_power.h b/code/r_central/menu/menu_tx_power.h deleted file mode 100644 index 17391f9e..00000000 --- a/code/r_central/menu/menu_tx_power.h +++ /dev/null @@ -1,49 +0,0 @@ -#pragma once -#include "menu_objects.h" -#include "menu_item_select.h" -#include "menu_item_slider.h" - -class MenuTXPower: public Menu -{ - public: - MenuTXPower(); - virtual ~MenuTXPower(); - virtual void onShow(); - virtual void valuesToUI(); - virtual int onBack(); - virtual void onReturnFromChild(int iChildMenuId, int returnValue); - virtual void Render(); - virtual void onSelectItem(); - - bool m_bShowController; - bool m_bShowVehicle; - - protected: - void RenderTableLine(int iCardModel, const char* szText, const int* piValues, bool bIsHeader, bool bIsBoosterLine); - void drawPowerLine(const char* szText, float yPos, int value); - void sendPowerToVehicle(int txRTL8812AU, int txRTL8812EU, int txAtheros); - - float m_yTemp; - float m_yTopRender; - float m_xTable; - float m_xTableCellWidth; - int m_iLine; - - MenuItemSlider* m_pItemsSlider[10]; - MenuItemSelect* m_pItemsSelect[10]; - - bool m_bShowThinLine; - - int m_IndexPowerVehicleRTL8812AU; - int m_IndexPowerVehicleRTL8812EU; - int m_IndexPowerVehicleAtheros; - int m_IndexPowerControllerRTL8812AU; - int m_IndexPowerControllerRTL8812EU; - int m_IndexPowerControllerAtheros; - int m_IndexPowerMax; - int m_IndexShowAllCards; - int m_IndexShowBoosters; - - bool m_bValuesChangedVehicle; - bool m_bValuesChangedController; -}; \ No newline at end of file diff --git a/code/r_central/menu/menu_tx_power_max.cpp b/code/r_central/menu/menu_tx_power_max.cpp deleted file mode 100644 index f591b8c8..00000000 --- a/code/r_central/menu/menu_tx_power_max.cpp +++ /dev/null @@ -1,261 +0,0 @@ -/* - Ruby Licence - Copyright (c) 2024 Petru Soroaga petrusoroaga@yahoo.com - All rights reserved. - - Redistribution and use in source and/or binary forms, with or without - modification, are permitted provided that the following conditions are met: - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - * Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - * Copyright info and developer info must be preserved as is in the user - interface, additions could be made to that info. - * Neither the name of the organization nor the - names of its contributors may be used to endorse or promote products - derived from this software without specific prior written permission. - * Military use is not permited. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND - ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED - WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE AUTHOR (PETRU SOROAGA) BE LIABLE FOR ANY - DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES - (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND - ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT - (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS - SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*/ - -#include "menu.h" -#include "menu_tx_power_max.h" -#include "menu_objects.h" -#include "menu_item_text.h" -#include "menu_confirmation.h" - -MenuTXPowerMax::MenuTXPowerMax() -:Menu(MENU_ID_TX_POWER_MAX, "Set Radio Power Limits", NULL) -{ - m_Width = 0.42; - m_xPos = menu_get_XStartPos(m_Width)-0.03; m_yPos = 0.2; - - m_bShowController = false; - m_bShowVehicle = false; - - - m_IndexPowerMaxControllerRTL8812AU = -1; - m_IndexPowerMaxControllerRTL8812EU = -1; - m_IndexPowerMaxControllerAtheros = -1; - - m_IndexPowerMaxVehicleRTL8812AU = -1; - m_IndexPowerMaxVehicleRTL8812EU = -1; - m_IndexPowerMaxVehicleAtheros = -1; - - addTopLine("You can limit the max output power level from your radio cards to avoid for example buring the input of a Tx booster if you are using one."); -} - -MenuTXPowerMax::~MenuTXPowerMax() -{ -} - -void MenuTXPowerMax::onShow() -{ - float fSliderWidth = 0.18; - removeAllItems(); - - int iSliderIndex = 0; - if ( m_bShowVehicle ) - { - if ( g_pCurrentModel->hasRadioCardsRTL8812AU() ) - { - m_pItemsSlider[iSliderIndex] = new MenuItemSlider("Vehicle Max Tx Power (RTL8812AU)", "Sets the maximum allowed TX power on current vehicle for RTL8812AU cards.", 1,MAX_TX_POWER,40, fSliderWidth); - m_IndexPowerMaxVehicleRTL8812AU = addMenuItem(m_pItemsSlider[iSliderIndex]); - iSliderIndex++; - } - if ( g_pCurrentModel->hasRadioCardsRTL8812EU() ) - { - m_pItemsSlider[iSliderIndex] = new MenuItemSlider("Vehicle Max Tx Power (RTL8812EU)", "Sets the maximum allowed TX power on current vehicle for RTL8812EU cards.", 1,MAX_TX_POWER,40, fSliderWidth); - m_IndexPowerMaxVehicleRTL8812EU = addMenuItem(m_pItemsSlider[iSliderIndex]); - iSliderIndex++; - } - if ( g_pCurrentModel->hasRadioCardsAtheros() ) - { - m_pItemsSlider[iSliderIndex] = new MenuItemSlider("Vehicle Max Tx Power (Atheros)", "Sets the maximum allowed TX power on current vehicle for Atheros cards.", 1,MAX_TX_POWER,40, fSliderWidth); - m_IndexPowerMaxVehicleAtheros = addMenuItem(m_pItemsSlider[iSliderIndex]); - iSliderIndex++; - } - } - - if ( m_bShowController ) - { - if ( hardware_radio_has_rtl8812au_cards() ) - { - m_pItemsSlider[iSliderIndex] = new MenuItemSlider("Controller Max Tx Power (RTL8812AU)", "Sets the maximum allowed TX power on controller for RTL8812AU cards.", 1,MAX_TX_POWER,40, fSliderWidth); - m_IndexPowerMaxControllerRTL8812AU = addMenuItem(m_pItemsSlider[iSliderIndex]); - iSliderIndex++; - } - if ( hardware_radio_has_rtl8812eu_cards() ) - { - m_pItemsSlider[iSliderIndex] = new MenuItemSlider("Controller Max Tx Power (RTL8812EU)", "Sets the maximum allowed TX power on controller for RTL8812EU cards.", 1,MAX_TX_POWER,40, fSliderWidth); - m_IndexPowerMaxControllerRTL8812EU = addMenuItem(m_pItemsSlider[iSliderIndex]); - iSliderIndex++; - } - if ( hardware_radio_has_atheros_cards() ) - { - m_pItemsSlider[iSliderIndex] = new MenuItemSlider("Controller Max Tx Power (Atheros)", "Sets the maximum allowed TX power on controller for Atheros cards.", 1,MAX_TX_POWER,40, fSliderWidth); - m_IndexPowerMaxControllerAtheros = addMenuItem(m_pItemsSlider[iSliderIndex]); - iSliderIndex++; - } - } - Menu::onShow(); -} - -void MenuTXPowerMax::valuesToUI() -{ - ControllerSettings* pCS = get_ControllerSettings(); - - int iSliderIndex = 0; - if ( m_bShowVehicle ) - { - if ( g_pCurrentModel->hasRadioCardsRTL8812AU() ) - { - m_pItemsSlider[iSliderIndex]->setCurrentValue(g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812AU); - iSliderIndex++; - } - if ( g_pCurrentModel->hasRadioCardsRTL8812EU() ) - { - m_pItemsSlider[iSliderIndex]->setCurrentValue(g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812EU); - iSliderIndex++; - } - if ( g_pCurrentModel->hasRadioCardsAtheros() ) - { - m_pItemsSlider[iSliderIndex]->setCurrentValue(g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros); - iSliderIndex++; - } - } - - if ( m_bShowController ) - { - if ( hardware_radio_has_rtl8812au_cards() ) - { - m_pItemsSlider[iSliderIndex]->setCurrentValue(pCS->iMaxTXPowerRTL8812AU); - iSliderIndex++; - } - if ( hardware_radio_has_rtl8812eu_cards() ) - { - m_pItemsSlider[iSliderIndex]->setCurrentValue(pCS->iMaxTXPowerRTL8812EU); - iSliderIndex++; - } - if ( hardware_radio_has_atheros_cards() ) - { - m_pItemsSlider[iSliderIndex]->setCurrentValue(pCS->iMaxTXPowerAtheros); - iSliderIndex++; - } - } -} - -void MenuTXPowerMax::Render() -{ - RenderPrepare(); - float yTop = RenderFrameAndTitle(); - float y = yTop; - - for( int i=0; iradioInterfacesParams.txPowerRTL8812AU; - buffer[1] = g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU; - buffer[2] = g_pCurrentModel->radioInterfacesParams.txPowerAtheros; - buffer[3] = txMaxRTL8812AU; - buffer[4] = txMaxRTL8812EU; - buffer[5] = txMaxAtheros; - - if ( buffer[0] > buffer[3] ) - buffer[0] = buffer[3]; - if ( buffer[1] > buffer[4] ) - buffer[1] = buffer[4]; - if ( buffer[2] > buffer[5] ) - buffer[2] = buffer[5]; - if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_TX_POWERS, 0, buffer, 8) ) - valuesToUI(); -} - -void MenuTXPowerMax::onSelectItem() -{ - ControllerSettings* pCS = get_ControllerSettings(); - Menu::onSelectItem(); - - if ( m_pMenuItems[m_SelectedIndex]->isEditing() ) - return; - - if ( handle_commands_is_command_in_progress() ) - { - handle_commands_show_popup_progress(); - return; - } - - if ( m_IndexPowerMaxControllerRTL8812AU == m_SelectedIndex ) - { - pCS->iMaxTXPowerRTL8812AU = m_pItemsSlider[m_IndexPowerMaxControllerRTL8812AU]->getCurrentValue(); - if ( pCS->iTXPowerRTL8812AU > pCS->iMaxTXPowerRTL8812AU ) - { - pCS->iTXPowerRTL8812AU = pCS->iMaxTXPowerRTL8812AU; - hardware_radio_set_txpower_rtl8812au(pCS->iTXPowerRTL8812AU); - } - save_ControllerSettings(); - return; - } - - if ( m_IndexPowerMaxControllerRTL8812EU == m_SelectedIndex ) - { - pCS->iMaxTXPowerRTL8812EU = m_pItemsSlider[m_IndexPowerMaxControllerRTL8812EU]->getCurrentValue(); - if ( pCS->iTXPowerRTL8812EU > pCS->iMaxTXPowerRTL8812EU ) - { - pCS->iTXPowerRTL8812EU = pCS->iMaxTXPowerRTL8812EU; - hardware_radio_set_txpower_rtl8812eu(pCS->iTXPowerRTL8812EU); - } - save_ControllerSettings(); - return; - } - - if ( m_IndexPowerMaxControllerAtheros == m_SelectedIndex ) - { - pCS->iMaxTXPowerAtheros = m_pItemsSlider[m_IndexPowerMaxControllerAtheros]->getCurrentValue(); - if ( pCS->iTXPowerAtheros > pCS->iMaxTXPowerAtheros ) - { - pCS->iTXPowerAtheros = pCS->iMaxTXPowerAtheros; - hardware_radio_set_txpower_atheros(pCS->iTXPowerAtheros); - } - save_ControllerSettings(); - return; - } - - if ( m_IndexPowerMaxVehicleRTL8812AU == m_SelectedIndex && menu_check_current_model_ok_for_edit() ) - { - int val = m_pItemsSlider[m_IndexPowerMaxVehicleRTL8812AU]->getCurrentValue(); - sendMaxPowerToVehicle(val, g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812EU, g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros); - return; - } - - if ( m_IndexPowerMaxVehicleRTL8812EU == m_SelectedIndex && menu_check_current_model_ok_for_edit() ) - { - int val = m_pItemsSlider[m_IndexPowerMaxVehicleRTL8812EU]->getCurrentValue(); - sendMaxPowerToVehicle(g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812AU, val, g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros); - return; - } - - if ( m_IndexPowerMaxVehicleAtheros == m_SelectedIndex && menu_check_current_model_ok_for_edit() ) - { - int val = m_pItemsSlider[m_IndexPowerMaxVehicleAtheros]->getCurrentValue(); - sendMaxPowerToVehicle(g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812AU, g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812EU, val); - return; - } -} \ No newline at end of file diff --git a/code/r_central/menu/menu_tx_power_max.h b/code/r_central/menu/menu_tx_power_max.h deleted file mode 100644 index 23acb8ef..00000000 --- a/code/r_central/menu/menu_tx_power_max.h +++ /dev/null @@ -1,31 +0,0 @@ -#pragma once -#include "menu_objects.h" -#include "menu_item_select.h" -#include "menu_item_slider.h" - -class MenuTXPowerMax: public Menu -{ - public: - MenuTXPowerMax(); - virtual ~MenuTXPowerMax(); - virtual void onShow(); - virtual void valuesToUI(); - virtual void Render(); - virtual void onSelectItem(); - - bool m_bShowController; - bool m_bShowVehicle; - - private: - void sendMaxPowerToVehicle(int txMaxRTL8812AU, int txMaxRTL8812EU, int txMaxAtheros); - - MenuItemSlider* m_pItemsSlider[10]; - MenuItemSelect* m_pItemsSelect[10]; - - int m_IndexPowerMaxVehicleRTL8812AU; - int m_IndexPowerMaxVehicleRTL8812EU; - int m_IndexPowerMaxVehicleAtheros; - int m_IndexPowerMaxControllerRTL8812AU; - int m_IndexPowerMaxControllerRTL8812EU; - int m_IndexPowerMaxControllerAtheros; -}; \ No newline at end of file diff --git a/code/r_central/menu/menu_tx_raw_power.cpp b/code/r_central/menu/menu_tx_raw_power.cpp new file mode 100644 index 00000000..d020a627 --- /dev/null +++ b/code/r_central/menu/menu_tx_raw_power.cpp @@ -0,0 +1,355 @@ +/* + Ruby Licence + Copyright (c) 2024 Petru Soroaga petrusoroaga@yahoo.com + All rights reserved. + + Redistribution and use in source and/or binary forms, with or without + modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Copyright info and developer info must be preserved as is in the user + interface, additions could be made to that info. + * Neither the name of the organization nor the + names of its contributors may be used to endorse or promote products + derived from this software without specific prior written permission. + * Military use is not permited. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE AUTHOR (PETRU SOROAGA) BE LIABLE FOR ANY + DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#include "menu.h" +#include "menu_tx_raw_power.h" +#include "menu_objects.h" +#include "menu_item_text.h" +#include "menu_item_section.h" +#include "menu_confirmation.h" +#include "../../utils/utils_controller.h" +#include "../../base/tx_powers.h" + +MenuTXRawPower::MenuTXRawPower() +:Menu(MENU_ID_TX_RAW_POWER, "Custom Radio Power Levels", NULL) +{ + m_Width = 0.42; + m_xPos = menu_get_XStartPos(m_Width); + m_yPos = 0.18; + m_bShowVehicleSide = true; +} + +MenuTXRawPower::~MenuTXRawPower() +{ +} + +void MenuTXRawPower::onShow() +{ + addItems(); + Menu::onShow(); +} + +void MenuTXRawPower::valuesToUI() +{ + addItems(); +} + + +void MenuTXRawPower::addItems() +{ + int iTmp = getSelectedMenuItemIndex(); + ControllerSettings* pCS = get_ControllerSettings(); + + removeAllItems(); + + for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) + { + int iDriver = (g_pCurrentModel->radioInterfacesParams.interface_radiotype_and_driver[i] >> 8) & 0xFF; + int iCardModel = g_pCurrentModel->radioInterfacesParams.interface_card_model[i]; + int iPowerRaw = g_pCurrentModel->radioInterfacesParams.interface_raw_power[i]; + + m_pItemSelectVehicleCards[i] = createItemCard(true, i, iCardModel, iDriver, iPowerRaw); + if ( NULL != m_pItemSelectVehicleCards[i] ) + m_iIndexVehicleCards[i] = addMenuItem(m_pItemSelectVehicleCards[i]); + } + } + } + + addMenuItem(new MenuItemSection("Controller's Radio Interfaces Tx Powers")); + + m_iIndexAutoControllerPower = -1; + if ( m_bShowVehicleSide && pCS->iFixedTxPower ) + { + addMenuItem(new MenuItemText("Controller is set globally to fixed Tx power. Set it to Auto in the Controller menu if you want to be able to customize it per vehicle.")); + } + else + { + if ( m_bShowVehicleSide && (NULL != g_pCurrentModel) ) + { + m_pItemsSelect[0] = new MenuItemSelect("Auto-adjust Controller Tx Power", "Controller will auto-adjusts radio tx power to match the current vehicle."); + m_pItemsSelect[0]->addSelection("No"); + m_pItemsSelect[0]->addSelection("Yes"); + m_pItemsSelect[0]->setIsEditable(); + m_iIndexAutoControllerPower = addMenuItem(m_pItemsSelect[0]); + if ( g_pCurrentModel->radioInterfacesParams.iAutoControllerTxPower ) + m_pItemsSelect[0]->setSelectedIndex(1); + else + m_pItemsSelect[0]->setSelectedIndex(0); + } + for( int i=0; iisConfigurable) || (! pRadioHWInfo->isSupported) ) + continue; + + t_ControllerRadioInterfaceInfo* pCRII = controllerGetRadioCardInfo(pRadioHWInfo->szMAC); + if ( NULL == pCRII ) + continue; + + m_pItemSelectControllerCards[i] = createItemCard(false, i, pCRII->cardModel, pRadioHWInfo->iRadioDriver, pCRII->iRawPowerLevel); + if ( NULL != m_pItemSelectControllerCards[i] ) + { + m_iIndexControllerCards[i] = addMenuItem(m_pItemSelectControllerCards[i]); + if ( m_bShowVehicleSide ) + if ( g_pCurrentModel->radioInterfacesParams.iAutoControllerTxPower ) + m_pItemSelectControllerCards[i]->setEnabled(false); + } + } + } + m_SelectedIndex = iTmp; + if ( m_SelectedIndex >= m_ItemsCount ) + m_SelectedIndex = m_ItemsCount-1; +} + + +MenuItemSelect* MenuTXRawPower::createItemCard(bool bVehicle, int iCardIndex, int iCardModel, int iDriver, int iRawPower) +{ + char szText[128]; + char szTooltip[256]; + sprintf(szText, "Interface %d (%s)", iCardIndex+1, str_get_radio_card_model_string(iCardModel)); + sprintf(szTooltip, "Adjust the output tx power of %s's radio interface %d", bVehicle?"vehicle":"controller", iCardIndex+1); + MenuItemSelect* pItemSelect = new MenuItemSelect(szText, szTooltip); + + int iMaxRawPowerForCard = tx_powers_get_max_usable_power_raw_for_card(iDriver, iCardModel); + int iIndexSelected = -1; + int iMinRawDiff = 10000; + + int iRawValuesCount = 0; + const int* piRawValues = tx_powers_get_raw_radio_power_values(&iRawValuesCount); + + for( int i=0; i iMaxRawPowerForCard ) + sprintf(szText, "%d -> !!!", piRawValues[i]); + else + { + int iMwValue = tx_powers_convert_raw_to_mw(iDriver, iCardModel, piRawValues[i]); + sprintf(szText, "%d -> %d mW", piRawValues[i], iMwValue); + } + pItemSelect->addSelection(szText); + int iDiff = iRawPower - piRawValues[i]; + if ( iDiff < 0 ) + iDiff = - iDiff; + + if ( iDiff < iMinRawDiff ) + { + iMinRawDiff = iDiff; + iIndexSelected = pItemSelect->getSelectionsCount()-1; + } + } + + pItemSelect->setIsEditable(); + if ( -1 != iIndexSelected ) + pItemSelect->setSelectedIndex(iIndexSelected); + return pItemSelect; +} + +void MenuTXRawPower::computeSendPowerToVehicle(int iCardIndex) +{ + if ( (iCardIndex < 0) || (iCardIndex >= g_pCurrentModel->radioInterfacesParams.interfaces_count) ) + { + addMessage("Invalid card."); + return; + } + int iRawValuesCount = 0; + const int* piRawValues = tx_powers_get_raw_radio_power_values(&iRawValuesCount); + + int iPowerIndex = m_pItemSelectVehicleCards[iCardIndex]->getSelectedIndex(); + if ( (iPowerIndex < 0) || (iPowerIndex >= iRawValuesCount) ) + { + addMessage("Invalid value"); + return; + } + int iRawPowerToSet = piRawValues[iPowerIndex]; + log_line("MenuTXRawPower: Setting raw tx power for card %d to: %d", iCardIndex+1, iRawPowerToSet); + + u8 uCommandParams[MAX_RADIO_INTERFACES+1]; + uCommandParams[0] = g_pCurrentModel->radioInterfacesParams.interfaces_count; + + for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) + { + int iDriver = (g_pCurrentModel->radioInterfacesParams.interface_radiotype_and_driver[i] >> 8) & 0xFF; + int iCardModel = g_pCurrentModel->radioInterfacesParams.interface_card_model[i]; + uCommandParams[i+1] = g_pCurrentModel->radioInterfacesParams.interface_raw_power[i]; + if ( i == iCardIndex ) + uCommandParams[i+1] = iRawPowerToSet; + + int iCardMaxPowerMw = tx_powers_get_max_usable_power_mw_for_card(iDriver, iCardModel); + int iCardPowerMw = tx_powers_convert_raw_to_mw(iDriver, iCardModel, uCommandParams[i+1]); + + log_line("MenuTXRawPower: Setting tx raw power for card %d from %d to: %d (%d mw, max is %d mw)", + i+1, g_pCurrentModel->radioInterfacesParams.interface_raw_power[i], uCommandParams[i+1], iCardPowerMw, iCardMaxPowerMw); + } + + save_ControllerInterfacesSettings(); + apply_controller_radio_tx_powers(g_pCurrentModel, get_ControllerSettings()->iFixedTxPower, false); + save_ControllerInterfacesSettings(); + + if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_TX_POWERS, 0, uCommandParams, uCommandParams[0]+1) ) + valuesToUI(); +} + +void MenuTXRawPower::computeApplyControllerPower(int iCardIndex) +{ + if ( (iCardIndex < 0) || (iCardIndex >= hardware_get_radio_interfaces_count()) ) + { + addMessage("Invalid card."); + return; + } + + int iRawValuesCount = 0; + const int* piRawValues = tx_powers_get_raw_radio_power_values(&iRawValuesCount); + + int iPowerIndex = m_pItemSelectControllerCards[iCardIndex]->getSelectedIndex(); + if ( (iPowerIndex < 0) || (iPowerIndex >= iRawValuesCount) ) + { + addMessage("Invalid value"); + return; + } + int iRawPowerToSet = piRawValues[iPowerIndex]; + + if ( ! hardware_radio_is_index_wifi_radio(iCardIndex) ) + return; + + if ( hardware_radio_index_is_sik_radio(iCardIndex) ) + return; + + radio_hw_info_t* pRadioHWInfo = hardware_get_radio_info(iCardIndex); + if ( (! pRadioHWInfo->isConfigurable) || (! pRadioHWInfo->isSupported) ) + return; + + t_ControllerRadioInterfaceInfo* pCRII = controllerGetRadioCardInfo(pRadioHWInfo->szMAC); + if ( NULL == pCRII ) + return; + + pCRII->iRawPowerLevel = iRawPowerToSet; + + save_ControllerInterfacesSettings(); + valuesToUI(); + apply_controller_radio_tx_powers(g_pCurrentModel, get_ControllerSettings()->iFixedTxPower, false); + save_ControllerInterfacesSettings(); + send_model_changed_message_to_router(MODEL_CHANGED_RADIO_POWERS, 0); +} + +void MenuTXRawPower::Render() +{ + RenderPrepare(); + + float yTop = RenderFrameAndTitle(); + float y = yTop; + + for( int i=0; iisEditing() ) + return; + + if ( handle_commands_is_command_in_progress() ) + { + handle_commands_show_popup_progress(); + return; + } + + if ( (-1 != m_iIndexAutoControllerPower) && (m_iIndexAutoControllerPower == m_SelectedIndex) ) + if ( NULL != g_pCurrentModel ) + { + u32 uIndex = m_pItemsSelect[0]->getSelectedIndex(); + save_ControllerSettings(); + u32 uParam = 0; + uParam |= uIndex << 8; + if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_AUTO_TX_POWERS, uParam, NULL, 0) ) + valuesToUI(); + return; + } + + if ( m_bShowVehicleSide ) + { + for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) + { + if ( (m_iIndexVehicleCards[i] != -1) && (m_iIndexVehicleCards[i] == m_SelectedIndex) ) + if ( NULL != m_pItemSelectVehicleCards[i] ) + { + computeSendPowerToVehicle(i); + return; + } + } + } + + for( int i=0; iiRadioType == RADIO_TYPE_ATHEROS ) - m_bControllerHas24Cards = true; - if ( pNIC->iRadioType == RADIO_TYPE_RALINK ) - m_bControllerHas24Cards = true; - else - m_bControllerHas58Cards = true; - } - - if ( m_bControllerHas24Cards && m_bControllerHas58Cards ) - m_bShowBothOnController = true; - - if ( NULL != g_pCurrentModel ) - { - for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) - { - if ( ((g_pCurrentModel->radioInterfacesParams.interface_radiotype_and_driver[i] & 0xFF00) >> 8) == RADIO_HW_DRIVER_ATHEROS ) - m_bVehicleHas24Cards = true; - if ( ((g_pCurrentModel->radioInterfacesParams.interface_radiotype_and_driver[i] & 0xFF00) >> 8) == RADIO_HW_DRIVER_RALINK ) - m_bVehicleHas24Cards = true; - else - m_bVehicleHas58Cards = true; - } - } - - if ( m_bVehicleHas24Cards && m_bVehicleHas58Cards ) - m_bShowBothOnVehicle = true; - - if ( m_bShowVehicle && m_bVehicleHas24Cards ) - m_bDisplay24Cards = true; - if ( m_bShowController && m_bControllerHas24Cards ) - m_bDisplay24Cards = true; - if ( m_bShowVehicle && m_bVehicleHas58Cards ) - m_bDisplay58Cards = true; - if ( m_bShowController && m_bControllerHas58Cards ) - m_bDisplay58Cards = true; - - removeAllItems(); - - m_IndexPowerController = -1; - m_IndexPowerControllerAtheros = -1; - m_IndexPowerControllerRTL = -1; - - m_IndexPowerVehicle = -1; - m_IndexPowerVehicleAtheros = -1; - m_IndexPowerVehicleRTL = -1; - - if ( m_bShowVehicle && (NULL != g_pCurrentModel) ) - { - if ( ! m_bShowBothOnVehicle ) - { - if ( m_bVehicleHas24Cards ) - m_pItemsSlider[0] = new MenuItemSlider("Vehicle Tx Power", "Sets the radio TX power used on the vehicle. Requires a reboot of the vehicle after change.", 1, g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros, g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros/2, fSliderWidth); - else - m_pItemsSlider[0] = new MenuItemSlider("Vehicle Tx Power", "Sets the radio TX power used on the vehicle. Requires a reboot of the vehicle after change.", 1, g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL, g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL/2, fSliderWidth); - m_IndexPowerVehicle = addMenuItem(m_pItemsSlider[0]); - } - else - { - char szBuff[256]; - char szCards[256]; - - szCards[0] = 0; - for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) - { - if ( ((g_pCurrentModel->radioInterfacesParams.interface_radiotype_and_driver[i] & 0xFF00) >> 8) == RADIO_HW_DRIVER_ATHEROS ) - strcat(szCards, " Atheros"); - if ( ((g_pCurrentModel->radioInterfacesParams.interface_radiotype_and_driver[i] & 0xFF00) >> 8) == RADIO_HW_DRIVER_RALINK ) - strcat(szCards, " RaLink"); - } - - snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "Vehicle Tx Power (2.4Ghz%s)", szCards); - m_pItemsSlider[1] = new MenuItemSlider(szBuff, "Sets the radio TX power used on the vehicle for Atheros/RaLink cards. Requires a reboot of the vehicle after change.", 1, g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros, g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros/2, fSliderWidth); - m_IndexPowerVehicleAtheros = addMenuItem(m_pItemsSlider[1]); - m_pItemsSlider[2] = new MenuItemSlider("Vehicle Tx Power (5.8Ghz)", "Sets the radio TX power used on the vehicle for RTL cards. Requires a reboot of the vehicle after change.", 1, g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL, g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL/2, fSliderWidth); - m_IndexPowerVehicleRTL = addMenuItem(m_pItemsSlider[2]); - } - } - - if ( m_bShowController ) - { - if ( ! m_bShowBothOnController ) - { - if ( m_bControllerHas24Cards ) - m_pItemsSlider[5] = new MenuItemSlider("Controller Tx Power", "Sets the radio TX power used on the controller. Requires a reboot of the controller after change.", 1, pCS->iMaxTXPowerAtheros, pCS->iMaxTXPowerAtheros/2, fSliderWidth); - else - m_pItemsSlider[5] = new MenuItemSlider("Controller Tx Power", "Sets the radio TX power used on the controller. Requires a reboot of the controller after change.", 1, pCS->iMaxTXPowerRTL, pCS->iMaxTXPowerRTL/2, fSliderWidth); - m_IndexPowerController = addMenuItem(m_pItemsSlider[5]); - } - else - { - char szBuff[256]; - char szCards[256]; - - szCards[0] = 0; - for( int n=0; niRadioType == RADIO_TYPE_ATHEROS ) - strcat(szCards, " Atheros"); - if ( pRadioHWInfo->iRadioType == RADIO_TYPE_RALINK ) - strcat(szCards, " RaLink"); - } - - snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "Controller Tx Power (2.4Ghz%s)", szCards); - m_pItemsSlider[6] = new MenuItemSlider(szBuff, "Sets the radio TX power used on the controller for Atheros/RaLink cards. Requires a reboot of the controller after change.", 1, pCS->iMaxTXPowerAtheros, pCS->iMaxTXPowerAtheros/2, fSliderWidth); - m_IndexPowerControllerAtheros = addMenuItem(m_pItemsSlider[6]); - m_pItemsSlider[7] = new MenuItemSlider("Controller Tx Power (5.8Ghz)", "Sets the radio TX power used on the controller for RTL cards. Requires a reboot of the controller after change.", 1, pCS->iMaxTXPowerRTL, pCS->iMaxTXPowerRTL/2, fSliderWidth); - m_IndexPowerControllerRTL = addMenuItem(m_pItemsSlider[7]); - } - } - m_IndexPowerMax = addMenuItem(new MenuItem("Limit Maximum Radio Power Levels")); - m_pMenuItems[m_IndexPowerMax]->showArrow(); - - m_pItemsSelect[0] = new MenuItemSelect("Show All Card Types", "Shows all card types in the table below, not just the ones detected as present."); - m_pItemsSelect[0]->addSelection("No"); - m_pItemsSelect[0]->addSelection("Yes"); - m_pItemsSelect[0]->setIsEditable(); - m_IndexShowAllCards = addMenuItem(m_pItemsSelect[0]); - - m_pItemsSelect[1] = new MenuItemSelect("Show 2W/4W Boosters", "Shows the power output for current radio interfaces when connected to 2W or 4W power boosters."); - m_pItemsSelect[1]->addSelection("No"); - m_pItemsSelect[1]->addSelection("Yes"); - m_pItemsSelect[1]->setIsEditable(); - m_IndexShowBoosters = addMenuItem(m_pItemsSelect[1]); - - - addMenuItem( new MenuItemText("Here is a table with aproximative ouput power levels for different cards:")); - - bool bFirstShow = m_bFirstShow; - Menu::onShow(); - - if ( bFirstShow && m_bSelectSecond ) - m_SelectedIndex = 1; -} - -void MenuTXInfo::valuesToUI() -{ - ControllerSettings* pCS = get_ControllerSettings(); - Preferences* pP = get_Preferences(); - - m_pItemsSelect[0]->setSelectedIndex(1 - pP->iShowOnlyPresentTxPowerCards); - m_pItemsSelect[1]->setSelectedIndex(pP->iShowTxBoosters); - - if ( m_bShowController ) - { - if ( -1 != m_IndexPowerController ) - { - if ( m_bControllerHas24Cards ) - m_pItemsSlider[5]->setCurrentValue(pCS->iTXPowerAtheros); - if ( m_bControllerHas58Cards ) - m_pItemsSlider[5]->setCurrentValue(pCS->iTXPowerRTL); - } - if ( -1 != m_IndexPowerControllerAtheros && m_bControllerHas24Cards ) - m_pItemsSlider[6]->setCurrentValue(pCS->iTXPowerAtheros); - if ( -1 != m_IndexPowerControllerRTL && m_bControllerHas58Cards ) - m_pItemsSlider[7]->setCurrentValue(pCS->iTXPowerRTL); - } - - if ( (NULL == g_pCurrentModel) || (!m_bShowVehicle) ) - return; - - if ( -1 != m_IndexPowerVehicle ) - { - if ( m_bVehicleHas24Cards ) - m_pItemsSlider[0]->setCurrentValue(g_pCurrentModel->radioInterfacesParams.txPowerAtheros); - if ( m_bVehicleHas58Cards ) - m_pItemsSlider[0]->setCurrentValue(g_pCurrentModel->radioInterfacesParams.txPowerRTL); - } - if ( -1 != m_IndexPowerVehicleAtheros && m_bVehicleHas24Cards ) - m_pItemsSlider[1]->setCurrentValue(g_pCurrentModel->radioInterfacesParams.txPowerAtheros); - if ( -1 != m_IndexPowerVehicleRTL && m_bVehicleHas58Cards ) - m_pItemsSlider[2]->setCurrentValue(g_pCurrentModel->radioInterfacesParams.txPowerRTL); -} - - -void MenuTXInfo::RenderTableLine(int iCardModel, const char* szText, const int* piValues, bool bIsHeader, bool bIsBoosterLine) -{ - Preferences* pP = get_Preferences(); - - float height_text = g_pRenderEngine->textHeight(g_idFontMenuSmall); - float x = m_RenderXPos + m_sfMenuPaddingX; - float y = m_yTemp; - float hItem = (1.0 + MENU_ITEM_SPACING) * g_pRenderEngine->textHeight(g_idFontMenuSmall); - - bool bIsPresentOnVehicle = false; - bool bIsPresentOnController = false; - - if ( 0 != iCardModel ) - { - if ( m_bShowVehicle && (NULL != g_pCurrentModel) ) - { - for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) - { - if ( g_pCurrentModel->radioInterfacesParams.interface_card_model[i] == iCardModel ) - bIsPresentOnVehicle = true; - if ( g_pCurrentModel->radioInterfacesParams.interface_card_model[i] == -iCardModel ) - bIsPresentOnVehicle = true; - } - } - - if ( m_bShowController ) - { - for( int n=0; nszMAC); - if ( NULL == pCardInfo ) - continue; - if ( iCardModel == pCardInfo->cardModel ) - bIsPresentOnController = true; - if ( iCardModel == -(pCardInfo->cardModel) ) - bIsPresentOnController = true; - } - } - } - - if ( (!bIsHeader) && pP->iShowOnlyPresentTxPowerCards ) - { - if ( m_bShowVehicle && (! bIsPresentOnVehicle) ) - return; - if ( m_bShowController && (! bIsPresentOnController) ) - return; - } - - if ( 0 != iCardModel ) - if ( (!bIsHeader) && (! pP->iShowOnlyPresentTxPowerCards) ) - if ( bIsPresentOnController || bIsPresentOnVehicle ) - { - //g_pRenderEngine->setColors(get_Color_MenuText(), 0.2); - //g_pRenderEngine->setFill(250,200,50,0.1); - double pColor[4]; - memcpy(pColor,get_Color_MenuBgTooltip(), 4*sizeof(double)); - pColor[0] -= 20; - pColor[1] -= 20; - pColor[2] -= 20; - g_pRenderEngine->setFill(pColor); - g_pRenderEngine->setStroke(get_Color_MenuBorder()); - g_pRenderEngine->setStrokeSize(1); - - float h = hItem + 0.4 * m_sfMenuPaddingY; - if ( pP->iShowTxBoosters ) - if ( ! bIsBoosterLine ) - if ( bIsPresentOnController || bIsPresentOnVehicle ) - h += hItem; - g_pRenderEngine->drawRoundRect(x - m_sfMenuPaddingX*0.4, y - m_sfMenuPaddingY*0.2, m_RenderWidth - 2.0*m_sfMenuPaddingX + 0.8 * m_sfMenuPaddingX, h, MENU_ROUND_MARGIN * m_sfMenuPaddingY); - - g_pRenderEngine->setColors(get_Color_MenuText()); - //g_pRenderEngine->setStroke(get_Color_MenuBorder()); - g_pRenderEngine->setStrokeSize(0); - } - - g_pRenderEngine->drawText(x, y, g_idFontMenuSmall, const_cast(szText)); - - x = m_xTable; - if ( bIsHeader ) - x += 0.008*m_sfScaleFactor; - - char szLevel[128]; - char szValue[32]; - float yTop = m_yTemp - height_text*2.0; - float yBottom = m_yPos+m_RenderHeight - 3.0*m_sfMenuPaddingY - 1.2*height_text; - for( int i=0; i= 1000000 ) - sprintf(szValue, " !!!"); - else if ( piValues[i] < 1000 ) - sprintf(szValue, "%d mW", piValues[i]); - else - sprintf(szValue, "%.1f W", ((float)piValues[i])/1000.0); - g_pRenderEngine->drawText(x, y, g_idFontMenuSmall, szValue); - x += m_xTableCellWidth; - - if ( bIsHeader ) - if ( i == 2 || i == 5 || i == 7 || i == 10 ) - { - g_pRenderEngine->setColors(get_Color_MenuText(), 0.5); - g_pRenderEngine->setStrokeSize(1); - g_pRenderEngine->drawLine(x-0.018*m_sfScaleFactor, yTop+0.02*m_sfScaleFactor, x-0.018*m_sfScaleFactor, yBottom); - g_pRenderEngine->setColors(get_Color_MenuText()); - g_pRenderEngine->setStroke(get_Color_MenuBorder()); - g_pRenderEngine->setStrokeSize(0); - } - - if ( bIsHeader ) - { - szLevel[0] = 0; - if ( i == 2 ) - strcpy(szLevel, "Low Power"); - if ( i == 5 ) - strcpy(szLevel, "Normal Power"); - if ( i == 7 ) - strcpy(szLevel, "Max Power"); - if ( i == 10 ) - strcpy(szLevel, "Experimental"); - if ( 0 != szLevel[0] ) - g_pRenderEngine->drawTextLeft( x-0.026*m_sfScaleFactor, yTop+0.015*m_sfScaleFactor, g_idFontMenuSmall, szLevel); - } - } - - m_yTemp += hItem; - if ( bIsHeader ) - { - g_pRenderEngine->setColors(get_Color_MenuText(), 0.7); - g_pRenderEngine->setStrokeSize(1); - g_pRenderEngine->drawLine(m_xPos + 1.1*m_sfMenuPaddingX,m_yTemp-0.005*m_sfScaleFactor, m_xPos - 1.1*m_sfMenuPaddingX+m_RenderWidth, m_yTemp-0.005*m_sfScaleFactor); - g_pRenderEngine->setColors(get_Color_MenuText()); - g_pRenderEngine->setStroke(get_Color_MenuBorder()); - g_pRenderEngine->setStrokeSize(0); - m_yTemp += MENU_TEXTLINE_SPACING * g_pRenderEngine->textHeight(g_idFontMenuSmall); - } - - if ( m_bShowThinLine ) - { - g_pRenderEngine->setColors(get_Color_MenuText(), 0.5); - g_pRenderEngine->setStrokeSize(1); - float yLine = y-0.005*m_sfScaleFactor; - g_pRenderEngine->drawLine(m_xPos + 1.1*m_sfMenuPaddingX, yLine, m_xPos - 1.1*m_sfMenuPaddingX+m_RenderWidth, yLine); - g_pRenderEngine->setColors(get_Color_MenuText()); - g_pRenderEngine->setStroke(get_Color_MenuBorder()); - g_pRenderEngine->setStrokeSize(0); - } - m_bShowThinLine = false; - m_iLine++; - - if ( ! bIsHeader ) - if ( ! bIsBoosterLine ) - if ( pP->iShowTxBoosters ) - if ( bIsPresentOnController || bIsPresentOnVehicle ) - { - int iTotalPowerValues[TX_POWER_TABLE_COLUMNS]; - for( int i=0; i 100 ) - iTotalPowerValues[i] = 1000000; - else for( int k=0; k<(int)(sizeof(s_iTxBoosterGainTable4W)/sizeof(s_iTxBoosterGainTable4W[0][0])/2)-1; k++ ) - { - if ( piValues[i] >= s_iTxBoosterGainTable4W[k][0] ) - if ( piValues[i] <= s_iTxBoosterGainTable4W[k+1][0] ) - { - iTotalPowerValues[i] = s_iTxBoosterGainTable4W[k][1] + (s_iTxBoosterGainTable4W[k+1][1] - s_iTxBoosterGainTable4W[k][1]) * (float)((float)(piValues[i] - s_iTxBoosterGainTable4W[k][0])/(float)(s_iTxBoosterGainTable4W[k+1][0] - s_iTxBoosterGainTable4W[k][0])); - break; - } - } - } - RenderTableLine(iCardModel, " + 4W booster", iTotalPowerValues, false, true); - } -} - -void MenuTXInfo::drawPowerLine(const char* szText, float yPos, int value) -{ - float height_text = g_pRenderEngine->textHeight(g_idFontMenuSmall); - float xPos = m_RenderXPos + m_sfMenuPaddingX; - char szBuff[64]; - - g_pRenderEngine->drawText( xPos, yPos, g_idFontMenuSmall, szText); - - float x = m_xTable; - float xEnd = x; - for( int i=0; isetColors(get_Color_MenuText(), 0.7); - g_pRenderEngine->setStrokeSize(1); - g_pRenderEngine->drawLine(x, yPos+0.6*height_text, x+width,yPos+0.6*height_text); - xEnd = x+width; - g_pRenderEngine->setColors(get_Color_MenuText()); - x += m_xTableCellWidth; - } - - sprintf(szBuff, "%d", value); - if ( value <= 0 ) - sprintf(szBuff, "N/A"); - g_pRenderEngine->drawText( xEnd+0.2*height_text, yPos, g_idFontMenuSmall, szBuff); -} - - -void MenuTXInfo::Render() -{ - Preferences* pP = get_Preferences(); - RenderPrepare(); - float height_text = g_pRenderEngine->textHeight(g_idFontMenuSmall); - - float yTop = RenderFrameAndTitle(); - float y = yTop; - - m_xTable = m_RenderXPos + m_sfMenuPaddingX; - m_xTable += 0.15*m_sfScaleFactor; - m_xTableCellWidth = 0.05*m_sfScaleFactor; - - for( int i=0; i<=m_IndexPowerMax+2; i++ ) - y += RenderItem(i,y); - - y += 1.0*height_text; - - m_yTopRender = y + 0.01*m_sfScaleFactor; - m_yTemp = y+0.01*m_sfScaleFactor + 1.0*height_text; - if ( m_bShowVehicle || m_bShowController ) - m_yTemp += 1.3 * height_text; - if ( m_bShowController && m_bShowVehicle ) - m_yTemp += 1.3 * height_text; - if ( m_bShowVehicle && m_bShowBothOnVehicle ) - m_yTemp += 1.4*height_text; - if ( m_bShowController && m_bShowBothOnController ) - m_yTemp += 1.4*height_text; - - //nst int infoH[TX_POWER_TABLE_COLUMNS] = { 10, 20, 30, 40, 50, 54, 56, 60, 63, 68, 72}; - - const int info722N[TX_POWER_TABLE_COLUMNS] = { 1, 2, 3, 10, 35, 60, 80, 90, 0, 0, 0}; - const int info722N2W[TX_POWER_TABLE_COLUMNS] = { 6, 20, 70, 205, 650, 900, 1000, 1900, 2000, 2000, 2000}; - const int info722N4W[TX_POWER_TABLE_COLUMNS] = { 10, 60, 200, 450, 1200, 1900, 2100, 2100, 2100, 2100, 2100}; - const int infoBlueStick[TX_POWER_TABLE_COLUMNS] = { 2, 4, 8, 28, 80, 110, 280, 1000, 0, 0, 0}; - //nst int infoGreenStick[TX_POWER_TABLE_COLUMNS] = { 2, 5, 5, 60, 75, 75, 0, 0, 0, 0, 0}; - const int infoAWUS036NH[TX_POWER_TABLE_COLUMNS] = { 10, 20, 30, 40, 60, 0, 0, 0, 0, 0, 0}; - const int infoAWUS036NHA[TX_POWER_TABLE_COLUMNS] = { 1, 2, 6, 17, 120, 180, 215, 310, 460, 0, 0}; - - //const int infoH[TX_POWER_TABLE_COLUMNS] = { 10, 20, 30, 40, 50, 54, 56, 60, 63, 68, 72}; - - const int infoGeneric[TX_POWER_TABLE_COLUMNS] = { 1, 2, 3, 10, 35, 60, 80, 90, 0, 0, 0}; - const int infoAWUS036ACH[TX_POWER_TABLE_COLUMNS] = { 2, 5, 20, 50, 160, 250, 300, 420, 500, 0, 0}; - const int infoASUSUSB56[TX_POWER_TABLE_COLUMNS] = { 2, 9, 30, 80, 200, 250, 300, 340, 370, 370, 150}; - const int infoRTLDualAnt[TX_POWER_TABLE_COLUMNS] = { 5, 17, 50, 150, 190, 210, 261, 310, 310, 310, 310}; - const int infoAli1W[TX_POWER_TABLE_COLUMNS] = { 1, 2, 5, 10, 30, 50, 100, 300, 450, 450, 450}; - const int infoA6100[TX_POWER_TABLE_COLUMNS] = { 1, 3, 9, 17, 30, 30, 35, 40, 0, 0, 0}; - const int infoAWUS036ACS[TX_POWER_TABLE_COLUMNS] = { 1, 2, 3, 10, 35, 50, 60, 90, 110, 0, 0}; - const int infoArcherT2UP[TX_POWER_TABLE_COLUMNS] = { 3, 10, 25, 55, 110, 120, 140, 150, 0, 0, 0}; - - RenderTableLine(0, "Card / Power Level", s_iTxPowerLevelValues, true, false); - - m_yTemp += 0.3 * height_text; - if ( pP->iShowOnlyPresentTxPowerCards ) - m_yTemp += height_text; - - m_iLine = 0; - - if ( m_bDisplay24Cards ) - { - RenderTableLine(CARD_MODEL_TPLINK722N, "TPLink WN722N", info722N, false, false); - RenderTableLine(CARD_MODEL_TPLINK722N, "WN722N + 2W Booster", info722N2W, false, false); - RenderTableLine(CARD_MODEL_TPLINK722N, "WN722N + 4W Booster", info722N4W, false, false); - RenderTableLine(CARD_MODEL_BLUE_STICK, "Blue Stick 2.4Ghz AR9271", infoBlueStick, false, false); - //RenderTableLine(CARD_MODEL_TPLINK722N, "Green Stick 2.4Ghz AR9271", infoGreenStick, false, false); - RenderTableLine(CARD_MODEL_ALFA_AWUS036NH, "Alfa AWUS036NH", infoAWUS036NH, false, false); - RenderTableLine(CARD_MODEL_ALFA_AWUS036NHA, "Alfa AWUS036NHA", infoAWUS036NHA, false, false); - } - if ( m_iLine != 0 ) - if ( m_bDisplay24Cards && m_bDisplay58Cards ) - m_bShowThinLine = true; - - if ( m_bDisplay58Cards ) - { - RenderTableLine(CARD_MODEL_RTL8812AU_DUAL_ANTENNA, "RTLDualAntenna 5.8Ghz", infoRTLDualAnt, false, false); - RenderTableLine(CARD_MODEL_ASUS_AC56, "ASUS AC-56", infoASUSUSB56, false, false); - RenderTableLine(CARD_MODEL_ALFA_AWUS036ACH, "Alfa AWUS036ACH", infoAWUS036ACH, false, false); - RenderTableLine(CARD_MODEL_ALFA_AWUS036ACS, "Alfa AWUS036ACS", infoAWUS036ACS, false, false); - RenderTableLine(CARD_MODEL_ZIPRAY, "1 Watt 5.8Ghz", infoAli1W, false, false); - RenderTableLine(CARD_MODEL_NETGEAR_A6100, "Netgear A6100", infoA6100, false, false); - RenderTableLine(CARD_MODEL_TENDA_U12, "Tenda U12", infoGeneric, false, false); - RenderTableLine(CARD_MODEL_ARCHER_T2UPLUS, "Archer T2U Plus", infoArcherT2UP, false, false); - RenderTableLine(CARD_MODEL_RTL8814AU, "RTL8814AU", infoGeneric, false, false); - } - - height_text = g_pRenderEngine->textHeight(g_idFontMenuSmall); - - if ( (NULL != g_pCurrentModel) && m_bShowVehicle ) - { - if ( m_bShowBothOnVehicle ) - { - drawPowerLine("Vehicle TX Power (2.4 Ghz band):", m_yTopRender, g_pCurrentModel->radioInterfacesParams.txPowerAtheros ); - drawPowerLine("Vehicle TX Power (5.8 Ghz band):", m_yTopRender, g_pCurrentModel->radioInterfacesParams.txPowerRTL ); - } - else - { - if ( m_bVehicleHas24Cards ) - drawPowerLine("Vehicle TX Power:", m_yTopRender, g_pCurrentModel->radioInterfacesParams.txPowerAtheros ); - else - drawPowerLine("Vehicle TX Power:", m_yTopRender, g_pCurrentModel->radioInterfacesParams.txPowerRTL ); - } - m_yTopRender += 1.4*height_text; - } - - ControllerSettings* pCS = get_ControllerSettings(); - - if ( m_bShowController ) - { - if ( m_bShowBothOnController ) - { - drawPowerLine("Controller TX Power (2.4 Ghz band):", m_yTopRender, pCS->iTXPowerAtheros ); - m_yTopRender += 1.4*height_text; - drawPowerLine("Controller TX Power (5.8 Ghz band):", m_yTopRender, pCS->iTXPowerRTL ); - } - else - { - if ( m_bControllerHas24Cards ) - drawPowerLine("Controller TX Power:", m_yTopRender, pCS->iTXPowerAtheros ); - else - drawPowerLine("Controller TX Power:", m_yTopRender, pCS->iTXPowerRTL ); - } - m_yTopRender += 1.4*height_text; - } - - g_pRenderEngine->drawText(m_xPos + Menu::getMenuPaddingX(), m_yPos+m_RenderHeight - 3.0*m_sfMenuPaddingY - height_text, g_idFontMenu, "* Power levels are measured at 5805 Mhz. Lower frequencies do increase the power a little bit."); -} - - -void MenuTXInfo::sendPowerToVehicle(int tx, int txAtheros, int txRTL) -{ - u8 buffer[10]; - memset(&(buffer[0]), 0, 10); - buffer[0] = tx; - buffer[1] = txAtheros; - buffer[2] = txRTL; - buffer[3] = g_pCurrentModel->radioInterfacesParams.txMaxPower; - buffer[4] = g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros; - buffer[5] = g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL; - - if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_TX_POWERS, 0, buffer, 8) ) - valuesToUI(); -} - - -int MenuTXInfo::onBack() -{ - if ( m_bValuesChangedController || m_bValuesChangedController58 ) - { - #if defined(HW_PLATFORM_RADXA_ZERO3) - if ( m_bValuesChangedController58 ) - return Menu::onBack(); - #endif - - MenuConfirmation* pMC = new MenuConfirmation("Restart Required","You need to restart the controller for the power changes to take effect.", 2); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - - if ( (NULL != g_pCurrentModel) && (g_pCurrentModel->rc_params.rc_enabled) ) - { - pMC->addTopLine("Warning! You have RC link enabled. RC link will be lost while the controller restarts."); - } - pMC->addTopLine("Do you want to restart your controller now?"); - add_menu_to_stack(pMC); - return 1; - } - - if ( m_bValuesChangedVehicle ) - if ( (g_pCurrentModel != NULL) && (! g_pCurrentModel->isRunningOnOpenIPCHardware() ) ) - { - char szTextW[256]; - sprintf(szTextW, "You need to restart the %s for the power changes to take effect.", g_pCurrentModel->getVehicleTypeString()); - MenuConfirmation* pMC = new MenuConfirmation("Restart Required", szTextW, 3); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - - if ( (NULL != g_pCurrentModel) && (g_pCurrentModel->rc_params.rc_enabled) ) - { - pMC->addTopLine("Warning! You have RC link enabled. RC link will be lost while the vehicle restarts."); - } - sprintf(szTextW, "Do you want to restart your %s now?", g_pCurrentModel->getVehicleTypeString()); - pMC->addTopLine(szTextW); - add_menu_to_stack(pMC); - return 1; - } - return Menu::onBack(); -} - -void MenuTXInfo::onReturnFromChild(int iChildMenuId, int returnValue) -{ - Menu::onReturnFromChild(iChildMenuId, returnValue); - - if ( 2 == iChildMenuId/1000 ) - { - m_bValuesChangedController = false; - if ( 1 == returnValue ) - { - onEventReboot(); - hardware_reboot(); - return; - } - menu_stack_pop(0); - return; - } - - if ( 3 == iChildMenuId/1000 ) - { - m_bValuesChangedVehicle = false; - if ( 1 == returnValue ) - { - handle_commands_send_to_vehicle(COMMAND_ID_REBOOT, 0, NULL, 0); - valuesToUI(); - menu_discard_all(); - return; - } - return; - } - - valuesToUI(); -} - -void MenuTXInfo::onSelectItem() -{ - Menu::onSelectItem(); - - if ( m_pMenuItems[m_SelectedIndex]->isEditing() ) - return; - - if ( handle_commands_is_command_in_progress() ) - { - handle_commands_show_popup_progress(); - return; - } - - ControllerSettings* pCS = get_ControllerSettings(); - Preferences* pP = get_Preferences(); - - if ( m_IndexShowAllCards == m_SelectedIndex ) - { - pP->iShowOnlyPresentTxPowerCards = 1- m_pItemsSelect[0]->getSelectedIndex(); - save_Preferences(); - valuesToUI(); - invalidate(); - return; - } - - if ( m_IndexShowBoosters == m_SelectedIndex ) - { - pP->iShowTxBoosters = m_pItemsSelect[1]->getSelectedIndex(); - save_Preferences(); - valuesToUI(); - invalidate(); - return; - } - - if ( m_IndexPowerController == m_SelectedIndex ) - { - if ( m_bControllerHas24Cards ) - { - if ( pCS->iTXPowerAtheros != m_pItemsSlider[5]->getCurrentValue() ) - m_bValuesChangedController = true; - pCS->iTXPowerAtheros = m_pItemsSlider[5]->getCurrentValue(); - } - if ( m_bControllerHas58Cards ) - { - if ( pCS->iTXPowerRTL != m_pItemsSlider[5]->getCurrentValue() ) - { - m_bValuesChangedController = true; - m_bValuesChangedController58 = true; - } - pCS->iTXPowerRTL = m_pItemsSlider[5]->getCurrentValue(); - } - if ( m_bControllerHas24Cards ) - { - hardware_set_radio_tx_power_atheros(pCS->iTXPowerAtheros); - } - if ( m_bControllerHas58Cards ) - { - hardware_set_radio_tx_power_rtl(pCS->iTXPowerRTL); - } - save_ControllerSettings(); - - if ( m_pItemsSlider[5]->getCurrentValue() > 59 ) - { - MenuConfirmation* pMC = new MenuConfirmation("High Power Levels","Setting a card to a very high power level can fry it if it does not have proper cooling.", 1, true); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - pMC->addTopLine("Proceed with caution!"); - add_menu_to_stack(pMC); - } - - return; - } - - if ( m_IndexPowerControllerAtheros == m_SelectedIndex ) - { - if ( pCS->iTXPowerAtheros != m_pItemsSlider[6]->getCurrentValue() ) - m_bValuesChangedController = true; - pCS->iTXPowerAtheros = m_pItemsSlider[6]->getCurrentValue(); - hardware_set_radio_tx_power_atheros(pCS->iTXPowerAtheros); - save_ControllerSettings(); - - if ( m_pItemsSlider[6]->getCurrentValue() > 59 ) - { - MenuConfirmation* pMC = new MenuConfirmation("High Power Levels","Setting a card to a very high power level can fry it if it does not have proper cooling.", 1, true); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - pMC->addTopLine("Proceed with caution!"); - add_menu_to_stack(pMC); - } - return; - } - - if ( m_IndexPowerControllerRTL == m_SelectedIndex ) - { - if ( pCS->iTXPowerRTL != m_pItemsSlider[7]->getCurrentValue() ) - { - m_bValuesChangedController = true; - m_bValuesChangedController58 = true; - } - pCS->iTXPowerRTL = m_pItemsSlider[7]->getCurrentValue(); - hardware_set_radio_tx_power_rtl(pCS->iTXPowerRTL); - save_ControllerSettings(); - - if ( m_pItemsSlider[7]->getCurrentValue() > 59 ) - { - MenuConfirmation* pMC = new MenuConfirmation("High Power Levels","Setting a card to a very high power level can fry it if it does not have proper cooling.", 1, true); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - pMC->addTopLine("Proceed with caution!"); - add_menu_to_stack(pMC); - } - - return; - } - - - if ( (m_IndexPowerVehicle == m_SelectedIndex) && menu_check_current_model_ok_for_edit() ) - { - int val = m_pItemsSlider[0]->getCurrentValue(); - int tx = g_pCurrentModel->radioInterfacesParams.txPower; - int txAtheros = g_pCurrentModel->radioInterfacesParams.txPowerAtheros; - int txRTL = g_pCurrentModel->radioInterfacesParams.txPowerRTL; - - if ( m_bVehicleHas24Cards ) - { - if ( val != txAtheros ) - m_bValuesChangedVehicle = true; - txAtheros = val; - } - if ( m_bVehicleHas58Cards ) - { - if ( val != txRTL ) - m_bValuesChangedVehicle = true; - txRTL = val; - } - sendPowerToVehicle(tx, txAtheros, txRTL); - - if ( val > 59 ) - { - MenuConfirmation* pMC = new MenuConfirmation("High Power Levels","Setting a card to a very high power level can fry it if it does not have proper cooling.", 1, true); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - pMC->addTopLine("Proceed with caution!"); - add_menu_to_stack(pMC); - } - - return; - } - if ( (m_IndexPowerVehicleAtheros == m_SelectedIndex) && menu_check_current_model_ok_for_edit() ) - { - int tx = g_pCurrentModel->radioInterfacesParams.txPower; - int txAtheros = m_pItemsSlider[1]->getCurrentValue(); - if ( g_pCurrentModel->radioInterfacesParams.txPowerAtheros != txAtheros ) - m_bValuesChangedVehicle = true; - - int txRTL = g_pCurrentModel->radioInterfacesParams.txPowerRTL; - sendPowerToVehicle(tx, txAtheros, txRTL); - - if ( txAtheros > 59 ) - { - MenuConfirmation* pMC = new MenuConfirmation("High Power Levels","Setting a card to a very high power level can fry it if it does not have proper cooling.", 1, true); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - pMC->addTopLine("Proceed with caution!"); - add_menu_to_stack(pMC); - } - return; - } - - if ( (m_IndexPowerVehicleRTL == m_SelectedIndex) && menu_check_current_model_ok_for_edit() ) - { - int tx = g_pCurrentModel->radioInterfacesParams.txPower; - int txAtheros = g_pCurrentModel->radioInterfacesParams.txPowerAtheros; - int txRTL = m_pItemsSlider[2]->getCurrentValue(); - if ( g_pCurrentModel->radioInterfacesParams.txPowerRTL != txRTL ) - m_bValuesChangedVehicle = true; - sendPowerToVehicle(tx, txAtheros, txRTL); - - if ( txRTL > 59 ) - { - MenuConfirmation* pMC = new MenuConfirmation("High Power Levels","Setting a card to a very high power level can fry it if it does not have proper cooling.", 1, true); - pMC->m_yPos = 0.3; - pMC->addTopLine(""); - pMC->addTopLine("Proceed with caution!"); - add_menu_to_stack(pMC); - } - - return; - } - - if ( m_IndexPowerMax == m_SelectedIndex ) - add_menu_to_stack(new MenuTXPowerMax()); - -} \ No newline at end of file diff --git a/code/r_central/menu/menu_txinfo.h b/code/r_central/menu/menu_txinfo.h deleted file mode 100644 index 103fafad..00000000 --- a/code/r_central/menu/menu_txinfo.h +++ /dev/null @@ -1,60 +0,0 @@ -#pragma once -#include "menu_objects.h" -#include "menu_item_select.h" -#include "menu_item_slider.h" - -class MenuTXInfo: public Menu -{ - public: - MenuTXInfo(); - virtual ~MenuTXInfo(); - virtual void onShow(); - virtual void valuesToUI(); - virtual int onBack(); - virtual void onReturnFromChild(int iChildMenuId, int returnValue); - virtual void Render(); - virtual void onSelectItem(); - - bool m_bSelectSecond; - bool m_bShowController; - bool m_bShowVehicle; - - private: - void RenderTableLine(int iCardModel, const char* szText, const int* piValues, bool bIsHeader, bool bIsBoosterLine); - void drawPowerLine(const char* szText, float yPos, int value); - void sendPowerToVehicle(int tx, int txAtheros, int txRTL); - - float m_yTemp; - float m_yTopRender; - float m_xTable; - float m_xTableCellWidth; - int m_iLine; - - MenuItemSlider* m_pItemsSlider[10]; - MenuItemSelect* m_pItemsSelect[10]; - - bool m_bShowThinLine; - bool m_bShowBothOnController; - bool m_bShowBothOnVehicle; - bool m_bDisplay24Cards; - bool m_bDisplay58Cards; - - bool m_bControllerHas24Cards; - bool m_bControllerHas58Cards; - bool m_bVehicleHas24Cards; - bool m_bVehicleHas58Cards; - - int m_IndexPowerVehicle; - int m_IndexPowerVehicleAtheros; - int m_IndexPowerVehicleRTL; - int m_IndexPowerController; - int m_IndexPowerControllerAtheros; - int m_IndexPowerControllerRTL; - int m_IndexPowerMax; - int m_IndexShowAllCards; - int m_IndexShowBoosters; - - bool m_bValuesChangedVehicle; - bool m_bValuesChangedController; - bool m_bValuesChangedController58; -}; \ No newline at end of file diff --git a/code/r_central/menu/menu_update_vehicle.cpp b/code/r_central/menu/menu_update_vehicle.cpp index dead1ec4..80e28e6f 100644 --- a/code/r_central/menu/menu_update_vehicle.cpp +++ b/code/r_central/menu/menu_update_vehicle.cpp @@ -51,7 +51,7 @@ MenuUpdateVehiclePopup::MenuUpdateVehiclePopup(int vehicleIndex) addTopLine(szBuff); - if ( get_sw_version_build(g_pCurrentModel) < 242 ) + if ( get_sw_version_build(g_pCurrentModel) < 248 ) addTopLine("Video protocols have changed from the version running on vehicle. It is recommended to update vehicle otherways you will not get a video feed."); sprintf(szBuff, "Do you want to update now?"); addTopLine(szBuff); diff --git a/code/r_central/menu/menu_vehicle_camera.cpp b/code/r_central/menu/menu_vehicle_camera.cpp index f9a0ba54..04e481a6 100644 --- a/code/r_central/menu/menu_vehicle_camera.cpp +++ b/code/r_central/menu/menu_vehicle_camera.cpp @@ -147,6 +147,7 @@ void MenuVehicleCamera::addItems() szCamName = g_pCurrentModel->getCameraName(g_pCurrentModel->iCurrentCamera); if ( (NULL != szCamName) && (0 != szCamName[0]) ) + if ( NULL == strstr(szCam, szCamName) ) { strcat(szCam, " ("); strcat(szCam, szCamName); @@ -160,14 +161,14 @@ void MenuVehicleCamera::addItems() m_pItemsSelect[12] = new MenuItemSelect("Camera Type", "Autodetect the active camera type or force a particular camera type for the active camera."); m_pItemsSelect[12]->addSelection("Autodetect"); - m_pItemsSelect[12]->addSelection("CSI Camera"); - m_pItemsSelect[12]->addSelection("HDMI Camera"); - m_pItemsSelect[12]->addSelection("Veye 290"); - m_pItemsSelect[12]->addSelection("Veye 307"); - m_pItemsSelect[12]->addSelection("Veye 327"); - m_pItemsSelect[12]->addSelection("OpenIPC IMX307"); - m_pItemsSelect[12]->addSelection("OpenIPC IMX335"); - m_pItemsSelect[12]->addSelection("OpenIPC IMX415"); + m_pItemsSelect[12]->addSelection("CSI Camera", !g_pCurrentModel->isRunningOnOpenIPCHardware()); + m_pItemsSelect[12]->addSelection("HDMI Camera", !g_pCurrentModel->isRunningOnOpenIPCHardware()); + m_pItemsSelect[12]->addSelection("Veye 290", !g_pCurrentModel->isRunningOnOpenIPCHardware()); + m_pItemsSelect[12]->addSelection("Veye 307", !g_pCurrentModel->isRunningOnOpenIPCHardware()); + m_pItemsSelect[12]->addSelection("Veye 327", !g_pCurrentModel->isRunningOnOpenIPCHardware()); + m_pItemsSelect[12]->addSelection("OpenIPC IMX307", g_pCurrentModel->isRunningOnOpenIPCHardware()); + m_pItemsSelect[12]->addSelection("OpenIPC IMX335", g_pCurrentModel->isRunningOnOpenIPCHardware()); + m_pItemsSelect[12]->addSelection("OpenIPC IMX415", g_pCurrentModel->isRunningOnOpenIPCHardware()); m_pItemsSelect[12]->addSelection("USB Camera", false); m_pItemsSelect[12]->addSelection("IP Camera", false); m_pItemsSelect[12]->setIsEditable(); diff --git a/code/r_central/menu/menu_vehicle_data_link.cpp b/code/r_central/menu/menu_vehicle_data_link.cpp index 1f2173cb..fd213fd9 100644 --- a/code/r_central/menu/menu_vehicle_data_link.cpp +++ b/code/r_central/menu/menu_vehicle_data_link.cpp @@ -49,8 +49,8 @@ MenuVehicleDataLink::MenuVehicleDataLink(void) m_pItemsSelect[0] = new MenuItemSelect("Vehicle Serial Port", "The vehicle serial port to use for the auxiliary data link."); m_pItemsSelect[0]->addSelection("None"); - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) - m_pItemsSelect[0]->addSelection(g_pCurrentModel->hardwareInterfacesInfo.serial_bus_names[i]); + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) + m_pItemsSelect[0]->addSelection(g_pCurrentModel->hardwareInterfacesInfo.serial_port_names[i]); m_pItemsSelect[0]->setIsEditable(); m_IndexPort = addMenuItem(m_pItemsSelect[0]); @@ -76,14 +76,14 @@ void MenuVehicleDataLink::valuesToUI() { int iCurrentSerialPortIndex = -1; u32 uCurrentSerialPortSpeed = 0; - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) { - if ( g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) - if ( (g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF) == SERIAL_PORT_USAGE_DATA_LINK ) + if ( g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) + if ( (g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF) == SERIAL_PORT_USAGE_DATA_LINK ) { iCurrentSerialPortIndex = i; - uCurrentSerialPortSpeed = g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[i]; + uCurrentSerialPortSpeed = g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[i]; break; } } @@ -141,11 +141,11 @@ void MenuVehicleDataLink::onSelectItem() int iCurrentSerialPortIndex = -1; - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) { - if ( g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) - if ( (g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF) == SERIAL_PORT_USAGE_DATA_LINK ) + if ( g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) + if ( (g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF) == SERIAL_PORT_USAGE_DATA_LINK ) { iCurrentSerialPortIndex = i; break; @@ -157,7 +157,7 @@ void MenuVehicleDataLink::onSelectItem() { int iSerialPort = m_pItemsSelect[0]->getSelectedIndex(); if ( iSerialPort != 0 ) - if ( (g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[iSerialPort-1] & 0xFF) == SERIAL_PORT_USAGE_SIK_RADIO ) + if ( (g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[iSerialPort-1] & 0xFF) == SERIAL_PORT_USAGE_SIK_RADIO ) { MenuConfirmation* pMC = new MenuConfirmation("Can't use serial port", "The serial port you selected can't be used for a custom data link as it's used for a SiK radio interface.",1, true); pMC->m_yPos = 0.3; @@ -172,8 +172,8 @@ void MenuVehicleDataLink::onSelectItem() { type_vehicle_hardware_interfaces_info new_info; memcpy((u8*)&new_info, (u8*)&(g_pCurrentModel->hardwareInterfacesInfo), sizeof(type_vehicle_hardware_interfaces_info)); - new_info.serial_bus_supported_and_usage[iCurrentSerialPortIndex] &= 0xFFFFFF00; - new_info.serial_bus_supported_and_usage[iCurrentSerialPortIndex] |= SERIAL_PORT_USAGE_NONE; + new_info.serial_port_supported_and_usage[iCurrentSerialPortIndex] &= 0xFFFFFF00; + new_info.serial_port_supported_and_usage[iCurrentSerialPortIndex] |= SERIAL_PORT_USAGE_NONE; log_line("Sending disabling data link serial port selection to vehicle."); if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_SERIAL_PORTS_INFO, 0, (u8*)&new_info, sizeof(type_vehicle_hardware_interfaces_info)) ) @@ -187,7 +187,7 @@ void MenuVehicleDataLink::onSelectItem() type_vehicle_hardware_interfaces_info new_info; memcpy((u8*)&new_info, (u8*)&(g_pCurrentModel->hardwareInterfacesInfo), sizeof(type_vehicle_hardware_interfaces_info)); - u8 uCurrentUsage = new_info.serial_bus_supported_and_usage[iSerialPort-1] & 0xFF; + u8 uCurrentUsage = new_info.serial_port_supported_and_usage[iSerialPort-1] & 0xFF; if ( uCurrentUsage != SERIAL_PORT_USAGE_DATA_LINK ) { if ( (uCurrentUsage == SERIAL_PORT_USAGE_TELEMETRY_MAVLINK) || (uCurrentUsage == SERIAL_PORT_USAGE_MSP_OSD) ) @@ -200,11 +200,11 @@ void MenuVehicleDataLink::onSelectItem() if ( iCurrentSerialPortIndex != -1 ) { - new_info.serial_bus_supported_and_usage[iCurrentSerialPortIndex] &= 0xFFFFFF00; - new_info.serial_bus_supported_and_usage[iCurrentSerialPortIndex] |= SERIAL_PORT_USAGE_NONE; + new_info.serial_port_supported_and_usage[iCurrentSerialPortIndex] &= 0xFFFFFF00; + new_info.serial_port_supported_and_usage[iCurrentSerialPortIndex] |= SERIAL_PORT_USAGE_NONE; } - new_info.serial_bus_supported_and_usage[iSerialPort-1] &= 0xFFFFFF00; - new_info.serial_bus_supported_and_usage[iSerialPort-1] |= SERIAL_PORT_USAGE_DATA_LINK; + new_info.serial_port_supported_and_usage[iSerialPort-1] &= 0xFFFFFF00; + new_info.serial_port_supported_and_usage[iSerialPort-1] |= SERIAL_PORT_USAGE_DATA_LINK; log_line("Sending new serial port to be used for data link to vehicle."); if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_SERIAL_PORTS_INFO, 0, (u8*)&new_info, sizeof(type_vehicle_hardware_interfaces_info)) ) @@ -219,12 +219,12 @@ void MenuVehicleDataLink::onSelectItem() return; long val = hardware_get_serial_baud_rates()[m_pItemsSelect[1]->getSelectedIndex()]; - if ( val == g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[iCurrentSerialPortIndex] ) + if ( val == g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[iCurrentSerialPortIndex] ) return; type_vehicle_hardware_interfaces_info new_info; memcpy((u8*)&new_info, (u8*)&(g_pCurrentModel->hardwareInterfacesInfo), sizeof(type_vehicle_hardware_interfaces_info)); - new_info.serial_bus_speed[iCurrentSerialPortIndex] = (u32)val; + new_info.serial_port_speed[iCurrentSerialPortIndex] = (u32)val; log_line("Sending new serial port speed for data link to vehicle."); if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_SERIAL_PORTS_INFO, 0, (u8*)&new_info, sizeof(type_vehicle_hardware_interfaces_info)) ) valuesToUI(); diff --git a/code/r_central/menu/menu_vehicle_osd_stats.cpp b/code/r_central/menu/menu_vehicle_osd_stats.cpp index 71f71f27..4980f7b5 100644 --- a/code/r_central/menu/menu_vehicle_osd_stats.cpp +++ b/code/r_central/menu/menu_vehicle_osd_stats.cpp @@ -60,6 +60,7 @@ MenuVehicleOSDStats::MenuVehicleOSDStats(void) m_IndexDevStatsVehicleVideo = -1; m_IndexDevStatsVehicleVideoGraphs = -1; m_IndexSnapshot = -1; + m_IndexStatsVideoH264FramesInfo = -1; m_pItemsSelect[0] = new MenuItemSelect("Font Size", "Increase/decrease OSD font size for stats windows for current OSD screen."); m_pItemsSelect[0]->addSelection("Smallest"); @@ -119,12 +120,12 @@ MenuVehicleOSDStats::MenuVehicleOSDStats(void) m_pItemsSelect[8] = new MenuItemSelect(" Graphs Resolution", "The resolution of the graphs, in miliseconds / bar."); - m_pItemsSelect[8]->addSelection("500 ms/bar"); - m_pItemsSelect[8]->addSelection("200 ms/bar"); - m_pItemsSelect[8]->addSelection("100 ms/bar"); - m_pItemsSelect[8]->addSelection("50 ms/bar"); - m_pItemsSelect[8]->addSelection("20 ms/bar"); m_pItemsSelect[8]->addSelection("10 ms/bar"); + m_pItemsSelect[8]->addSelection("20 ms/bar"); + m_pItemsSelect[8]->addSelection("50 ms/bar"); + m_pItemsSelect[8]->addSelection("100 ms/bar"); + m_pItemsSelect[8]->addSelection("200 ms/bar"); + m_pItemsSelect[8]->addSelection("500 ms/bar"); m_pItemsSelect[8]->setIsEditable(); m_IndexRadioRefreshInterval = addMenuItem(m_pItemsSelect[8]); @@ -222,20 +223,21 @@ MenuVehicleOSDStats::MenuVehicleOSDStats(void) m_IndexStatsVideoExtended = addMenuItem(m_pItemsSelect[4]); m_pItemsSelect[9] = new MenuItemSelect(" Graphs Resolution", "The resolution of the graphs, in miliseconds / bar."); - m_pItemsSelect[9]->addSelection("500 ms/bar"); - m_pItemsSelect[9]->addSelection("200 ms/bar"); - m_pItemsSelect[9]->addSelection("100 ms/bar"); - m_pItemsSelect[9]->addSelection("50 ms/bar"); - m_pItemsSelect[9]->addSelection("20 ms/bar"); m_pItemsSelect[9]->addSelection("10 ms/bar"); + m_pItemsSelect[9]->addSelection("20 ms/bar"); + m_pItemsSelect[9]->addSelection("50 ms/bar"); + m_pItemsSelect[9]->addSelection("100 ms/bar"); + //m_pItemsSelect[9]->addSelection("200 ms/bar"); + //m_pItemsSelect[9]->addSelection("500 ms/bar"); m_pItemsSelect[9]->setIsEditable(); m_IndexVideoRefreshInterval = addMenuItem(m_pItemsSelect[9]); - m_pItemsSelect[16] = new MenuItemSelect(" Adaptive video graph", "Shows a live graph of adaptive video link changes."); - m_pItemsSelect[16]->addSelection("Off"); - m_pItemsSelect[16]->addSelection("On"); - m_pItemsSelect[16]->setUseMultiViewLayout(); - m_IndexStatsAdaptiveVideoGraph = addMenuItem(m_pItemsSelect[16]); + //m_pItemsSelect[16] = new MenuItemSelect(" Adaptive video graph", "Shows a live graph of adaptive video link changes."); + //m_pItemsSelect[16]->addSelection("Off"); + //m_pItemsSelect[16]->addSelection("On"); + //m_pItemsSelect[16]->setUseMultiViewLayout(); + //m_IndexStatsAdaptiveVideoGraph = addMenuItem(m_pItemsSelect[16]); + m_IndexStatsAdaptiveVideoGraph = -1; if ( pCS->iDeveloperMode ) { @@ -274,16 +276,15 @@ MenuVehicleOSDStats::MenuVehicleOSDStats(void) m_pItemsSelect[33]->setIsEditable(); m_IndexRefreshIntervalVideoBitrateHistory = addMenuItem(m_pItemsSelect[33]); - m_pItemsSelect[23] = new MenuItemSelect("Video: Keyframe Stats", "Show statistics about the video stream keyframe intervals and auto adjustments."); - m_pItemsSelect[23]->addSelection("Off"); - m_pItemsSelect[23]->addSelection("Minimal"); - m_pItemsSelect[23]->addSelection("Compact"); - m_pItemsSelect[23]->addSelection("Full"); - m_pItemsSelect[23]->setIsEditable(); - m_IndexStatsVideoStreamKeyFramesInfo = addMenuItem(m_pItemsSelect[23]); - if ( pCS->iDeveloperMode ) { + m_pItemsSelect[23] = new MenuItemSelect("Video: H264/H265 Frame Stats", "Show statistics about the video stream H264/H65 frames and auto adjustments."); + m_pItemsSelect[23]->addSelection("Off"); + m_pItemsSelect[23]->addSelection("On"); + m_pItemsSelect[23]->setUseMultiViewLayout(); + m_pItemsSelect[23]->setTextColor(get_Color_Dev()); + m_IndexStatsVideoH264FramesInfo = addMenuItem(m_pItemsSelect[23]); + m_pItemsSelect[10] = new MenuItemSelect("Video: Retransmissions Stats", "Shows the extended developer video retransmissions stats."); m_pItemsSelect[10]->addSelection("Off"); m_pItemsSelect[10]->addSelection("On"); @@ -376,28 +377,28 @@ void MenuVehicleOSDStats::valuesToUI() else m_pItemsSelect[2]->setSelection(3); - if ( pCS->nGraphRadioRefreshInterval > 200 ) + if ( pCS->nGraphRadioRefreshInterval <= 10 ) m_pItemsSelect[8]->setSelection(0); - else if ( pCS->nGraphRadioRefreshInterval > 100 ) + else if ( pCS->nGraphRadioRefreshInterval <= 20 ) m_pItemsSelect[8]->setSelection(1); - else if ( pCS->nGraphRadioRefreshInterval > 50 ) + else if ( pCS->nGraphRadioRefreshInterval <= 50 ) m_pItemsSelect[8]->setSelection(2); - else if ( pCS->nGraphRadioRefreshInterval > 20 ) + else if ( pCS->nGraphRadioRefreshInterval <= 100 ) m_pItemsSelect[8]->setSelection(3); - else if ( pCS->nGraphRadioRefreshInterval > 10 ) + else if ( pCS->nGraphRadioRefreshInterval <= 200 ) m_pItemsSelect[8]->setSelection(4); else m_pItemsSelect[8]->setSelection(5); - if ( pCS->nGraphVideoRefreshInterval > 200 ) + if ( pCS->nGraphVideoRefreshInterval <= 10 ) m_pItemsSelect[9]->setSelection(0); - else if ( pCS->nGraphVideoRefreshInterval > 100 ) + else if ( pCS->nGraphVideoRefreshInterval <= 20 ) m_pItemsSelect[9]->setSelection(1); - else if ( pCS->nGraphVideoRefreshInterval > 50 ) + else if ( pCS->nGraphVideoRefreshInterval <= 50 ) m_pItemsSelect[9]->setSelection(2); - else if ( pCS->nGraphVideoRefreshInterval > 20 ) + else if ( pCS->nGraphVideoRefreshInterval <= 100 ) m_pItemsSelect[9]->setSelection(3); - else if ( pCS->nGraphVideoRefreshInterval > 10 ) + else if ( pCS->nGraphVideoRefreshInterval <= 200 ) m_pItemsSelect[9]->setSelection(4); else m_pItemsSelect[9]->setSelection(5); @@ -462,23 +463,27 @@ void MenuVehicleOSDStats::valuesToUI() m_pItemsSelect[26]->setSelectedIndex((g_pCurrentModel->osd_params.osd_flags3[layoutIndex] & OSD_FLAG3_SHOW_AUDIO_DECODE_STATS)?1:0); m_pItemsSelect[17]->setSelectedIndex((g_pCurrentModel->osd_params.osd_flags2[layoutIndex] & OSD_FLAG2_SHOW_VEHICLE_RADIO_INTERFACES_STATS)?1:0); - if ( g_pCurrentModel->osd_params.osd_flags[layoutIndex] & OSD_FLAG_SHOW_STATS_VIDEO_KEYFRAMES_INFO ) + if ( -1 != m_IndexStatsVideoH264FramesInfo ) { - if ( 0 == pCS->iShowVideoStreamInfoCompactType ) - m_pItemsSelect[23]->setSelectedIndex(3); - else if ( 1 == pCS->iShowVideoStreamInfoCompactType ) - m_pItemsSelect[23]->setSelectedIndex(2); + if ( g_pCurrentModel->osd_params.osd_flags[layoutIndex] & OSD_FLAG_SHOW_STATS_VIDEO_H264_FRAMES_INFO ) + { + //if ( 0 == pCS->iShowVideoStreamInfoCompactType ) + // m_pItemsSelect[23]->setSelectedIndex(3); + //else if ( 1 == pCS->iShowVideoStreamInfoCompactType ) + // m_pItemsSelect[23]->setSelectedIndex(2); + //else + m_pItemsSelect[23]->setSelectedIndex(1); + } else - m_pItemsSelect[23]->setSelectedIndex(1); + m_pItemsSelect[23]->setSelectedIndex(0); } - else - m_pItemsSelect[23]->setSelectedIndex(0); if ( g_pCurrentModel->osd_params.osd_flags2[layoutIndex] & OSD_FLAG2_SHOW_STATS_VIDEO ) { m_pItemsSelect[4]->setEnabled(true); m_pItemsSelect[9]->setEnabled(true); - m_pItemsSelect[16]->setEnabled(true); + if ( -1 != m_IndexStatsAdaptiveVideoGraph ) + m_pItemsSelect[16]->setEnabled(true); if ( pCS->iDeveloperMode ) { if ( -1 != m_IndexSnapshot ) @@ -491,7 +496,8 @@ void MenuVehicleOSDStats::valuesToUI() { m_pItemsSelect[4]->setEnabled(false); m_pItemsSelect[9]->setEnabled(false); - m_pItemsSelect[16]->setEnabled(false); + if ( -1 != m_IndexStatsAdaptiveVideoGraph ) + m_pItemsSelect[16]->setEnabled(false); //if ( pCS->iDeveloperMode ) { if ( -1 != m_IndexSnapshot ) @@ -510,7 +516,8 @@ void MenuVehicleOSDStats::valuesToUI() if ( g_pCurrentModel->osd_params.osd_flags[layoutIndex] & OSD_FLAG_EXTENDED_VIDEO_DECODE_STATS ) m_pItemsSelect[4]->setSelectedIndex(3); - m_pItemsSelect[16]->setSelection((g_pCurrentModel->osd_params.osd_flags2[layoutIndex] & OSD_FLAG2_SHOW_ADAPTIVE_VIDEO_GRAPH)?1:0); + if ( -1 != m_IndexStatsAdaptiveVideoGraph ) + m_pItemsSelect[16]->setSelection((g_pCurrentModel->osd_params.osd_flags2[layoutIndex] & OSD_FLAG2_SHOW_ADAPTIVE_VIDEO_GRAPH)?1:0); m_pItemsSelect[5]->setSelection((g_pCurrentModel->osd_params.osd_flags[layoutIndex] & OSD_FLAG_SHOW_EFFICIENCY_STATS)?1:0); m_pItemsSelect[6]->setSelection((g_pCurrentModel->osd_params.osd_flags2[layoutIndex] & OSD_FLAG2_SHOW_STATS_RC)?1:0); @@ -699,17 +706,17 @@ void MenuVehicleOSDStats::onSelectItem() if ( m_IndexRadioRefreshInterval == m_SelectedIndex ) { if ( 0 == m_pItemsSelect[8]->getSelectedIndex() ) - pCS->nGraphRadioRefreshInterval = 500; + pCS->nGraphRadioRefreshInterval = 10; if ( 1 == m_pItemsSelect[8]->getSelectedIndex() ) - pCS->nGraphRadioRefreshInterval = 200; + pCS->nGraphRadioRefreshInterval = 20; if ( 2 == m_pItemsSelect[8]->getSelectedIndex() ) - pCS->nGraphRadioRefreshInterval = 100; - if ( 3 == m_pItemsSelect[8]->getSelectedIndex() ) pCS->nGraphRadioRefreshInterval = 50; + if ( 3 == m_pItemsSelect[8]->getSelectedIndex() ) + pCS->nGraphRadioRefreshInterval = 100; if ( 4 == m_pItemsSelect[8]->getSelectedIndex() ) - pCS->nGraphRadioRefreshInterval = 20; + pCS->nGraphRadioRefreshInterval = 200; if ( 5 == m_pItemsSelect[8]->getSelectedIndex() ) - pCS->nGraphRadioRefreshInterval = 10; + pCS->nGraphRadioRefreshInterval = 500; save_ControllerSettings(); invalidate(); valuesToUI(); @@ -778,17 +785,17 @@ void MenuVehicleOSDStats::onSelectItem() if ( m_IndexVideoRefreshInterval == m_SelectedIndex ) { if ( 0 == m_pItemsSelect[9]->getSelectedIndex() ) - pCS->nGraphVideoRefreshInterval = 500; + pCS->nGraphVideoRefreshInterval = 10; if ( 1 == m_pItemsSelect[9]->getSelectedIndex() ) - pCS->nGraphVideoRefreshInterval = 200; + pCS->nGraphVideoRefreshInterval = 20; if ( 2 == m_pItemsSelect[9]->getSelectedIndex() ) - pCS->nGraphVideoRefreshInterval = 100; - if ( 3 == m_pItemsSelect[9]->getSelectedIndex() ) pCS->nGraphVideoRefreshInterval = 50; + if ( 3 == m_pItemsSelect[9]->getSelectedIndex() ) + pCS->nGraphVideoRefreshInterval = 100; if ( 4 == m_pItemsSelect[9]->getSelectedIndex() ) - pCS->nGraphVideoRefreshInterval = 20; + pCS->nGraphVideoRefreshInterval = 200; if ( 5 == m_pItemsSelect[9]->getSelectedIndex() ) - pCS->nGraphVideoRefreshInterval = 10; + pCS->nGraphVideoRefreshInterval = 500; save_ControllerSettings(); invalidate(); valuesToUI(); @@ -819,7 +826,7 @@ void MenuVehicleOSDStats::onSelectItem() sendToVehicle = true; } - if ( m_IndexStatsAdaptiveVideoGraph == m_SelectedIndex ) + if ( (-1 != m_IndexStatsAdaptiveVideoGraph) && (m_IndexStatsAdaptiveVideoGraph == m_SelectedIndex) ) { if ( 0 == m_pItemsSelect[16]->getSelectedIndex() ) params.osd_flags2[layoutIndex] &= ~OSD_FLAG2_SHOW_ADAPTIVE_VIDEO_GRAPH; @@ -828,19 +835,19 @@ void MenuVehicleOSDStats::onSelectItem() sendToVehicle = true; } - if ( m_IndexStatsVideoStreamKeyFramesInfo == m_SelectedIndex ) + if ( (-1 != m_IndexStatsVideoH264FramesInfo) && (m_IndexStatsVideoH264FramesInfo == m_SelectedIndex) ) { if ( 0 == m_pItemsSelect[23]->getSelectedIndex() ) - params.osd_flags[layoutIndex] &= ~OSD_FLAG_SHOW_STATS_VIDEO_KEYFRAMES_INFO; + params.osd_flags[layoutIndex] &= ~OSD_FLAG_SHOW_STATS_VIDEO_H264_FRAMES_INFO; else { - params.osd_flags[layoutIndex] |= OSD_FLAG_SHOW_STATS_VIDEO_KEYFRAMES_INFO; - if ( 3 == m_pItemsSelect[23]->getSelectedIndex() ) - pCS->iShowVideoStreamInfoCompactType = 0; - else if ( 2 == m_pItemsSelect[23]->getSelectedIndex() ) - pCS->iShowVideoStreamInfoCompactType = 1; - else - pCS->iShowVideoStreamInfoCompactType = 2; + params.osd_flags[layoutIndex] |= OSD_FLAG_SHOW_STATS_VIDEO_H264_FRAMES_INFO; + //if ( 3 == m_pItemsSelect[23]->getSelectedIndex() ) + // pCS->iShowVideoStreamInfoCompactType = 0; + //else if ( 2 == m_pItemsSelect[23]->getSelectedIndex() ) + // pCS->iShowVideoStreamInfoCompactType = 1; + //else + // pCS->iShowVideoStreamInfoCompactType = 2; save_ControllerSettings(); } sendToVehicle = true; diff --git a/code/r_central/menu/menu_vehicle_osd_stats.h b/code/r_central/menu/menu_vehicle_osd_stats.h index a119fd4d..7c9cb831 100644 --- a/code/r_central/menu/menu_vehicle_osd_stats.h +++ b/code/r_central/menu/menu_vehicle_osd_stats.h @@ -24,7 +24,7 @@ class MenuVehicleOSDStats: public Menu int m_IndexAudioDecodeStats; int m_IndexVehicleDevStats; int m_IndexRadioRefreshInterval, m_IndexVideoRefreshInterval, m_IndexSnapshot, m_IndexSnapshotTimeout; - int m_IndexStatsVideoStreamKeyFramesInfo, m_IndexRefreshIntervalVideoBitrateHistory; + int m_IndexStatsVideoH264FramesInfo, m_IndexRefreshIntervalVideoBitrateHistory; int m_IndexTelemetryStats; int m_IndexShowControllerAdaptiveInfoStats; int m_IndexStatsVideoExtended, m_IndexStatsAdaptiveVideoGraph, m_IndexStatsEff, m_IndexStatsRC; diff --git a/code/r_central/menu/menu_vehicle_peripherals.cpp b/code/r_central/menu/menu_vehicle_peripherals.cpp index c9aa67a0..e0bf5220 100644 --- a/code/r_central/menu/menu_vehicle_peripherals.cpp +++ b/code/r_central/menu/menu_vehicle_peripherals.cpp @@ -60,15 +60,15 @@ MenuVehiclePeripherals::MenuVehiclePeripherals(void) addMenuItem(new MenuItemSection("Serial Ports")); - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) { if ( i != 0 ) addSeparator(); - u32 uUsage = g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF; - sprintf( szBuff, "%s Usage:", g_pCurrentModel->hardwareInterfacesInfo.serial_bus_names[i] ); + u32 uUsage = g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF; + sprintf( szBuff, "%s Usage:", g_pCurrentModel->hardwareInterfacesInfo.serial_port_names[i] ); m_pItemsSelect[i*2] = new MenuItemSelect(szBuff); - if ( ! (g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED) ) + if ( ! (g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED) ) { m_pItemsSelect[i*2]->addSelection("Not Supported"); m_pItemsSelect[i*2]->setEnabled(false); @@ -108,7 +108,7 @@ MenuVehiclePeripherals::MenuVehiclePeripherals(void) } m_IndexSerialPortsUsage[i] = addMenuItem(m_pItemsSelect[i*2]); - sprintf( szBuff, "%s Baudrate", g_pCurrentModel->hardwareInterfacesInfo.serial_bus_names[i] ); + sprintf( szBuff, "%s Baudrate", g_pCurrentModel->hardwareInterfacesInfo.serial_port_names[i] ); m_pItemsSelect[i*2+1] = new MenuItemSelect(szBuff, "Sets the baud rate of this serial port."); for( int n=0; nhardwareInterfacesInfo.serial_bus_count; i++ ) + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) { - if ( ! (g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED) ) + if ( ! (g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED) ) { m_pItemsSelect[i*2]->setSelectedIndex(0); m_pItemsSelect[i*2]->setEnabled(false); @@ -149,7 +149,7 @@ void MenuVehiclePeripherals::valuesToUI() m_pItemsSelect[i*2]->setEnabled(true); - u32 uUsage = g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF; + u32 uUsage = g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF; if ( uUsage == SERIAL_PORT_USAGE_SIK_RADIO ) { m_pItemsSelect[i*2]->setSelectedIndex(1); @@ -204,7 +204,7 @@ void MenuVehiclePeripherals::valuesToUI() else m_pItemsSelect[i*2+1]->setSelectionIndexEnabled(n); - if ( hardware_get_serial_baud_rates()[n] == g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[i] ) + if ( hardware_get_serial_baud_rates()[n] == g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[i] ) { m_pItemsSelect[i*2+1]->setSelection(n); bFoundSpeed = true; @@ -243,7 +243,7 @@ void MenuVehiclePeripherals::onSelectItem() return; } - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) { if ( m_IndexSerialPortsUsage[i] == m_SelectedIndex ) { @@ -269,7 +269,7 @@ void MenuVehiclePeripherals::onSelectItem() newUsage = SERIAL_PORT_USAGE_SERIAL_RADIO_ELRS_915; if ( 8 == m_pItemsSelect[i*2]->getSelectedIndex() ) newUsage = SERIAL_PORT_USAGE_SERIAL_RADIO_ELRS_24; - if ( newUsage == (g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF) ) + if ( newUsage == (g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF) ) return; } else @@ -288,13 +288,13 @@ void MenuVehiclePeripherals::onSelectItem() } } } - if ( newUsage == (g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF) ) + if ( newUsage == (g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF) ) return; type_vehicle_hardware_interfaces_info new_info; memcpy((u8*)&new_info, (u8*)&(g_pCurrentModel->hardwareInterfacesInfo), sizeof(type_vehicle_hardware_interfaces_info)); - new_info.serial_bus_supported_and_usage[i] &= 0xFFFFFF00; - new_info.serial_bus_supported_and_usage[i] |= (u8)newUsage; + new_info.serial_port_supported_and_usage[i] &= 0xFFFFFF00; + new_info.serial_port_supported_and_usage[i] |= (u8)newUsage; log_line("Sending new serial ports usage to vehicle."); if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_SERIAL_PORTS_INFO, 0, (u8*)&new_info, sizeof(type_vehicle_hardware_interfaces_info)) ) valuesToUI(); @@ -304,12 +304,12 @@ void MenuVehiclePeripherals::onSelectItem() if ( m_IndexSerialPortsBaudRate[i] == m_SelectedIndex ) { long val = hardware_get_serial_baud_rates()[m_pItemsSelect[i*2+1]->getSelectedIndex()]; - if ( val == g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[i] ) + if ( val == g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[i] ) return; type_vehicle_hardware_interfaces_info new_info; memcpy((u8*)&new_info, (u8*)&(g_pCurrentModel->hardwareInterfacesInfo), sizeof(type_vehicle_hardware_interfaces_info)); - new_info.serial_bus_speed[i] = val; + new_info.serial_port_speed[i] = val; log_line("Sending new serial ports info to vehicle."); if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_SERIAL_PORTS_INFO, 0, (u8*)&new_info, sizeof(type_vehicle_hardware_interfaces_info)) ) valuesToUI(); diff --git a/code/r_central/menu/menu_vehicle_peripherals.h b/code/r_central/menu/menu_vehicle_peripherals.h index bab62151..dab93dba 100644 --- a/code/r_central/menu/menu_vehicle_peripherals.h +++ b/code/r_central/menu/menu_vehicle_peripherals.h @@ -19,7 +19,7 @@ class MenuVehiclePeripherals: public Menu bool m_bWaitingForVehicleInfo; - int m_IndexSerialPortsUsage[MAX_MODEL_SERIAL_BUSSES]; - int m_IndexStartPortUsagePluginsStartIndex[MAX_MODEL_SERIAL_BUSSES]; - int m_IndexSerialPortsBaudRate[MAX_MODEL_SERIAL_BUSSES]; + int m_IndexSerialPortsUsage[MAX_MODEL_SERIAL_PORTS]; + int m_IndexStartPortUsagePluginsStartIndex[MAX_MODEL_SERIAL_PORTS]; + int m_IndexSerialPortsBaudRate[MAX_MODEL_SERIAL_PORTS]; }; \ No newline at end of file diff --git a/code/r_central/menu/menu_vehicle_radio.cpp b/code/r_central/menu/menu_vehicle_radio.cpp index 9940d83a..81d195e3 100644 --- a/code/r_central/menu/menu_vehicle_radio.cpp +++ b/code/r_central/menu/menu_vehicle_radio.cpp @@ -35,13 +35,14 @@ #include "menu_item_select.h" #include "menu_confirmation.h" #include "menu_item_text.h" +#include "menu_item_legend.h" #include "menu_vehicle_radio_link.h" #include "menu_vehicle_radio_link_sik.h" #include "menu_radio_config.h" -#include "menu_tx_power.h" -#include "menu_tx_power_8812eu.h" +#include "menu_tx_raw_power.h" #include "menu_negociate_radio.h" - +#include "../../base/tx_powers.h" +#include "../../utils/utils_controller.h" #include "../link_watch.h" #include "../launchers_controller.h" #include "../../base/encr.h" @@ -52,18 +53,27 @@ int s_iTempGenNewFrequencyLink = 0; MenuVehicleRadioConfig::MenuVehicleRadioConfig(void) :Menu(MENU_ID_VEHICLE_RADIO_CONFIG, "Vehicle Radio Configuration", NULL) { - m_Width = 0.30; + m_Width = 0.38; m_xPos = menu_get_XStartPos(m_Width); m_yPos = 0.21; m_bControllerHasKey = false; - for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) + { + int iDriver = (g_pCurrentModel->radioInterfacesParams.interface_radiotype_and_driver[i] >> 8) & 0xFF; + int iCardModel = g_pCurrentModel->radioInterfacesParams.interface_card_model[i]; + int iPowerRaw = tx_powers_get_max_usable_power_raw_for_card(iDriver, iCardModel); + int iPowerMw = tx_powers_get_max_usable_power_mw_for_card(iDriver, iCardModel); + log_line("[MenuVehicleRadio] Max power for radio interface %d (%s, %s): raw: %d, mw: %d, current raw power: %d", + i+1, str_get_radio_card_model_string(iCardModel), str_get_radio_driver_description(iDriver), iPowerRaw, iPowerMw, g_pCurrentModel->radioInterfacesParams.interface_raw_power[i]); + } + valuesToUI(); } @@ -73,7 +83,9 @@ MenuVehicleRadioConfig::~MenuVehicleRadioConfig() void MenuVehicleRadioConfig::populate() { + int iTmp = getSelectedMenuItemIndex(); removeAllItems(); + char szBuff[128]; char szTooltip[256]; char szTitle[128]; @@ -262,23 +274,17 @@ void MenuVehicleRadioConfig::populate() } */ - if ( g_pCurrentModel->hasRadioCardsRTL8812AU() > 0 ) - { - m_IndexTxPowerRTL8812AU = addMenuItem(new MenuItem("Power Level (RTL8812AU)", "Change the transmit power levels for the vehicle's radio interfaces that use RTL8812AU chipset.")); - m_pMenuItems[m_IndexTxPowerRTL8812AU]->showArrow(); - } - if ( g_pCurrentModel->hasRadioCardsRTL8812EU() > 0 ) - { - m_IndexTxPowerRTL8812EU = addMenuItem(new MenuItem("Power Level (RTL8812EU)", "Change the transmit power levels for the vehicle's radio interfaces that use RTL8812EU chipset.")); - m_pMenuItems[m_IndexTxPowerRTL8812EU]->showArrow(); - } - if ( g_pCurrentModel->hasRadioCardsAtheros() > 0 ) - { - m_IndexTxPowerAtheros = addMenuItem(new MenuItem("Power Level (Atheros)", "Change the transmit power levels for the vehicle's radio interfaces that use Atheros chipset.")); - m_pMenuItems[m_IndexTxPowerAtheros]->showArrow(); - } + int iMwPowers[MAX_RADIO_INTERFACES]; + tx_power_get_current_mw_powers_for_model(g_pCurrentModel, &iMwPowers[0]); + m_iMaxPowerMw = tx_powers_get_max_usable_power_mw_for_model(g_pCurrentModel); + m_pItemsSelect[0] = createMenuItemTxPowers("Radio Tx Power (mW)", false, &(iMwPowers[0]), g_pCurrentModel->radioInterfacesParams.interfaces_count, m_iMaxPowerMw); + m_IndexTxPower = addMenuItem(m_pItemsSelect[0]); + + MenuItemLegend* pLegend = new MenuItemLegend("Note", "Maximum selectable Tx power is computed based on detected radio interfaces on the vehicle and controller.", 0); + pLegend->setExtraHeight(0.4*g_pRenderEngine->textHeight(g_idFontMenu)); + addMenuItem(pLegend); - m_IndexRadioConfig = addMenuItem(new MenuItem("Radio Parameters", "Full radio configuration")); + m_IndexRadioConfig = addMenuItem(new MenuItem("Radio Links Config", "Full radio configuration")); m_pMenuItems[m_IndexRadioConfig]->showArrow(); m_pItemsSelect[4] = new MenuItemSelect("Disable Uplinks", "Disable all uplinks, makes the system a one way system. Except for initial pairing and synching and sending commands to the vehicle. No video retransmissions happen, adaptive video is also disabled."); @@ -293,6 +299,7 @@ void MenuVehicleRadioConfig::populate() m_pItemsSelect[3]->setIsEditable(); m_IndexPrioritizeUplink = addMenuItem(m_pItemsSelect[3]); + /* m_pItemsSelect[2] = new MenuItemSelect("Radio Encryption", "Changes the encryption used for the radio links. You can encrypt the video data, or telemetry data, or everything, including the ability to search for and find this vehicle (unless your controller has the right pass phrase)."); m_pItemsSelect[2]->addSelection("None"); m_pItemsSelect[2]->addSelection("Video Stream Only"); @@ -301,16 +308,38 @@ void MenuVehicleRadioConfig::populate() m_pItemsSelect[2]->addSelection("All Streams and Data"); m_pItemsSelect[2]->setIsEditable(); m_IndexEncryption = addMenuItem(m_pItemsSelect[2]); + */ + m_IndexEncryption = -1; m_IndexOptimizeLinks = addMenuItem(new MenuItem("Optmize Radio Links Wizard", "Runs a process to optimize radio links parameters.")); m_pMenuItems[m_IndexOptimizeLinks]->showArrow(); + + m_SelectedIndex = iTmp; + if ( m_SelectedIndex >= m_ItemsCount ) + m_SelectedIndex = m_ItemsCount-1; +} + +void MenuVehicleRadioConfig::onShow() +{ + int iTmp = getSelectedMenuItemIndex(); + + valuesToUI(); + Menu::onShow(); + invalidate(); + + m_SelectedIndex = iTmp; + if ( m_SelectedIndex >= m_ItemsCount ) + m_SelectedIndex = m_ItemsCount-1; } + void MenuVehicleRadioConfig::valuesToUI() { populate(); - m_pItemsSelect[2]->setSelectedIndex(0); + if ( m_IndexEncryption != -1 ) + m_pItemsSelect[2]->setSelectedIndex(0); + m_pItemsSelect[3]->setSelectedIndex(0); if ( g_pCurrentModel->uModelFlags & MODEL_FLAG_PRIORITIZE_UPLINK ) @@ -325,48 +354,32 @@ void MenuVehicleRadioConfig::valuesToUI() else m_pItemsSelect[3]->setEnabled(true); - if ( g_pCurrentModel->enc_flags & MODEL_ENC_FLAG_ENC_VIDEO ) - m_pItemsSelect[2]->setSelectedIndex(1); - - if ( g_pCurrentModel->enc_flags & MODEL_ENC_FLAG_ENC_DATA ) - m_pItemsSelect[2]->setSelectedIndex(2); - - if ( g_pCurrentModel->enc_flags & MODEL_ENC_FLAG_ENC_DATA ) - if ( g_pCurrentModel->enc_flags & MODEL_ENC_FLAG_ENC_VIDEO ) - m_pItemsSelect[2]->setSelectedIndex(3); + if ( -1 != m_IndexEncryption ) + { + if ( g_pCurrentModel->enc_flags & MODEL_ENC_FLAG_ENC_VIDEO ) + m_pItemsSelect[2]->setSelectedIndex(1); - if ( g_pCurrentModel->enc_flags & MODEL_ENC_FLAG_ENC_ALL ) - m_pItemsSelect[2]->setSelectedIndex(4); + if ( g_pCurrentModel->enc_flags & MODEL_ENC_FLAG_ENC_DATA ) + m_pItemsSelect[2]->setSelectedIndex(2); - if ( ! m_bControllerHasKey ) - { - m_pItemsSelect[2]->setSelectedIndex(0); - //m_pItemsSelect[2]->setEnabled(false); - } + if ( g_pCurrentModel->enc_flags & MODEL_ENC_FLAG_ENC_DATA ) + if ( g_pCurrentModel->enc_flags & MODEL_ENC_FLAG_ENC_VIDEO ) + m_pItemsSelect[2]->setSelectedIndex(3); - if ( -1 != m_IndexTxPowerRTL8812AU ) - { - char szBuff[32]; - strcpy(szBuff, "N/A"); - sprintf(szBuff, "%d", g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU); - m_pMenuItems[m_IndexTxPowerRTL8812AU]->setValue(szBuff); - } + if ( g_pCurrentModel->enc_flags & MODEL_ENC_FLAG_ENC_ALL ) + m_pItemsSelect[2]->setSelectedIndex(4); - if ( -1 != m_IndexTxPowerRTL8812EU ) - { - char szBuff[32]; - strcpy(szBuff, "N/A"); - sprintf(szBuff, "%d", g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU); - m_pMenuItems[m_IndexTxPowerRTL8812EU]->setValue(szBuff); + if ( ! m_bControllerHasKey ) + { + m_pItemsSelect[2]->setSelectedIndex(0); + //m_pItemsSelect[2]->setEnabled(false); + } } - if ( -1 != m_IndexTxPowerAtheros ) - { - char szBuff[32]; - strcpy(szBuff, "N/A"); - sprintf(szBuff, "%d", g_pCurrentModel->radioInterfacesParams.txPowerAtheros); - m_pMenuItems[m_IndexTxPowerAtheros]->setValue(szBuff); - } + int iMwPowers[MAX_RADIO_INTERFACES]; + tx_power_get_current_mw_powers_for_model(g_pCurrentModel, &iMwPowers[0]); + m_iMaxPowerMw = tx_powers_get_max_usable_power_mw_for_model(g_pCurrentModel); + selectMenuItemTxPowersValue(m_pItemsSelect[0], false, &(iMwPowers[0]), g_pCurrentModel->radioInterfacesParams.interfaces_count, m_iMaxPowerMw); } void MenuVehicleRadioConfig::Render() @@ -383,6 +396,18 @@ void MenuVehicleRadioConfig::Render() } +int MenuVehicleRadioConfig::onBack() +{ + return Menu::onBack(); +} + +void MenuVehicleRadioConfig::onReturnFromChild(int iChildMenuId, int returnValue) +{ + Menu::onReturnFromChild(iChildMenuId, returnValue); + + valuesToUI(); +} + void MenuVehicleRadioConfig::sendNewRadioLinkFrequency(int iVehicleLinkIndex, u32 uNewFreqKhz) { if ( (iVehicleLinkIndex < 0) || (iVehicleLinkIndex >= MAX_RADIO_INTERFACES) ) @@ -424,6 +449,56 @@ void MenuVehicleRadioConfig::sendNewRadioLinkFrequency(int iVehicleLinkIndex, u3 } +void MenuVehicleRadioConfig::computeSendPowerToVehicle() +{ + int iIndex = m_pItemsSelect[0]->getSelectedIndex(); + + if ( iIndex == m_pItemsSelect[0]->getSelectionsCount() -1 ) + { + add_menu_to_stack(new MenuTXRawPower()); + return; + } + + log_line("MenuVehicleRadio: Setting tx power to %s", m_pItemsSelect[0]->getSelectionIndexText(iIndex)); + + int iPowerLevelsCount = 0; + const int* piPowerLevelsMw = tx_powers_get_ui_levels_mw(&iPowerLevelsCount); + int iPowerMwToSet = piPowerLevelsMw[iIndex]; + + u8 uCommandParams[MAX_RADIO_INTERFACES+1]; + uCommandParams[0] = g_pCurrentModel->radioInterfacesParams.interfaces_count; + bool bDifferent = false; + for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) + { + int iDriver = (g_pCurrentModel->radioInterfacesParams.interface_radiotype_and_driver[i] >> 8) & 0xFF; + int iCardModel = g_pCurrentModel->radioInterfacesParams.interface_card_model[i]; + int iCardMaxPowerMw = tx_powers_get_max_usable_power_mw_for_card(iDriver, iCardModel); + int iCardNewPowerMw = iPowerMwToSet; + if ( iCardNewPowerMw > iCardMaxPowerMw ) + iCardNewPowerMw = iCardMaxPowerMw; + int iTxPowerRawToSet = tx_powers_convert_mw_to_raw(iDriver, iCardModel, iCardNewPowerMw); + uCommandParams[i+1] = iTxPowerRawToSet; + log_line("MenuVehicleRadio: Setting tx raw power for card %d from %d to: %d (%d mw)", + i+1, g_pCurrentModel->radioInterfacesParams.interface_raw_power[i], uCommandParams[i+1], iCardNewPowerMw); + if ( uCommandParams[i+1] != g_pCurrentModel->radioInterfacesParams.interface_raw_power[i] ) + bDifferent = true; + } + + if ( ! bDifferent ) + { + log_line("MenuVehicleRadio: No change"); + return; + } + + save_ControllerInterfacesSettings(); + apply_controller_radio_tx_powers(g_pCurrentModel, get_ControllerSettings()->iFixedTxPower, false); + save_ControllerInterfacesSettings(); + + if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_TX_POWERS, 0, uCommandParams, uCommandParams[0]+1) ) + valuesToUI(); +} + + void MenuVehicleRadioConfig::onSelectItem() { if ( handle_commands_is_command_in_progress() ) @@ -459,7 +534,7 @@ void MenuVehicleRadioConfig::onSelectItem() valuesToUI(); } - if ( m_IndexEncryption == m_SelectedIndex ) + if ( (-1 != m_IndexEncryption) && (m_IndexEncryption == m_SelectedIndex) ) { if ( ! m_bControllerHasKey ) { @@ -504,22 +579,9 @@ void MenuVehicleRadioConfig::onSelectItem() return; } - if ( (m_IndexTxPowerRTL8812AU == m_SelectedIndex) || (m_IndexTxPowerAtheros == m_SelectedIndex) ) + if ( m_IndexTxPower == m_SelectedIndex ) { - MenuTXPower* pMenu = new MenuTXPower(); - pMenu->m_bShowController = false; - pMenu->m_bShowVehicle = true; - add_menu_to_stack(pMenu); - return; - } - - if ( m_IndexTxPowerRTL8812EU == m_SelectedIndex ) - { - //MenuTXPower8812EU* pMenu = new MenuTXPower8812EU(); - MenuTXPower* pMenu = new MenuTXPower(); - pMenu->m_bShowController = false; - pMenu->m_bShowVehicle = true; - add_menu_to_stack(pMenu); + computeSendPowerToVehicle(); return; } diff --git a/code/r_central/menu/menu_vehicle_radio.h b/code/r_central/menu/menu_vehicle_radio.h index 5777c3eb..c3b89f4b 100644 --- a/code/r_central/menu/menu_vehicle_radio.h +++ b/code/r_central/menu/menu_vehicle_radio.h @@ -9,6 +9,9 @@ class MenuVehicleRadioConfig: public Menu public: MenuVehicleRadioConfig(); virtual ~MenuVehicleRadioConfig(); + virtual void onShow(); + virtual int onBack(); + virtual void onReturnFromChild(int iChildMenuId, int returnValue); virtual void Render(); virtual void valuesToUI(); virtual void onSelectItem(); @@ -20,9 +23,7 @@ class MenuVehicleRadioConfig: public Menu int m_IndexPrioritizeUplink; int m_IndexDisableUplink; int m_IndexEncryption; - int m_IndexTxPowerRTL8812AU; - int m_IndexTxPowerRTL8812EU; - int m_IndexTxPowerAtheros; + int m_IndexTxPower; int m_IndexRadioConfig; int m_IndexOptimizeLinks; int m_IndexFreq[MAX_RADIO_INTERFACES]; @@ -31,7 +32,10 @@ class MenuVehicleRadioConfig: public Menu int m_SupportedChannelsCount[MAX_RADIO_INTERFACES]; bool m_bControllerHasKey; + int m_iMaxPowerMw; + void populate(); void sendNewRadioLinkFrequency(int iVehicleLinkIndex, u32 uNewFreqKhz); + void computeSendPowerToVehicle(); }; \ No newline at end of file diff --git a/code/r_central/menu/menu_vehicle_radio_interface.cpp b/code/r_central/menu/menu_vehicle_radio_interface.cpp index 4445d3c9..36408fad 100644 --- a/code/r_central/menu/menu_vehicle_radio_interface.cpp +++ b/code/r_central/menu/menu_vehicle_radio_interface.cpp @@ -34,11 +34,11 @@ #include "menu_item_select.h" #include "menu_item_section.h" #include "menu_item_text.h" -#include "menu_tx_power.h" +#include "menu_tx_raw_power.h" #include "menu_confirmation.h" #include "../launchers_controller.h" #include "../link_watch.h" - +#include "../../base/tx_powers.h" const char* s_szMenuRadio_SingleCard3 = "Note: You can not change the function and capabilities of the radio interface as there is a single one present on the vehicle."; @@ -80,9 +80,9 @@ void MenuVehicleRadioInterface::onShow() void MenuVehicleRadioInterface::valuesToUI() { if ( g_pCurrentModel->radioInterfacesParams.interface_card_model[m_iRadioInterface] < 0 ) - m_pItemsSelect[1]->setSelection(-g_pCurrentModel->radioInterfacesParams.interface_card_model[m_iRadioInterface]); + m_pItemsSelect[1]->setSelection(1-g_pCurrentModel->radioInterfacesParams.interface_card_model[m_iRadioInterface]); else - m_pItemsSelect[1]->setSelection(g_pCurrentModel->radioInterfacesParams.interface_card_model[m_iRadioInterface]); + m_pItemsSelect[1]->setSelection(1+g_pCurrentModel->radioInterfacesParams.interface_card_model[m_iRadioInterface]); } void MenuVehicleRadioInterface::Render() @@ -135,9 +135,11 @@ void MenuVehicleRadioInterface::onSelectItem() int iCardModel = m_pItemsSelect[1]->getSelectedIndex(); u32 uParam = m_iRadioInterface; if ( 0 == iCardModel ) + uParam |= 0xFF00; + else if ( 1 == iCardModel ) uParam = uParam | (128<<8); else - uParam = uParam | ((128-iCardModel) << 8); + uParam = uParam | ((128-(iCardModel-1)) << 8); if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_RADIO_CARD_MODEL, uParam, NULL, 0) ) valuesToUI(); diff --git a/code/r_central/menu/menu_vehicle_radio_link.cpp b/code/r_central/menu/menu_vehicle_radio_link.cpp index 77eb1a24..80407f50 100644 --- a/code/r_central/menu/menu_vehicle_radio_link.cpp +++ b/code/r_central/menu/menu_vehicle_radio_link.cpp @@ -34,11 +34,12 @@ #include "menu_item_select.h" #include "menu_item_section.h" #include "menu_item_text.h" -#include "menu_tx_power.h" +#include "menu_tx_raw_power.h" #include "menu_confirmation.h" #include "../launchers_controller.h" #include "../link_watch.h" #include "../../radio/radiolink.h" +#include "../../base/tx_powers.h" const char* s_szMenuRadio_SingleCard2 = "Note: You can not change the usage and capabilities of the radio link as there is a single radio link between vehicle and controller."; diff --git a/code/r_central/menu/menu_vehicle_radio_link_elrs.cpp b/code/r_central/menu/menu_vehicle_radio_link_elrs.cpp index cb1973cc..6d90cc7d 100644 --- a/code/r_central/menu/menu_vehicle_radio_link_elrs.cpp +++ b/code/r_central/menu/menu_vehicle_radio_link_elrs.cpp @@ -34,7 +34,7 @@ #include "menu_item_select.h" #include "menu_item_section.h" #include "menu_item_text.h" -#include "menu_tx_power.h" +#include "menu_tx_raw_power.h" #include "menu_confirmation.h" #include "../launchers_controller.h" #include "../link_watch.h" diff --git a/code/r_central/menu/menu_vehicle_radio_link_sik.cpp b/code/r_central/menu/menu_vehicle_radio_link_sik.cpp index ab2ea371..a2bae764 100644 --- a/code/r_central/menu/menu_vehicle_radio_link_sik.cpp +++ b/code/r_central/menu/menu_vehicle_radio_link_sik.cpp @@ -34,7 +34,7 @@ #include "menu_item_select.h" #include "menu_item_section.h" #include "menu_item_text.h" -#include "menu_tx_power.h" +#include "menu_tx_raw_power.h" #include "menu_confirmation.h" #include "../launchers_controller.h" #include "../link_watch.h" diff --git a/code/r_central/menu/menu_vehicle_telemetry.cpp b/code/r_central/menu/menu_vehicle_telemetry.cpp index e5b8dc5b..b62f4982 100644 --- a/code/r_central/menu/menu_vehicle_telemetry.cpp +++ b/code/r_central/menu/menu_vehicle_telemetry.cpp @@ -82,8 +82,8 @@ MenuVehicleTelemetry::MenuVehicleTelemetry(void) m_pItemsSelect[1] = new MenuItemSelect("Vehicle Serial Port", "The Ruby vehicle port at which the flight controller connects to."); m_pItemsSelect[1]->addSelection("None"); - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) - m_pItemsSelect[1]->addSelection(g_pCurrentModel->hardwareInterfacesInfo.serial_bus_names[i]); + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) + m_pItemsSelect[1]->addSelection(g_pCurrentModel->hardwareInterfacesInfo.serial_port_names[i]); m_pItemsSelect[1]->setIsEditable(); m_IndexVSerialPort = addMenuItem(m_pItemsSelect[1]); @@ -230,16 +230,16 @@ void MenuVehicleTelemetry::valuesToUI() int iCurrentSerialPortIndexForTelemetry = -1; u32 uCurrentSerialPortSpeed = 0; - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) { - u32 uPortTelemetryType = g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF; - if ( g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) + u32 uPortTelemetryType = g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF; + if ( g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) if ( (uPortTelemetryType == SERIAL_PORT_USAGE_TELEMETRY_MAVLINK) || (uPortTelemetryType == SERIAL_PORT_USAGE_TELEMETRY_LTM) || (uPortTelemetryType == SERIAL_PORT_USAGE_MSP_OSD) ) { iCurrentSerialPortIndexForTelemetry = i; - uCurrentSerialPortSpeed = g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[i]; + uCurrentSerialPortSpeed = g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[i]; break; } } @@ -326,11 +326,11 @@ void MenuVehicleTelemetry::onSelectItem() return; int iCurrentSerialPortIndexForTelemetry = -1; - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) { - u32 uPortTelemetryType = g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF; + u32 uPortTelemetryType = g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF; - if ( g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) + if ( g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) if ( (uPortTelemetryType == SERIAL_PORT_USAGE_TELEMETRY_MAVLINK) || (uPortTelemetryType == SERIAL_PORT_USAGE_TELEMETRY_LTM) || (uPortTelemetryType == SERIAL_PORT_USAGE_MSP_OSD) ) @@ -361,18 +361,18 @@ void MenuVehicleTelemetry::onSelectItem() if ( (params.fc_telemetry_type == TELEMETRY_TYPE_NONE) && (-1 != iCurrentSerialPortIndexForTelemetry) ) { // Remove serial port usage (set it to none) - g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[iCurrentSerialPortIndexForTelemetry] &= 0xFFFFFF00; + g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[iCurrentSerialPortIndexForTelemetry] &= 0xFFFFFF00; } // Assign a default serial port if none is set if ( (params.fc_telemetry_type != TELEMETRY_TYPE_NONE) && (-1 == iCurrentSerialPortIndexForTelemetry) ) { log_line("MenuVehicleTelemetry: Try to find a default serial port for telemetry..."); - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) { - u32 uPortUsage = g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF; + u32 uPortUsage = g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF; - if ( g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) + if ( g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) if ( uPortUsage == SERIAL_PORT_USAGE_NONE ) { iCurrentSerialPortIndexForTelemetry = i; @@ -389,16 +389,16 @@ void MenuVehicleTelemetry::onSelectItem() type_vehicle_hardware_interfaces_info new_info; memcpy((u8*)&new_info, (u8*)&(g_pCurrentModel->hardwareInterfacesInfo), sizeof(type_vehicle_hardware_interfaces_info)); - if ( new_info.serial_bus_speed[iCurrentSerialPortIndexForTelemetry] <= 0 ) - new_info.serial_bus_speed[iCurrentSerialPortIndexForTelemetry] = DEFAULT_FC_TELEMETRY_SERIAL_SPEED; + if ( new_info.serial_port_speed[iCurrentSerialPortIndexForTelemetry] <= 0 ) + new_info.serial_port_speed[iCurrentSerialPortIndexForTelemetry] = DEFAULT_FC_TELEMETRY_SERIAL_SPEED; - new_info.serial_bus_supported_and_usage[iCurrentSerialPortIndexForTelemetry] &= 0xFFFFFF00; + new_info.serial_port_supported_and_usage[iCurrentSerialPortIndexForTelemetry] &= 0xFFFFFF00; if ( 1 == m_pItemsSelect[0]->getSelectedIndex() ) - new_info.serial_bus_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_TELEMETRY_MAVLINK; + new_info.serial_port_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_TELEMETRY_MAVLINK; if ( 2 == m_pItemsSelect[0]->getSelectedIndex() ) - new_info.serial_bus_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_TELEMETRY_LTM; + new_info.serial_port_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_TELEMETRY_LTM; if ( 3 == m_pItemsSelect[0]->getSelectedIndex() ) - new_info.serial_bus_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_MSP_OSD; + new_info.serial_port_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_MSP_OSD; // We don't need to send the serial ports configuration to vehicle as the vehicle // does the same assignment if no serial port is set when telemetry changes with @@ -546,7 +546,7 @@ void MenuVehicleTelemetry::onSelectItem() { int iSerialPort = m_pItemsSelect[1]->getSelectedIndex(); if ( iSerialPort != 0 ) - if ( (g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[iSerialPort-1] & 0xFF) == SERIAL_PORT_USAGE_SIK_RADIO ) + if ( (g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[iSerialPort-1] & 0xFF) == SERIAL_PORT_USAGE_SIK_RADIO ) { MenuConfirmation* pMC = new MenuConfirmation("Can't use serial port", "The serial port you selected can't be used for telemetry connection to flight controller as it's used for a SiK radio interface.",1, true); pMC->m_yPos = 0.3; @@ -561,8 +561,8 @@ void MenuVehicleTelemetry::onSelectItem() { type_vehicle_hardware_interfaces_info new_info; memcpy((u8*)&new_info, (u8*)&(g_pCurrentModel->hardwareInterfacesInfo), sizeof(type_vehicle_hardware_interfaces_info)); - new_info.serial_bus_supported_and_usage[iCurrentSerialPortIndexForTelemetry] &= 0xFFFFFF00; - new_info.serial_bus_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_NONE; + new_info.serial_port_supported_and_usage[iCurrentSerialPortIndexForTelemetry] &= 0xFFFFFF00; + new_info.serial_port_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_NONE; log_line("Sending disabling telemetry serial port selection to vehicle."); if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_SERIAL_PORTS_INFO, 0, (u8*)&new_info, sizeof(type_vehicle_hardware_interfaces_info)) ) @@ -576,7 +576,7 @@ void MenuVehicleTelemetry::onSelectItem() type_vehicle_hardware_interfaces_info new_info; memcpy((u8*)&new_info, (u8*)&(g_pCurrentModel->hardwareInterfacesInfo), sizeof(type_vehicle_hardware_interfaces_info)); - u8 uCurrentUsage = new_info.serial_bus_supported_and_usage[iSerialPort-1] & 0xFF; + u8 uCurrentUsage = new_info.serial_port_supported_and_usage[iSerialPort-1] & 0xFF; if ( uCurrentUsage == SERIAL_PORT_USAGE_DATA_LINK ) { MenuConfirmation* pMC = new MenuConfirmation("User Data Link Disabled", "The serial port was used by your custom data link. It was reasigned to the telemetry link.",1, true); @@ -586,17 +586,17 @@ void MenuVehicleTelemetry::onSelectItem() if ( iCurrentSerialPortIndexForTelemetry != -1 ) { - new_info.serial_bus_supported_and_usage[iCurrentSerialPortIndexForTelemetry] &= 0xFFFFFF00; - new_info.serial_bus_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_NONE; + new_info.serial_port_supported_and_usage[iCurrentSerialPortIndexForTelemetry] &= 0xFFFFFF00; + new_info.serial_port_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_NONE; } - new_info.serial_bus_supported_and_usage[iSerialPort-1] &= 0xFFFFFF00; + new_info.serial_port_supported_and_usage[iSerialPort-1] &= 0xFFFFFF00; if ( 1 == m_pItemsSelect[0]->getSelectedIndex() ) - new_info.serial_bus_supported_and_usage[iSerialPort-1] |= SERIAL_PORT_USAGE_TELEMETRY_MAVLINK; + new_info.serial_port_supported_and_usage[iSerialPort-1] |= SERIAL_PORT_USAGE_TELEMETRY_MAVLINK; if ( 2 == m_pItemsSelect[0]->getSelectedIndex() ) - new_info.serial_bus_supported_and_usage[iSerialPort-1] |= SERIAL_PORT_USAGE_TELEMETRY_LTM; + new_info.serial_port_supported_and_usage[iSerialPort-1] |= SERIAL_PORT_USAGE_TELEMETRY_LTM; if ( 3 == m_pItemsSelect[0]->getSelectedIndex() ) - new_info.serial_bus_supported_and_usage[iSerialPort-1] |= SERIAL_PORT_USAGE_MSP_OSD; + new_info.serial_port_supported_and_usage[iSerialPort-1] |= SERIAL_PORT_USAGE_MSP_OSD; log_line("Sending new serial port to be used for telemetry to vehicle."); if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_SERIAL_PORTS_INFO, 0, (u8*)&new_info, sizeof(type_vehicle_hardware_interfaces_info)) ) @@ -611,12 +611,12 @@ void MenuVehicleTelemetry::onSelectItem() return; long val = hardware_get_serial_baud_rates()[m_pItemsSelect[2]->getSelectedIndex()]; - if ( val == g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[iCurrentSerialPortIndexForTelemetry] ) + if ( val == g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[iCurrentSerialPortIndexForTelemetry] ) return; type_vehicle_hardware_interfaces_info new_info; memcpy((u8*)&new_info, (u8*)&(g_pCurrentModel->hardwareInterfacesInfo), sizeof(type_vehicle_hardware_interfaces_info)); - new_info.serial_bus_speed[iCurrentSerialPortIndexForTelemetry] = (u32)val; + new_info.serial_port_speed[iCurrentSerialPortIndexForTelemetry] = (u32)val; log_line("Sending new serial port speed for telemetry to vehicle: %u", val); if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_SERIAL_PORTS_INFO, 0, (u8*)&new_info, sizeof(type_vehicle_hardware_interfaces_info)) ) valuesToUI(); diff --git a/code/r_central/menu/menu_vehicle_video.cpp b/code/r_central/menu/menu_vehicle_video.cpp index 2d0327f0..b53b8054 100644 --- a/code/r_central/menu/menu_vehicle_video.cpp +++ b/code/r_central/menu/menu_vehicle_video.cpp @@ -31,7 +31,7 @@ #include "../../base/video_capture_res.h" #include "../../base/utils.h" -#include "../../base/controller_utils.h" +#include "../../utils/utils_controller.h" #include "menu.h" #include "menu_vehicle_video.h" #include "menu_vehicle_video_bidir.h" @@ -117,6 +117,7 @@ MenuVehicleVideo::MenuVehicleVideo(void) m_pItemsSlider[1] = new MenuItemSlider("Keyframe interval (ms)", "A keyframe is added every [n] miliseconds. Bigger keyframe values usually results in better quality video and lower bandwidth requirements but longer breakups if any.", 50,20000,200, fSliderWidth); m_pItemsSlider[1]->setStep(10); + m_pItemsSlider[1]->setSufix("ms"); m_IndexKeyframe = addMenuItem(m_pItemsSlider[1]); m_pMenuItemVideoKeyframeWarning = new MenuItemText("", true); @@ -126,6 +127,7 @@ MenuVehicleVideo::MenuVehicleVideo(void) m_pItemsSlider[2] = new MenuItemSlider("Video Bitrate (Mbps)", "Sets the video bitrate of the video stream generated by the camera.", 1,80,0, fSliderWidth); m_pItemsSlider[2]->setTooltip("Sets a target desired bitrate for the video stream."); m_pItemsSlider[2]->enableHalfSteps(); + m_pItemsSlider[2]->setSufix("mbps"); m_IndexVideoBitrate = addMenuItem(m_pItemsSlider[2]); m_pItemsSelect[13] = new MenuItemSelect("Keep constant", "Adjust camera bitrate (when there are variations due to scenery change) to try to keep the set fixed bitrate."); @@ -615,9 +617,11 @@ void MenuVehicleVideo::onSelectItem() (paramsNew.uVideoExtraFlags & VIDEO_FLAG_GENERATE_H265)?"H265":"H264"); if ( g_pCurrentModel->video_params.uVideoExtraFlags != paramsNew.uVideoExtraFlags ) - if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_VIDEO_PARAMS, 0, (u8*)¶msNew, sizeof(video_parameters_t)) ) - valuesToUI(); - else - send_control_message_to_router(PACEKT_TYPE_LOCAL_CONTROLLER_ADAPTIVE_VIDEO_PAUSE, 10000); + { + if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_VIDEO_PARAMS, 0, (u8*)¶msNew, sizeof(video_parameters_t)) ) + valuesToUI(); + else + send_control_message_to_router(PACEKT_TYPE_LOCAL_CONTROLLER_ADAPTIVE_VIDEO_PAUSE, 10000); + } } } diff --git a/code/r_central/menu/menu_vehicle_video_bidir.cpp b/code/r_central/menu/menu_vehicle_video_bidir.cpp index 078efa38..56c3bd28 100644 --- a/code/r_central/menu/menu_vehicle_video_bidir.cpp +++ b/code/r_central/menu/menu_vehicle_video_bidir.cpp @@ -31,7 +31,7 @@ #include "../../base/video_capture_res.h" #include "../../base/utils.h" -#include "../../base/controller_utils.h" +#include "../../utils/utils_controller.h" #include "menu.h" #include "menu_vehicle_video_bidir.h" #include "menu_vehicle_video_profile.h" diff --git a/code/r_central/menu/menu_vehicle_video_encodings.cpp b/code/r_central/menu/menu_vehicle_video_encodings.cpp index 768053fd..b0ebba53 100644 --- a/code/r_central/menu/menu_vehicle_video_encodings.cpp +++ b/code/r_central/menu/menu_vehicle_video_encodings.cpp @@ -34,7 +34,7 @@ #include "menu_item_select.h" #include "menu_item_section.h" #include "../../base/utils.h" -#include "../../base/controller_utils.h" +#include "../../utils/utils_controller.h" const char* s_szWarningBitrate = "Warning: The current radio datarate is to small for the current video encoding settings.\n You will experience delays in the video stream.\n Increase the radio datarate, or decrease the video bitrate, decrease the encoding params."; @@ -114,28 +114,35 @@ MenuVehicleVideoEncodings::MenuVehicleVideoEncodings(void) addMenuItem(new MenuItemSection("H264 Encoder Settings")); - m_pItemsSelect[4] = new MenuItemSelect("H264 Profile", "The higher the H264 profile, the higher the CPU usage on encode and decode and higher the end to end video latencey. Higher profiles can have lower video quality as more compression algorithms are used."); - m_pItemsSelect[4]->addSelection("Baseline"); - m_pItemsSelect[4]->addSelection("Main"); - //m_pItemsSelect[4]->addSelection("Extended"); - m_pItemsSelect[4]->addSelection("High"); - m_pItemsSelect[4]->setIsEditable(); - m_IndexH264Profile = addMenuItem(m_pItemsSelect[4]); - - m_pItemsSelect[5] = new MenuItemSelect("H264 Level", ""); - m_pItemsSelect[5]->addSelection("4"); - m_pItemsSelect[5]->addSelection("4.1"); - m_pItemsSelect[5]->addSelection("4.2"); - m_pItemsSelect[5]->setIsEditable(); - m_IndexH264Level = addMenuItem(m_pItemsSelect[5]); - - m_pItemsSelect[6] = new MenuItemSelect("H264 Inter Refresh", ""); - m_pItemsSelect[6]->addSelection("Cyclic"); - m_pItemsSelect[6]->addSelection("Adaptive"); - m_pItemsSelect[6]->addSelection("Both"); - m_pItemsSelect[6]->addSelection("Cyclic Rows"); - m_pItemsSelect[6]->setIsEditable(); - m_IndexH264Refresh = addMenuItem(m_pItemsSelect[6]); + m_IndexH264Profile = -1; + m_IndexH264Level = -1; + m_IndexH264Refresh = -1; + + if ( ! g_pCurrentModel->isRunningOnOpenIPCHardware() ) + { + m_pItemsSelect[4] = new MenuItemSelect("H264 Profile", "The higher the H264 profile, the higher the CPU usage on encode and decode and higher the end to end video latencey. Higher profiles can have lower video quality as more compression algorithms are used."); + m_pItemsSelect[4]->addSelection("Baseline"); + m_pItemsSelect[4]->addSelection("Main"); + m_pItemsSelect[4]->addSelection("High"); + m_pItemsSelect[4]->addSelection("Extended"); + m_pItemsSelect[4]->setIsEditable(); + m_IndexH264Profile = addMenuItem(m_pItemsSelect[4]); + + m_pItemsSelect[5] = new MenuItemSelect("H264 Level", ""); + m_pItemsSelect[5]->addSelection("4"); + m_pItemsSelect[5]->addSelection("4.1"); + m_pItemsSelect[5]->addSelection("4.2"); + m_pItemsSelect[5]->setIsEditable(); + m_IndexH264Level = addMenuItem(m_pItemsSelect[5]); + + m_pItemsSelect[6] = new MenuItemSelect("H264 Inter Refresh", ""); + m_pItemsSelect[6]->addSelection("Cyclic"); + m_pItemsSelect[6]->addSelection("Adaptive"); + m_pItemsSelect[6]->addSelection("Both"); + m_pItemsSelect[6]->addSelection("Cyclic Rows"); + m_pItemsSelect[6]->setIsEditable(); + m_IndexH264Refresh = addMenuItem(m_pItemsSelect[6]); + } m_pItemsSelect[12] = new MenuItemSelect("H264 Slices", "Split video frames into multiple smaller parts. When having heavy radio interference there is a chance that not the entire video is corrupted if video is sliced up. But is uses more processing power."); for( int i=1; i<=16; i++ ) @@ -146,27 +153,51 @@ MenuVehicleVideoEncodings::MenuVehicleVideoEncodings(void) m_pItemsSelect[12]->setIsEditable(); m_IndexH264Slices = addMenuItem(m_pItemsSelect[12]); - m_pItemsSelect[7] = new MenuItemSelect("H264 Insert PPS Headers", ""); - m_pItemsSelect[7]->addSelection("No"); - m_pItemsSelect[7]->addSelection("Yes"); - m_pItemsSelect[7]->setIsEditable(); - m_IndexH264Headers = addMenuItem(m_pItemsSelect[7]); + m_pItemsSelect[17] = new MenuItemSelect("Remove extra H264/H265 frames", "Removes frames not needed for video decoding."); + m_pItemsSelect[17]->addSelection("No"); + m_pItemsSelect[17]->addSelection("Yes"); + m_pItemsSelect[17]->setIsEditable(); + m_IndexRemoveH264PPS = addMenuItem(m_pItemsSelect[17]); - m_pItemsSelect[11] = new MenuItemSelect("H264 Fill SPS Timings", ""); - m_pItemsSelect[11]->addSelection("No"); - m_pItemsSelect[11]->addSelection("Yes"); - m_pItemsSelect[11]->setIsEditable(); - m_IndexH264SPSTimings = addMenuItem(m_pItemsSelect[11]); + m_IndexInsertH264PPS = -1; + m_IndexInsertH264SPSTimings = -1; + if ( ! g_pCurrentModel->isRunningOnOpenIPCHardware() ) + { + m_pItemsSelect[7] = new MenuItemSelect("Insert H264 PPS Headers", ""); + m_pItemsSelect[7]->addSelection("No"); + m_pItemsSelect[7]->addSelection("Yes"); + m_pItemsSelect[7]->setIsEditable(); + m_IndexInsertH264PPS = addMenuItem(m_pItemsSelect[7]); + + m_pItemsSelect[11] = new MenuItemSelect("Fill H264 SPS Timings", ""); + m_pItemsSelect[11]->addSelection("No"); + m_pItemsSelect[11]->addSelection("Yes"); + m_pItemsSelect[11]->setIsEditable(); + m_IndexInsertH264SPSTimings = addMenuItem(m_pItemsSelect[11]); + } - m_pItemsSelect[8] = new MenuItemSelect("Auto H264 quantization", "Use default quantization for the H264 video encoding, or set a custom value."); - m_pItemsSelect[8]->addSelection("No"); - m_pItemsSelect[8]->addSelection("Yes"); - m_pItemsSelect[8]->setIsEditable(); - m_IndexCustomQuant = addMenuItem(m_pItemsSelect[8]); + m_IndexIPQuantizationDelta = -1; + m_IndexCustomQuant = -1; + m_IndexQuantValue = -1; - m_pItemsSlider[4] = new MenuItemSlider("Manual video quantization", 0,40,20,fSliderWidth); - m_pItemsSlider[4]->setTooltip("Sets a fixed H264 quantization parameter for the video stream. Higher values reduces quality but decreases bitrate requirements and latency. The default is about 16"); - m_IndexQuantValue = addMenuItem(m_pItemsSlider[4]); + if ( g_pCurrentModel->isRunningOnOpenIPCHardware() ) + { + m_pItemsSlider[18] = new MenuItemSlider("I-P Frames Quantization Delta", -12,12,-2,fSliderWidth); + m_pItemsSlider[18]->setTooltip("Sets a relative quantization difference between P and I frames. Higher values increase the quality of I frames compared to P frames."); + m_IndexIPQuantizationDelta = addMenuItem(m_pItemsSlider[18]); + } + else + { + m_pItemsSelect[8] = new MenuItemSelect("Auto H264 quantization", "Use default quantization for the H264 video encoding, or set a custom value."); + m_pItemsSelect[8]->addSelection("No"); + m_pItemsSelect[8]->addSelection("Yes"); + m_pItemsSelect[8]->setIsEditable(); + m_IndexCustomQuant = addMenuItem(m_pItemsSelect[8]); + + m_pItemsSlider[4] = new MenuItemSlider("Manual video quantization", 0,40,20,fSliderWidth); + m_pItemsSlider[4]->setTooltip("Sets a fixed H264 quantization parameter for the video stream. Higher values reduces quality but decreases bitrate requirements and latency. The default is about 16"); + m_IndexQuantValue = addMenuItem(m_pItemsSlider[4]); + } m_pItemsSelect[14] = new MenuItemSelect("Enable adaptive H264 quantization", "Enable algorithm that auto adjusts the H264 quantization to match the desired video bitrate in realtime."); m_pItemsSelect[14]->addSelection("No"); @@ -198,7 +229,8 @@ void MenuVehicleVideoEncodings::valuesToUI() m_pItemsSelect[19]->setSelectedIndex((int) uECSpread); - m_pItemsSelect[4]->setSelectedIndex((g_pCurrentModel->video_params.uVideoExtraFlags & VIDEO_FLAG_ENABLE_LOCAL_HDMI_OUTPUT)?1:0); + if ( -1 != m_IndexH264Profile ) + m_pItemsSelect[4]->setSelectedIndex((g_pCurrentModel->video_params.uVideoExtraFlags & VIDEO_FLAG_ENABLE_LOCAL_HDMI_OUTPUT)?1:0); log_line("MenuVideoEncodings: Current video profile: %d, %s, current video datarate: %u", g_pCurrentModel->video_params.user_selected_video_link_profile, @@ -223,10 +255,14 @@ void MenuVehicleVideoEncodings::valuesToUI() m_pItemsSelect[16]->setSelection(selectedIndex); - m_pItemsSelect[4]->setSelection(g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264profile); - m_pItemsSelect[5]->setSelection(g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264level); - m_pItemsSelect[6]->setSelection(g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264refresh); - m_pItemsSelect[7]->setSelection((int)(g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].insertPPS)); + if ( -1 != m_IndexH264Profile ) + m_pItemsSelect[4]->setSelection(g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264profile); + if ( -1 != m_IndexH264Level ) + m_pItemsSelect[5]->setSelection(g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264level); + if ( -1 != m_IndexH264Refresh ) + m_pItemsSelect[6]->setSelection(g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264refresh); + if ( -1 != m_IndexInsertH264PPS ) + m_pItemsSelect[7]->setSelection(g_pCurrentModel->video_params.iInsertPPSVideoFrames); if ( g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_VIDEO_ADAPTIVE_QUANTIZATION_STRENGTH_HIGH ) m_pItemsSelect[15]->setSelectedIndex(1); @@ -244,31 +280,45 @@ void MenuVehicleVideoEncodings::valuesToUI() m_pItemsSelect[15]->setEnabled(false); } + if ( -1 != m_IndexIPQuantizationDelta ) + m_pItemsSlider[18]->setCurrentValue(g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].iIPQuantizationDelta); if ( g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264quantization > 0 ) { - m_pItemsSelect[8]->setSelection(0); - m_pItemsSlider[4]->setCurrentValue(g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264quantization); - m_pItemsSlider[4]->setEnabled(true); + if ( -1 != m_IndexCustomQuant ) + m_pItemsSelect[8]->setSelection(0); + if ( -1 != m_IndexQuantValue ) + { + m_pItemsSlider[4]->setCurrentValue(g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264quantization); + m_pItemsSlider[4]->setEnabled(true); + } m_pItemsSelect[14]->setEnabled(false); m_pItemsSelect[15]->setEnabled(false); } else { - m_pItemsSelect[8]->setSelection(1); - m_pItemsSlider[4]->setCurrentValue(-g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264quantization); - m_pItemsSlider[4]->setEnabled(false); + if ( -1 != m_IndexCustomQuant ) + m_pItemsSelect[8]->setSelection(1); + if ( -1 != m_IndexQuantValue ) + { + m_pItemsSlider[4]->setCurrentValue(-g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264quantization); + m_pItemsSlider[4]->setEnabled(false); + } m_pItemsSelect[14]->setEnabled(true); //m_pItemsSelect[15]->setEnabled(true); } - m_pItemsSelect[11]->setSelectedIndex((g_pCurrentModel->video_params.uVideoExtraFlags & VIDEO_FLAG_FILL_H264_SPT_TIMINGS)?1:0); + if ( -1 != m_IndexInsertH264SPSTimings ) + m_pItemsSelect[11]->setSelectedIndex(g_pCurrentModel->video_params.iInsertSPTVideoFramesTimings); + if ( -1 != m_IndexRemoveH264PPS ) + m_pItemsSelect[17]->setSelectedIndex(g_pCurrentModel->video_params.iRemovePPSVideoFrames); + m_pItemsSelect[12]->setSelectedIndex(g_pCurrentModel->video_params.iH264Slices-1); - if ( hardware_board_is_openipc(g_pCurrentModel->hwCapabilities.uBoardType) ) - { - m_pItemsSelect[12]->setSelectedIndex(0); - m_pItemsSelect[12]->setEnabled(false); - } + //if ( hardware_board_is_openipc(g_pCurrentModel->hwCapabilities.uBoardType) ) + //{ + // m_pItemsSelect[12]->setSelectedIndex(0); + // m_pItemsSelect[12]->setEnabled(false); + //} m_ShowBitrateWarning = false; u32 uRealDataRate = g_pCurrentModel->getLinkRealDataRate(0); @@ -356,23 +406,32 @@ void MenuVehicleVideoEncodings::sendVideoLinkProfile() (pProfile->uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_VIDEO_ADAPTIVE_H264_QUANTIZATION)?"On":"ROff", (pProfile->uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_VIDEO_ADAPTIVE_QUANTIZATION_STRENGTH_HIGH)?"Strength: High":"Strength: Low"); - pProfile->h264profile = m_pItemsSelect[4]->getSelectedIndex(); - pProfile->h264level = m_pItemsSelect[5]->getSelectedIndex(); - pProfile->h264refresh = m_pItemsSelect[6]->getSelectedIndex(); - pProfile->insertPPS = m_pItemsSelect[7]->getSelectedIndex()?1:0; - if ( 0 == m_pItemsSelect[8]->getSelectedIndex() ) - { - pProfile->h264quantization = m_pItemsSlider[4]->getCurrentValue(); - if ( pProfile->h264quantization < 5 ) - pProfile->h264quantization = 5; - } - else + if ( -1 != m_IndexH264Profile ) + pProfile->h264profile = m_pItemsSelect[4]->getSelectedIndex(); + if ( -1 != m_IndexH264Level ) + pProfile->h264level = m_pItemsSelect[5]->getSelectedIndex(); + if ( -1 != m_IndexH264Refresh ) + pProfile->h264refresh = m_pItemsSelect[6]->getSelectedIndex(); + + if ( (-1 != m_IndexCustomQuant) && (-1 != m_IndexQuantValue) ) { - if ( pProfile->h264quantization > 0 ) - pProfile->h264quantization = - pProfile->h264quantization; + if ( 0 == m_pItemsSelect[8]->getSelectedIndex() ) + { + pProfile->h264quantization = m_pItemsSlider[4]->getCurrentValue(); + if ( pProfile->h264quantization < 5 ) + pProfile->h264quantization = 5; + } + else + { + if ( pProfile->h264quantization > 0 ) + pProfile->h264quantization = - pProfile->h264quantization; + } } log_line("H264 quantization: %d", pProfile->h264quantization); + if ( -1 != m_IndexIPQuantizationDelta ) + pProfile->iIPQuantizationDelta = m_pItemsSlider[18]->getCurrentValue(); + int index = m_pItemsSelect[16]->getSelectedIndex(); if ( index == 0 ) pProfile->radio_datarate_video_bps = 0; @@ -398,8 +457,8 @@ void MenuVehicleVideoEncodings::sendVideoLinkProfile() if ( pProfile->h264level == g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264level ) if ( pProfile->h264profile == g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264profile ) if ( pProfile->h264refresh == g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264refresh ) - if ( pProfile->insertPPS == g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].insertPPS ) if ( pProfile->h264quantization == g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264quantization ) + if ( pProfile->iIPQuantizationDelta == g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].iIPQuantizationDelta ) return; // Propagate changes to lower video profiles @@ -416,6 +475,21 @@ void MenuVehicleVideoEncodings::sendVideoLinkProfile() valuesToUI(); } +void MenuVehicleVideoEncodings::sendVideoParams() +{ + video_parameters_t params; + memcpy(¶ms, &g_pCurrentModel->video_params, sizeof(video_parameters_t)); + + if ( -1 != m_IndexInsertH264PPS ) + params.iInsertPPSVideoFrames = m_pItemsSelect[7]->getSelectedIndex(); + if ( -1 != m_IndexInsertH264SPSTimings ) + params.iInsertSPTVideoFramesTimings = m_pItemsSelect[11]->getSelectedIndex(); + if ( -1 != m_IndexRemoveH264PPS ) + params.iRemovePPSVideoFrames = m_pItemsSelect[17]->getSelectedIndex(); + + if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_VIDEO_PARAMS, 0, (u8*)¶ms, sizeof(video_parameters_t)) ) + valuesToUI(); +} void MenuVehicleVideoEncodings::onSelectItem() { @@ -432,7 +506,6 @@ void MenuVehicleVideoEncodings::onSelectItem() if ( hardware_board_is_openipc(g_pCurrentModel->hwCapabilities.uBoardType) ) if ( (m_IndexHDMIOutput == m_SelectedIndex) || - (m_IndexH264Slices == m_SelectedIndex) || (m_IndexCustomQuant == m_SelectedIndex) || (m_IndexQuantValue == m_SelectedIndex) || (m_IndexEnableAdaptiveQuantization == m_SelectedIndex) || @@ -476,31 +549,26 @@ void MenuVehicleVideoEncodings::onSelectItem() return; } - if ( m_IndexH264Profile == m_SelectedIndex ) - sendVideoLinkProfile(); - if ( m_IndexH264Level == m_SelectedIndex ) + if ( (-1 != m_IndexH264Profile) && (m_IndexH264Profile == m_SelectedIndex) ) sendVideoLinkProfile(); - if ( m_IndexH264Refresh == m_SelectedIndex ) + if ( (-1 != m_IndexH264Level) && (m_IndexH264Level == m_SelectedIndex) ) sendVideoLinkProfile(); - if ( m_IndexH264Headers == m_SelectedIndex ) + if ( (-1 != m_IndexH264Refresh) && (m_IndexH264Refresh == m_SelectedIndex) ) sendVideoLinkProfile(); - if ( m_IndexH264SPSTimings == m_SelectedIndex ) + if ( (-1 != m_IndexRemoveH264PPS) && (m_IndexRemoveH264PPS == m_SelectedIndex) ) { - video_parameters_t paramsOld; - memcpy(¶msOld, &g_pCurrentModel->video_params, sizeof(video_parameters_t)); - int index = m_pItemsSelect[11]->getSelectedIndex(); - if ( index == 0 ) - g_pCurrentModel->video_params.uVideoExtraFlags &= ~(VIDEO_FLAG_FILL_H264_SPT_TIMINGS); - else - g_pCurrentModel->video_params.uVideoExtraFlags |= VIDEO_FLAG_FILL_H264_SPT_TIMINGS; - - video_parameters_t paramsNew; - memcpy(¶msNew, &g_pCurrentModel->video_params, sizeof(video_parameters_t)); - memcpy(&g_pCurrentModel->video_params, ¶msOld, sizeof(video_parameters_t)); - - if ( ! handle_commands_send_to_vehicle(COMMAND_ID_SET_VIDEO_PARAMS, 0, (u8*)¶msNew, sizeof(video_parameters_t)) ) - valuesToUI(); + sendVideoParams(); + return; + } + if ( (-1 != m_IndexInsertH264PPS) && (m_IndexInsertH264PPS == m_SelectedIndex) ) + { + sendVideoParams(); + return; + } + if ( (-1 != m_IndexInsertH264SPSTimings) && (m_IndexInsertH264SPSTimings == m_SelectedIndex) ) + { + sendVideoParams(); return; } @@ -519,7 +587,9 @@ void MenuVehicleVideoEncodings::onSelectItem() return; } - if ( (m_IndexCustomQuant == m_SelectedIndex || m_IndexQuantValue == m_SelectedIndex) && menu_check_current_model_ok_for_edit() ) + if ( (-1 != m_IndexCustomQuant) && (-1 != m_IndexQuantValue) ) + if ( (m_IndexCustomQuant == m_SelectedIndex) || (m_IndexQuantValue == m_SelectedIndex) ) + if ( menu_check_current_model_ok_for_edit() ) { u32 uParam = 0; if ( 0 == m_pItemsSelect[8]->getSelectedIndex() ) @@ -537,13 +607,19 @@ void MenuVehicleVideoEncodings::onSelectItem() return; } - if ( m_IndexEnableAdaptiveQuantization == m_SelectedIndex || - m_IndexAdaptiveH264QuantizationStrength == m_SelectedIndex ) + if ( (-1 != m_IndexIPQuantizationDelta) && (m_IndexIPQuantizationDelta == m_SelectedIndex) ) { sendVideoLinkProfile(); + return; + } + if ( (m_IndexEnableAdaptiveQuantization == m_SelectedIndex) || + (m_IndexAdaptiveH264QuantizationStrength == m_SelectedIndex) ) + { + sendVideoLinkProfile(); + return; } - if ( m_IndexResetParams == m_SelectedIndex && menu_check_current_model_ok_for_edit() ) + if ( (m_IndexResetParams == m_SelectedIndex) && menu_check_current_model_ok_for_edit() ) { // Reset expert params if ( ! handle_commands_send_to_vehicle(COMMAND_ID_RESET_VIDEO_LINK_PROFILE, 0, NULL, 0) ) diff --git a/code/r_central/menu/menu_vehicle_video_encodings.h b/code/r_central/menu/menu_vehicle_video_encodings.h index e7bb79a1..3aa8b0ae 100644 --- a/code/r_central/menu/menu_vehicle_video_encodings.h +++ b/code/r_central/menu/menu_vehicle_video_encodings.h @@ -14,12 +14,14 @@ class MenuVehicleVideoEncodings: public Menu private: void sendVideoLinkProfile(); + void sendVideoParams(); int m_IndexPacketSize, m_IndexBlockPackets, m_IndexBlockFECs, m_IndexECSchemeSpread; int m_IndexDataRate; - int m_IndexH264Profile, m_IndexH264Level, m_IndexH264Refresh, m_IndexH264Headers; - int m_IndexH264SPSTimings; + int m_IndexH264Profile, m_IndexH264Level, m_IndexH264Refresh; + int m_IndexRemoveH264PPS, m_IndexInsertH264PPS, m_IndexInsertH264SPSTimings; int m_IndexH264Slices; + int m_IndexIPQuantizationDelta; int m_IndexCustomQuant, m_IndexQuantValue; int m_IndexResetParams; int m_IndexEnableAdaptiveQuantization; diff --git a/code/r_central/osd/osd.cpp b/code/r_central/osd/osd.cpp index 868b4398..b2fcf61f 100644 --- a/code/r_central/osd/osd.cpp +++ b/code/r_central/osd/osd.cpp @@ -253,46 +253,53 @@ float osd_show_mah(float x, float y, u32 mah, bool bRightAlign) float _osd_show_gps(float x, float y, bool bMultiLine) { + int iOSVehicleDataSourceIndex = osd_get_current_data_source_vehicle_index(); + char szBuff[32]; float height_text = osd_getFontHeight(); float height_text_big = osd_getFontHeightBig(); float x0 = x; float w = 0; - if ( NULL == g_pCurrentModel || (0 == g_pCurrentModel->iGPSCount) || (!g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].bGotFCTelemetry) ) + if ( NULL == g_pCurrentModel || (0 == g_pCurrentModel->iGPSCount) || (!g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].bGotFCTelemetry) ) { x += osd_show_value(x,y, "No GPS", g_idFontOSD); x += osd_getSpacingH(); return x-x0; } - if ( g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.gps_fix_type >= GPS_FIX_TYPE_3D_FIX || (( g_TimeNow / 300 ) % 3) != 0 ) + if ( g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].headerFCTelemetry.gps_fix_type >= GPS_FIX_TYPE_3D_FIX || (( g_TimeNow / 300 ) % 3) != 0 ) g_pRenderEngine->drawIcon(x,y, 0.8*height_text_big/g_pRenderEngine->getAspectRatio(), 0.8*height_text_big, g_idIconGPS); x += 1.0*height_text_big/g_pRenderEngine->getAspectRatio(); - if ( g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.gps_fix_type >= GPS_FIX_TYPE_3D_FIX ) + if ( g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].headerFCTelemetry.gps_fix_type >= GPS_FIX_TYPE_3D_FIX ) g_pRenderEngine->drawText(x-0.3*height_text_big, y-0.7*osd_getSpacingV(), g_idFontOSDSmall, "3D"); - sprintf(szBuff, "%d", g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.satelites); + sprintf(szBuff, "%d", g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].headerFCTelemetry.satelites); w = osd_show_value(x,y, szBuff, g_idFontOSDBig); x += w + 0.5*osd_getSpacingH(); - if ( bMultiLine ) - { - osd_show_value_centered((x0+x)*0.5, y+height_text_big-height_text*0.1, "HDOP", g_idFontOSDSmall); - sprintf(szBuff, "%.1f", g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.hdop/100.0); - osd_show_value_centered((x0+x)*0.5, y+height_text_big-height_text*0.1+osd_getFontHeightSmall(), szBuff, g_idFontOSDSmall); - } - else + if ( pairing_isStarted() ) + if ( g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].pModel->telemetry_params.fc_telemetry_type != TELEMETRY_TYPE_NONE ) + if ( vehicle_runtime_has_received_fc_telemetry(g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].uVehicleId) ) + if ( g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].pModel->is_spectator || g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].bPairedConfirmed ) { - w = osd_show_value(x, y-height_text*0.1, "HDOP", g_idFontOSDSmall); - sprintf(szBuff, "%.1f", g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.hdop/100.0); - osd_show_value(x, y + osd_getFontHeightSmall(), szBuff, g_idFontOSDSmall); - x += w; - x += osd_getSpacingH(); + if ( bMultiLine ) + { + osd_show_value_centered((x0+x)*0.5, y+height_text_big-height_text*0.1, "HDOP", g_idFontOSDSmall); + sprintf(szBuff, "%.1f", g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].headerFCTelemetry.hdop/100.0); + osd_show_value_centered((x0+x)*0.5, y+height_text_big-height_text*0.1+osd_getFontHeightSmall(), szBuff, g_idFontOSDSmall); + } + else + { + w = osd_show_value(x, y-height_text*0.1, "HDOP", g_idFontOSDSmall); + sprintf(szBuff, "%.1f", g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].headerFCTelemetry.hdop/100.0); + osd_show_value(x, y + osd_getFontHeightSmall(), szBuff, g_idFontOSDSmall); + x += w; + x += osd_getSpacingH(); + } } - - u16 hdop2 = (((u16)g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.extra_info[3])<<8) + ((u16)g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.extra_info[4]); + u16 hdop2 = (((u16)g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].headerFCTelemetry.extra_info[3])<<8) + ((u16)g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.extra_info[4]); bool bShowMore = false; //if ( (g_pCurrentModel->iGPSCount > 1) || ((hdop2 != 0xFFFF) && (hdop2 != 0)) || ((satelites2 != 0xFF)&&(satelites2 != 0)) ) @@ -307,41 +314,46 @@ float _osd_show_gps(float x, float y, bool bMultiLine) float x1 = x; - if ( ((g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.extra_info[2] >= GPS_FIX_TYPE_3D_FIX) && (g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.extra_info[2] != 0xFF)) || (( g_TimeNow / 300 ) % 3) != 0 ) + if ( ((g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].headerFCTelemetry.extra_info[2] >= GPS_FIX_TYPE_3D_FIX) && (g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.extra_info[2] != 0xFF)) || (( g_TimeNow / 300 ) % 3) != 0 ) g_pRenderEngine->drawIcon(x,y, 0.8*height_text_big/g_pRenderEngine->getAspectRatio(), 0.8*height_text_big, g_idIconGPS); x += 1.0*height_text_big/g_pRenderEngine->getAspectRatio(); - if ( (g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.extra_info[2] >= GPS_FIX_TYPE_3D_FIX) && (g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.extra_info[2] != 0xFF) ) + if ( (g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].headerFCTelemetry.extra_info[2] >= GPS_FIX_TYPE_3D_FIX) && (g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.extra_info[2] != 0xFF) ) g_pRenderEngine->drawText(x-0.3*height_text_big, y-0.7*osd_getSpacingV(), g_idFontOSDSmall, "3D"); - if ( g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.extra_info[1] == 0xFF ) + if ( g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].headerFCTelemetry.extra_info[1] == 0xFF ) strcpy(szBuff, "N/A"); else - sprintf(szBuff, "%d", g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerFCTelemetry.extra_info[1]); + sprintf(szBuff, "%d", g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].headerFCTelemetry.extra_info[1]); w = osd_show_value(x,y, szBuff, g_idFontOSDBig); x += w + 0.5*osd_getSpacingH(); - if ( bMultiLine ) + if ( pairing_isStarted() ) + if ( g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].pModel->telemetry_params.fc_telemetry_type != TELEMETRY_TYPE_NONE ) + if ( vehicle_runtime_has_received_fc_telemetry(g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].uVehicleId) ) + if ( g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].pModel->is_spectator || g_VehiclesRuntimeInfo[iOSVehicleDataSourceIndex].bPairedConfirmed ) { - osd_show_value_centered((x1+x)*0.5, y+height_text_big-height_text*0.1, "HDOP", g_idFontOSDSmall); - if ( hdop2 == 0xFFFF ) - strcpy(szBuff, "---"); - else - sprintf(szBuff, "%.1f", hdop2/100.0); - osd_show_value_centered((x1+x)*0.5, y+height_text_big-height_text*0.1+osd_getFontHeightSmall(), szBuff, g_idFontOSDSmall); - } - else - { - w = osd_show_value(x, y-height_text*0.1, "HDOP", g_idFontOSDSmall); - if ( hdop2 == 0xFFFF ) - strcpy(szBuff, "---"); + if ( bMultiLine ) + { + osd_show_value_centered((x1+x)*0.5, y+height_text_big-height_text*0.1, "HDOP", g_idFontOSDSmall); + if ( hdop2 == 0xFFFF ) + strcpy(szBuff, "---"); + else + sprintf(szBuff, "%.1f", hdop2/100.0); + osd_show_value_centered((x1+x)*0.5, y+height_text_big-height_text*0.1+osd_getFontHeightSmall(), szBuff, g_idFontOSDSmall); + } else - sprintf(szBuff, "%.1f", hdop2/100.0); - osd_show_value(x, y + osd_getFontHeightSmall(), szBuff, g_idFontOSDSmall); - x += w; - x += osd_getSpacingH(); + { + w = osd_show_value(x, y-height_text*0.1, "HDOP", g_idFontOSDSmall); + if ( hdop2 == 0xFFFF ) + strcpy(szBuff, "---"); + else + sprintf(szBuff, "%.1f", hdop2/100.0); + osd_show_value(x, y + osd_getFontHeightSmall(), szBuff, g_idFontOSDSmall); + x += w; + x += osd_getSpacingH(); + } } - return x- x0; } diff --git a/code/r_central/osd/osd_debug_stats.cpp b/code/r_central/osd/osd_debug_stats.cpp index fe92e52a..e5a291c9 100644 --- a/code/r_central/osd/osd_debug_stats.cpp +++ b/code/r_central/osd/osd_debug_stats.cpp @@ -222,6 +222,10 @@ float _osd_render_debug_stats_graph_bars(float xPos, float yPos, float hGraph, f float fHeightPixel = g_pRenderEngine->getPixelHeight(); float fWidthBar = fWidth / iCountValues; + g_pRenderEngine->setStrokeSize(1.0); + g_pRenderEngine->drawLine(xPos, yPos-g_pRenderEngine->getPixelHeight(), xPos+fWidth, yPos-g_pRenderEngine->getPixelHeight()); + g_pRenderEngine->drawLine(xPos, yPos+hGraph+g_pRenderEngine->getPixelHeight(), xPos+fWidth, yPos+hGraph+g_pRenderEngine->getPixelHeight()); + for( int i=0; iiDeltaIndexFromVehicle; if ( iIndexVehicleStart < 0 ) @@ -578,7 +581,7 @@ void osd_render_debug_stats() /**/ //-------------------------------------------- - if ( pP->uDebugStatsFlags & CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_VIDEO_DATA_PACKETS ) + if ( pP->uDebugStatsFlags & CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_TX_PACKETS ) { for( int i=0; iuRxVideoPackets[i+iStartIntervals][0]; - uTmp2[i]+= pCRTInfo->uRxVideoECPackets[i+iStartIntervals][0]; - uTmp3[i]+= 5*pCRTInfo->uRxVideoRetrPackets[i+iStartIntervals][0]; + uTmp[i] += pCRTInfo->uRxVideoPackets[i+iStartIntervals][k]; + uTmp2[i]+= 5*pCRTInfo->uRxDataPackets[i+iStartIntervals][k]; + uTmp3[i]+= 5*pCRTInfo->uRxHighPriorityPackets[i+iStartIntervals][k]; } + if ( uTmp3[i] > 0 ) + if ( uTmp3[i] < uTmp[i]/4 ) + uTmp3[i] = uTmp[i]/4; + } + g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Rx Video/Data/High Priority Packets"); + y += height_text*1.3; + y += _osd_render_debug_stats_graph_bars(fGraphXStart, y, hGraphSmall, fWidthGraph, uTmp, uTmp2, uTmp3, iCountIntervals, 1); + y += height_text_small; + iCountGraphs++; + + for( int i=0; iuTxPackets[i+iStartIntervals]; + uTmp2[i] = 0; + uTmp3[i] = pCRTInfo->uTxHighPriorityPackets[i+iStartIntervals]; } - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Rx Video/EC/Retr Packets"); + g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Tx Regular/High Priority Packets"); y += height_text*1.3; y += _osd_render_debug_stats_graph_bars(fGraphXStart, y, hGraphSmall, fWidthGraph, uTmp, uTmp2, uTmp3, iCountIntervals, 1); y += height_text_small; @@ -600,17 +618,43 @@ void osd_render_debug_stats() } //-------------------------------------------- - if ( pP->uDebugStatsFlags & CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_H264265_FRAMES ) - { - for( int i=0; iuDebugStatsFlags & CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_AIR_GAPS ) { - uTmp[i] = pCRTInfo->uRecvEndOfFrame[i+iStartIntervals]; + for( int i=0; iuRxMaxAirgapSlots[i+iStartIntervals]; + } + g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Rx Max air gaps"); + y += height_text*1.3; + //y += _osd_render_debug_stats_graph_values(fGraphXStart, y, hGraphSmall, fWidthGraph, uTmp, iCountIntervals); + y += _osd_render_debug_stats_graph_bars(fGraphXStart, y, hGraphSmall, fWidthGraph, uTmp, NULL, NULL, iCountIntervals, 0); + y += height_text_small; + iCountGraphs++; + + for( int i=0; iuRxMaxAirgapSlots2[i+iStartIntervals]; + } + g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Rx Max air gaps (2)"); + y += height_text*1.3; + //y += _osd_render_debug_stats_graph_values(fGraphXStart, y, hGraphSmall, fWidthGraph, uTmp, iCountIntervals); + y += _osd_render_debug_stats_graph_bars(fGraphXStart, y, hGraphSmall, fWidthGraph, uTmp, NULL, NULL, iCountIntervals, 0); + y += height_text_small; + iCountGraphs++; } - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Received P/I frames end"); - y += height_text*1.3; - y += _osd_render_debug_stats_graph_values(fGraphXStart, y, hGraphSmall, fWidthGraph, uTmp, iCountIntervals); - y += height_text_small; - iCountGraphs++; + + //-------------------------------------------- + if ( pP->uDebugStatsFlags & CTRL_RT_DEBUG_INFO_FLAG_SHOW_RX_H264265_FRAMES ) + { + for( int i=0; iuRecvEndOfFrame[i+iStartIntervals]; + } + g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Received P/I frames end"); + y += height_text*1.3; + y += _osd_render_debug_stats_graph_values(fGraphXStart, y, hGraphSmall, fWidthGraph, uTmp, iCountIntervals); + y += height_text_small; + iCountGraphs++; } //----------------------------------------------- diff --git a/code/r_central/osd/osd_links.cpp b/code/r_central/osd/osd_links.cpp index d0eb36d6..49e5537c 100644 --- a/code/r_central/osd/osd_links.cpp +++ b/code/r_central/osd/osd_links.cpp @@ -436,6 +436,7 @@ float _osd_show_local_radio_link_new(float xPos, float yPos, int iLocalRadioLink bool bDRChanged = false; if ( g_bOSDElementChangeNotification ) + if ( pModelToUse->bDeveloperMode ) if ( pModelToUse->osd_params.osd_flags3[pModelToUse->osd_params.layout] & OSD_FLAG3_HIGHLIGHT_CHANGING_ELEMENTS ) if ( g_TimeNow < s_uLastOSDVehRadioLinkInterfacesRecvDataratesChangeTimes[iVehicleRadioLinkId][i] + g_uOSDElementChangeTimeout ) bDRChanged = true; @@ -472,7 +473,7 @@ float _osd_show_local_radio_link_new(float xPos, float yPos, int iLocalRadioLink if ( bShowLine1AsError ) g_pRenderEngine->setColors(get_Color_IconError()); - if ( bDRChanged && g_bOSDElementChangeNotification ) + if ( bDRChanged && g_bOSDElementChangeNotification && pModelToUse->bDeveloperMode ) if ( pModelToUse->osd_params.osd_flags3[pModelToUse->osd_params.layout] & OSD_FLAG3_HIGHLIGHT_CHANGING_ELEMENTS ) osd_set_colors_text(get_Color_OSDElementChanged()); @@ -629,6 +630,7 @@ float _osd_show_local_radio_link_new(float xPos, float yPos, int iLocalRadioLink bool bDRChanged = false; if ( g_bOSDElementChangeNotification ) + if ( pModelToUse->bDeveloperMode ) if ( pModelToUse->osd_params.osd_flags3[pModelToUse->osd_params.layout] & OSD_FLAG3_HIGHLIGHT_CHANGING_ELEMENTS ) if ( g_TimeNow < s_uLastOSDRadioLinkInterfacesRecvDataratesChangeTimes[iLocalRadioLinkId][i] + g_uOSDElementChangeTimeout ) bDRChanged = true; @@ -701,7 +703,7 @@ float _osd_show_local_radio_link_new(float xPos, float yPos, int iLocalRadioLink if ( bShowLine1AsError ) g_pRenderEngine->setColors(get_Color_IconError()); - if ( bDRChanged && g_bOSDElementChangeNotification ) + if ( bDRChanged && g_bOSDElementChangeNotification && pModelToUse->bDeveloperMode ) if ( pModelToUse->osd_params.osd_flags3[pModelToUse->osd_params.layout] & OSD_FLAG3_HIGHLIGHT_CHANGING_ELEMENTS ) osd_set_colors_text(get_Color_OSDElementChanged()); diff --git a/code/r_central/osd/osd_stats.cpp b/code/r_central/osd/osd_stats.cpp index 676b4aa9..5f3c78c5 100644 --- a/code/r_central/osd/osd_stats.cpp +++ b/code/r_central/osd/osd_stats.cpp @@ -84,7 +84,6 @@ static u32 s_uOSDSnapshotHistoryDiscardedPackets[SNAPSHOT_HISTORY_SIZE]; static shared_mem_radio_stats s_OSDSnapshot_RadioStats; static shared_mem_video_stream_stats_rx_processors s_OSDSnapshot_VideoDecodeStats; -static shared_mem_video_stream_stats_history_rx_processors s_OSDSnapshot_VideoDecodeHist; #define MAX_OSD_COLUMNS 10 @@ -109,11 +108,6 @@ static float s_fOSDStatsWindowsMinimBoxHeight = 0.0; static float s_fOSDVideoDecodeWidthZoom = 1.0; -static u32 s_uOSDMaxFrameDeviationCamera = 0; -static u32 s_uOSDMaxFrameDeviationTx = 0; -static u32 s_uOSDMaxFrameDeviationRx = 0; -static u32 s_uOSDMaxFrameDeviationPlayer = 0; - void _osd_stats_draw_line(float xLeft, float xRight, float y, u32 uFontId, const char* szTextLeft, const char* szTextRight) { g_pRenderEngine->drawText(xLeft, y, uFontId, szTextLeft); @@ -124,13 +118,9 @@ void _osd_stats_draw_line(float xLeft, float xRight, float y, u32 uFontId, const void osd_stats_init() { s_uStatsRenderRCCount = 0; - s_uOSDMaxFrameDeviationCamera = 0; - s_uOSDMaxFrameDeviationTx = 0; - s_uOSDMaxFrameDeviationRx = 0; - s_uOSDMaxFrameDeviationPlayer = 0; } -void osd_stats_video_decode_snapshot_update(int iDeveloperMode, shared_mem_radio_stats* pSM_RadioStats, shared_mem_video_stream_stats* pVDS, shared_mem_video_stream_stats_history* pVDSH, shared_mem_video_stream_stats_rx_processors* pSM_VideoStats, shared_mem_video_stream_stats_history_rx_processors* pSM_VideoHistoryStats) +void osd_stats_video_decode_snapshot_update(int iDeveloperMode, shared_mem_radio_stats* pSM_RadioStats, shared_mem_video_stream_stats* pVDS, shared_mem_video_stream_stats_rx_processors* pSM_VideoStats) { ControllerSettings* pCS = get_ControllerSettings(); @@ -233,7 +223,7 @@ void osd_stats_video_decode_snapshot_update(int iDeveloperMode, shared_mem_radio */ } -float osd_render_stats_video_decode_get_height(int iDeveloperMode, bool bIsSnapshot, shared_mem_radio_stats* pSM_RadioStats, shared_mem_video_stream_stats_rx_processors* pSM_VideoStats, shared_mem_video_stream_stats_history_rx_processors* pSM_VideoHistoryStats, float scale) +float osd_render_stats_video_decode_get_height(int iDeveloperMode, bool bIsSnapshot, shared_mem_radio_stats* pSM_RadioStats, shared_mem_video_stream_stats_rx_processors* pSM_VideoStats, float scale) { Model* pActiveModel = osd_get_current_data_source_vehicle_model(); @@ -242,10 +232,10 @@ float osd_render_stats_video_decode_get_height(int iDeveloperMode, bool bIsSnaps float height_text = g_pRenderEngine->textHeight(s_idFontStats); float height_text_small = g_pRenderEngine->textHeight(s_idFontStatsSmall); - float hGraph = 0.04; - float hGraphHistory = 2.2*height_text; + float hGraph = 3.0*height_text; + float hGraphHistory = 2.5*height_text; - float height = 2.0 *s_fOSDStatsMargin*1.0; + float height = 2.0 *s_fOSDStatsMargin*1.1 + 0.9*height_text*s_OSDStatsLineSpacing; bool bIsMinimal = false; bool bIsCompact = false; @@ -261,82 +251,25 @@ float osd_render_stats_video_decode_get_height(int iDeveloperMode, bool bIsSnaps else bIsNormal = true; - // Title - //if ( ! bIsMinimal ) - height += height_text*s_OSDStatsLineSpacing; - // Stream info - if ( bIsMinimal || bIsCompact || bIsNormal || bIsExtended ) - height += height_text_small*s_OSDStatsLineSpacing; + height += height_text*s_OSDStatsLineSpacing; - // EC Scheme - if ( bIsCompact || bIsNormal || bIsExtended ) - height += height_text*s_OSDStatsLineSpacing; - - // Dynamic Params + // Stream info 2 if ( bIsCompact || bIsNormal || bIsExtended ) - height += 7.2*height_text*s_OSDStatsLineSpacing; - if ( bIsNormal || bIsExtended ) - height += height_text*s_OSDStatsLineSpacing; - - // Rx packets Buffers - if ( bIsExtended ) - { - float hBar = 0.014*scale; - height += hBar + height_text; - } - - // History graph - height += height_text_small*1.2; - height += hGraphHistory; - height += height_text_small*0.3; - - if ( iDeveloperMode ) - if ( bIsExtended ) - { - // Max EC packets used per interval - height += height_text_small*1.2; - height += hGraph*0.6; - - { - // History gap graph - height += height_text_small*1.2; - height += hGraph*0.6; - - // Pending good blocks graph - height += height_text_small*1.2; - height += hGraph*0.8; - } - } + height += height_text_small*s_OSDStatsLineSpacing; + // Retr, adaptive if ( bIsNormal || bIsExtended ) - height += height_text * s_OSDStatsLineSpacing; - if ( bIsExtended ) - height += height_text * s_OSDStatsLineSpacing; - - { - if ( bIsNormal || bIsExtended ) - height += height_text * s_OSDStatsLineSpacing; - if ( bIsExtended ) - height += 2.0 * height_text * s_OSDStatsLineSpacing; + height += 2.0*height_text*s_OSDStatsLineSpacing; - // History requested retransmissions - - if ( bIsNormal || bIsExtended ) - if ( iDeveloperMode ) - { - height += height_text_small*2.0; - height += hGraph; - } + // Graph + height += 1.5*height_text_small; + height += hGraphHistory; - // Dev requested Retransmissions - if ( iDeveloperMode ) - height += 6.0*height_text*s_OSDStatsLineSpacing; - } return height; } -float osd_render_stats_video_decode_get_width(int iDeveloperMode, bool bIsSnapshot, shared_mem_radio_stats* pSM_RadioStats, shared_mem_video_stream_stats_rx_processors* pSM_VideoStats, shared_mem_video_stream_stats_history_rx_processors* pSM_VideoHistoryStats, float scale) +float osd_render_stats_video_decode_get_width(int iDeveloperMode, bool bIsSnapshot, shared_mem_radio_stats* pSM_RadioStats, shared_mem_video_stream_stats_rx_processors* pSM_VideoStats, float scale) { if ( g_fOSDStatsForcePanelWidth > 0.01 ) { @@ -352,9 +285,9 @@ float osd_render_stats_video_decode_get_width(int iDeveloperMode, bool bIsSnapsh return width; } -float osd_render_stats_video_decode(float xPos, float yPos, int iDeveloperMode, bool bIsSnapshot, shared_mem_radio_stats* pSM_RadioStats, shared_mem_video_stream_stats_rx_processors* pSM_VideoStats, shared_mem_video_stream_stats_history_rx_processors* pSM_VideoHistoryStats, float scale) +float osd_render_stats_video_decode(float xPos, float yPos, int iDeveloperMode, bool bIsSnapshot, shared_mem_radio_stats* pSM_RadioStats, shared_mem_video_stream_stats_rx_processors* pSM_VideoStats, float scale) { - if ( NULL == osd_get_current_data_source_vehicle_model() || NULL == pSM_RadioStats || NULL == pSM_VideoStats || NULL == pSM_VideoHistoryStats ) + if ( NULL == osd_get_current_data_source_vehicle_model() || NULL == pSM_RadioStats || NULL == pSM_VideoStats ) return 0.0; Model* pActiveModel = osd_get_current_data_source_vehicle_model(); @@ -364,14 +297,12 @@ float osd_render_stats_video_decode(float xPos, float yPos, int iDeveloperMode, return 0.0; shared_mem_video_stream_stats* pVDS = NULL; - shared_mem_video_stream_stats_history* pVDSH = NULL; for( int i=0; ivideo_streams[i].uVehicleId == uActiveVehicleId ) { pVDS = &(pSM_VideoStats->video_streams[i]); - pVDSH = &(pSM_VideoHistoryStats->video_streams[i]); break; } } @@ -379,7 +310,7 @@ float osd_render_stats_video_decode(float xPos, float yPos, int iDeveloperMode, if ( (NULL == pVDS) || (NULL == pActiveModel) ) return 0.0; - + ControllerSettings* pCS = get_ControllerSettings(); int iIndexRouterRuntimeInfo = -1; for( int i=0; iradio_streams[0][STREAM_ID_VIDEO_1].rxBytesPerSec*8/1000.0/1000.0; + float fReceivedVideoMbps = pSM_RadioStats->radio_streams[0][STREAM_ID_VIDEO_1].rxBytesPerSec*8/1000.0/1000.0; for( int i=0; iradio_streams[i][STREAM_ID_VIDEO_1].uVehicleId == pActiveModel->uVehicleId ) { - frecv_video_mbps = pSM_RadioStats->radio_streams[i][STREAM_ID_VIDEO_1].rxBytesPerSec*8/1000.0/1000.0; + fReceivedVideoMbps = pSM_RadioStats->radio_streams[i][STREAM_ID_VIDEO_1].rxBytesPerSec*8/1000.0/1000.0; break; } } @@ -420,11 +351,11 @@ float osd_render_stats_video_decode(float xPos, float yPos, int iDeveloperMode, s_iPeakCountRender++; float height_text = g_pRenderEngine->textHeight(s_idFontStats); float height_text_small = g_pRenderEngine->textHeight(s_idFontStatsSmall); - float hGraph = 0.04; - float hGraphHistory = 2.2*height_text; + float hGraph = 3.0*height_text; + float hGraphHistory = 2.5*height_text; - float width = osd_render_stats_video_decode_get_width(iDeveloperMode, bIsSnapshot, pSM_RadioStats, pSM_VideoStats, pSM_VideoHistoryStats, scale); - float height = osd_render_stats_video_decode_get_height(iDeveloperMode, bIsSnapshot, pSM_RadioStats, pSM_VideoStats, pSM_VideoHistoryStats, scale); + float width = osd_render_stats_video_decode_get_width(iDeveloperMode, bIsSnapshot, pSM_RadioStats, pSM_VideoStats, scale); + float height = osd_render_stats_video_decode_get_height(iDeveloperMode, bIsSnapshot, pSM_RadioStats, pSM_VideoStats, scale); float wPixel = g_pRenderEngine->getPixelWidth(); char szBuff[64]; @@ -444,112 +375,140 @@ float osd_render_stats_video_decode(float xPos, float yPos, int iDeveloperMode, // ------------------------- // Begin - Title - //if ( ! bIsMinimal ) + if ( bIsSnapshot ) + { + sprintf(szBuff, "Snapshot %d", s_uOSDSnapshotCount); + g_pRenderEngine->drawText(xPos, yPos, s_idFontStats, szBuff); + } + else { - if ( bIsSnapshot ) + //if ( ! (pActiveModel->osd_params.osd_flags2[osd_get_current_layout_index()] & OSD_FLAG2_SHOW_COMPACT_VIDEO_DECODE_STATS) ) + g_pRenderEngine->drawText(xPos, yPos, s_idFontStats, "Video Stream"); + + szBuff[0] = 0; + char szMode[32]; + //strcpy(szMode, str_get_video_profile_name(pVDS->video_link_profile & 0x0F)); + //if ( pActiveModel->osd_params.osd_flags2[osd_get_current_layout_index()] & OSD_FLAG2_SHOW_COMPACT_VIDEO_DECODE_STATS ) + // szMode[0] = 0; + strcpy(szMode, str_get_video_profile_name(pVDS->PHVF.uCurrentVideoLinkProfile)); + int diffEC = pVDS->PHVF.uCurrentBlockECPackets - pActiveModel->video_link_profiles[pVDS->PHVF.uCurrentVideoLinkProfile].block_fecs; + + if ( diffEC > 0 ) { - sprintf(szBuff, "Snapshot %d", s_uOSDSnapshotCount); - g_pRenderEngine->drawText(xPos, yPos, s_idFontStats, szBuff); + char szTmp[16]; + sprintf(szTmp, "-%d", diffEC); + strcat(szMode, szTmp); } - else - { - //if ( ! (pActiveModel->osd_params.osd_flags2[osd_get_current_layout_index()] & OSD_FLAG2_SHOW_COMPACT_VIDEO_DECODE_STATS) ) - g_pRenderEngine->drawText(xPos, yPos, s_idFontStats, "Video Stream"); - - szBuff[0] = 0; - char szMode[32]; - //strcpy(szMode, str_get_video_profile_name(pVDS->video_link_profile & 0x0F)); - //if ( pActiveModel->osd_params.osd_flags2[osd_get_current_layout_index()] & OSD_FLAG2_SHOW_COMPACT_VIDEO_DECODE_STATS ) - // szMode[0] = 0; - strcpy(szMode, str_get_video_profile_name(pVDS->PHVF.uCurrentVideoLinkProfile)); - int diffEC = pVDS->PHVF.uCurrentBlockECPackets - pActiveModel->video_link_profiles[pVDS->PHVF.uCurrentVideoLinkProfile].block_fecs; - - if ( diffEC > 0 ) - { - char szTmp[16]; - sprintf(szTmp, "-%d", diffEC); - strcat(szMode, szTmp); - } - if ( pVDS->PHVF.uVideoStatusFlags2 & VIDEO_STATUS_FLAGS2_IS_ON_LOWER_BITRATE ) - strcat(szMode, "-"); - if ( pVDS->uCurrentVideoProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ONE_WAY_FIXED_VIDEO ) - strcat(szMode, "-1Way"); + if ( pVDS->PHVF.uVideoStatusFlags2 & VIDEO_STATUS_FLAGS2_IS_ON_LOWER_BITRATE ) + strcat(szMode, "-"); + if ( pVDS->uCurrentVideoProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ONE_WAY_FIXED_VIDEO ) + strcat(szMode, "-1Way"); - sprintf(szBuff, "%s %.1f Mbs", szMode, frecv_video_mbps); - if ( pVDS->PHVF.uVideoStatusFlags2 & VIDEO_STATUS_FLAGS2_IS_ON_LOWER_BITRATE ) - sprintf(szBuff, "%s- %.1f Mbs", szMode, frecv_video_mbps); + sprintf(szBuff, "%s %.1f Mbs", szMode, fReceivedVideoMbps); + if ( pVDS->PHVF.uVideoStatusFlags2 & VIDEO_STATUS_FLAGS2_IS_ON_LOWER_BITRATE ) + sprintf(szBuff, "%s- %.1f Mbs", szMode, fReceivedVideoMbps); - if ( g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].bGotRubyTelemetryInfo ) - { - sprintf(szBuff, "%s %.1f (%.1f) Mbs", szMode, frecv_video_mbps, g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerRubyTelemetryExtended.downlink_tx_video_bitrate_bps/1000.0/1000.0); - if ( pVDS->PHVF.uVideoStatusFlags2 & VIDEO_STATUS_FLAGS2_IS_ON_LOWER_BITRATE ) - sprintf(szBuff, "%s- %.1f (%.1f) Mbs", szMode, frecv_video_mbps, g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerRubyTelemetryExtended.downlink_tx_video_bitrate_bps/1000.0/1000.0); - } - u32 uRealDataRate = pActiveModel->getLinkRealDataRate(0); - if ( pActiveModel->radioLinksParams.links_count > 1 ) - if ( pActiveModel->getLinkRealDataRate(1) > uRealDataRate ) - uRealDataRate = pActiveModel->getLinkRealDataRate(1); + if ( g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].bGotRubyTelemetryInfo ) + { + sprintf(szBuff, "%s %.1f (%.1f) Mbs", szMode, fReceivedVideoMbps, g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerRubyTelemetryExtended.downlink_tx_video_bitrate_bps/1000.0/1000.0); + if ( pVDS->PHVF.uVideoStatusFlags2 & VIDEO_STATUS_FLAGS2_IS_ON_LOWER_BITRATE ) + sprintf(szBuff, "%s- %.1f (%.1f) Mbs", szMode, fReceivedVideoMbps, g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].headerRubyTelemetryExtended.downlink_tx_video_bitrate_bps/1000.0/1000.0); + } + u32 uRealDataRate = pActiveModel->getLinkRealDataRate(0); + if ( pActiveModel->radioLinksParams.links_count > 1 ) + if ( pActiveModel->getLinkRealDataRate(1) > uRealDataRate ) + uRealDataRate = pActiveModel->getLinkRealDataRate(1); - if ( frecv_video_mbps*1000*1000 >= (float)(uRealDataRate) * DEFAULT_VIDEO_LINK_MAX_LOAD_PERCENT / 100.0 ) - g_pRenderEngine->setColors(get_Color_IconWarning()); - - if ( g_bHasVideoDataOverloadAlarm && (g_TimeLastVideoDataOverloadAlarm > 0) && (g_TimeNow < g_TimeLastVideoDataOverloadAlarm + 5000) ) - g_pRenderEngine->setColors(get_Color_IconError()); + if ( fReceivedVideoMbps*1000*1000 >= (float)(uRealDataRate) * DEFAULT_VIDEO_LINK_MAX_LOAD_PERCENT / 100.0 ) + g_pRenderEngine->setColors(get_Color_IconWarning()); + + if ( g_bHasVideoDataOverloadAlarm && (g_TimeLastVideoDataOverloadAlarm > 0) && (g_TimeNow < g_TimeLastVideoDataOverloadAlarm + 5000) ) + g_pRenderEngine->setColors(get_Color_IconError()); - if ( ! (pActiveModel->osd_params.osd_flags2[osd_get_current_layout_index()] & OSD_FLAG2_SHOW_COMPACT_VIDEO_DECODE_STATS) ) - { - osd_show_value_left(xPos+width,yPos, szBuff, s_idFontStats); - //y += height_text*1.3*s_OSDStatsLineSpacing; - } - else - osd_show_value_left(xPos+width,yPos, szBuff, s_idFontStatsSmall); + if ( ! (pActiveModel->osd_params.osd_flags2[osd_get_current_layout_index()] & OSD_FLAG2_SHOW_COMPACT_VIDEO_DECODE_STATS) ) + { + osd_show_value_left(xPos+width,yPos, szBuff, s_idFontStats); + //y += height_text*1.3*s_OSDStatsLineSpacing; } - - y += height_text*s_OSDStatsLineSpacing; + else + osd_show_value_left(xPos+width,yPos, szBuff, s_idFontStatsSmall); } + + y += height_text*s_OSDStatsLineSpacing + height_text*0.4; + // End - Title - // ------------------------- + // --------------------------------------------------------- osd_set_colors(); + // ----------------------------------------------------- + // Stream Info + char szCurrentProfile[64]; szCurrentProfile[0] = 0; strcpy(szCurrentProfile, str_get_video_profile_name(pVDS->PHVF.uCurrentVideoLinkProfile)); if ( pVDS->PHVF.uVideoStatusFlags2 & VIDEO_STATUS_FLAGS2_IS_ON_LOWER_BITRATE ) strcat(szCurrentProfile, "-"); - //if ( pVDS->uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ONE_WAY_FIXED_VIDEO ) - // strcat(szCurrentProfile, "-1Way"); + if ( pActiveModel->video_link_profiles[pActiveModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ONE_WAY_FIXED_VIDEO ) + strcat(szCurrentProfile, "-1Way"); - // Stream Info - if ( bIsMinimal || bIsCompact || bIsNormal || bIsExtended ) + u32 uVehicleIdVideo = 0; + if ( (osd_get_current_data_source_vehicle_index() >= 0) && (osd_get_current_data_source_vehicle_index() < MAX_CONCURENT_VEHICLES) ) + uVehicleIdVideo = g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].uVehicleId; + if ( link_has_received_videostream(uVehicleIdVideo) ) { - u32 uVehicleIdVideo = 0; - if ( (osd_get_current_data_source_vehicle_index() >= 0) && (osd_get_current_data_source_vehicle_index() < MAX_CONCURENT_VEHICLES) ) - uVehicleIdVideo = g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].uVehicleId; - if ( link_has_received_videostream(uVehicleIdVideo) ) + char szVideoType[64]; + strcpy(szVideoType, "N/A"); + if (((pVDS->PHVF.uVideoStreamIndexAndType >> 4) & 0x0F) == VIDEO_TYPE_H265 ) + strcpy(szVideoType, "H265"); + else if (((pVDS->PHVF.uVideoStreamIndexAndType >> 4) & 0x0F) == VIDEO_TYPE_H264 ) + strcpy(szVideoType, "H264"); + + snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "%s %s %s %d fps ", szCurrentProfile, szVideoType, getOptionVideoResolutionName(pVDS->iCurrentVideoWidth, pVDS->iCurrentVideoHeight), pVDS->iCurrentVideoFPS); + g_pRenderEngine->drawText(xPos, y, s_idFontStatsSmall, szBuff); + float wtmp = g_pRenderEngine->textWidth(s_idFontStatsSmall, szBuff); + + snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), " %d ms ", pVDS->PHVF.uCurrentVideoKeyframeIntervalMs); + if ( pActiveModel->isVideoLinkFixedOneWay() ) + strcat(szBuff, "1Way KF"); + else if ( pActiveModel->video_link_profiles[pActiveModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_LINK ) + strcat(szBuff, "Auto KF"); + else + strcat(szBuff, "Fixed KF"); + + static int sl_iLastKeyframeValue = 0; + static u32 sl_uLastKeyframeValueChange = 0; + if ( pVDS->PHVF.uCurrentVideoKeyframeIntervalMs != sl_iLastKeyframeValue ) { - char szVideoType[64]; - strcpy(szVideoType, "N/A"); - if (((pVDS->PHVF.uVideoStreamIndexAndType >> 4) & 0x0F) == VIDEO_TYPE_H265 ) - strcpy(szVideoType, "H265"); - else if (((pVDS->PHVF.uVideoStreamIndexAndType >> 4) & 0x0F) == VIDEO_TYPE_H264 ) - strcpy(szVideoType, "H264"); - - snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "%s %s %s %d fps %d ms KF", szCurrentProfile, szVideoType, getOptionVideoResolutionName(pVDS->iCurrentVideoWidth, pVDS->iCurrentVideoHeight), pVDS->iCurrentVideoFPS, pVDS->PHVF.uCurrentVideoKeyframeIntervalMs); + sl_iLastKeyframeValue = pVDS->PHVF.uCurrentVideoKeyframeIntervalMs; + sl_uLastKeyframeValueChange = g_TimeNow; } + + if ( (g_TimeNow < sl_uLastKeyframeValueChange+1500) && ((g_TimeNow/g_uOSDElementChangeBlinkInterval)%2) ) + osd_set_colors_text(get_Color_OSDElementChanged()); else - sprintf(szBuff, "Stream: N/A"); + osd_set_colors(); + + g_pRenderEngine->drawText(xPos + wtmp, y, s_idFontStatsSmall, szBuff); + osd_set_colors(); + } + else + { + sprintf(szBuff, "Stream: N/A"); g_pRenderEngine->drawText(xPos, y, s_idFontStatsSmall, szBuff); - y += height_text_small*s_OSDStatsLineSpacing; } + y += height_text_small*s_OSDStatsLineSpacing; u32 videoBitrate = pActiveModel->video_link_profiles[pVDS->PHVF.uCurrentVideoLinkProfile].bitrate_fixed_bps; //u32 msData = (1000*8*pVDS->data_packets_per_block*pVDS->video_data_length)/(pActiveModel->video_link_profiles[(pVDS->video_link_profile & 0x0F)].bitrate_fixed_bps+1); //u32 msFEC = (1000*8*pVDS->fec_packets_per_block*pVDS->video_data_length)/(pActiveModel->video_link_profiles[(pVDS->video_link_profile & 0x0F)].bitrate_fixed_bps+1); + // -------------------------------------------------- + // Stream info 2 + if ( bIsCompact || bIsNormal || bIsExtended ) { static u32 s_uTimeLastECSchemeChangedTime = 0; @@ -575,54 +534,40 @@ float osd_render_stats_video_decode(float xPos, float yPos, int iDeveloperMode, szBuff2[0] = 0; if ( ! (pActiveModel->video_link_profiles[pActiveModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_KEYFRAME) ) { - snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "EC: %s %s%d/%d/%u/%d", szCurrentProfile, - (pActiveModel->video_link_profiles[pVDS->PHVF.uCurrentVideoLinkProfile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_AUTO_EC_SCHEME)?"(A)":"", pVDS->PHVF.uCurrentBlockDataPackets, pVDS->PHVF.uCurrentBlockECPackets, uECSpread, pVDS->PHVF.uCurrentBlockPacketSize); - sprintf(szBuff2, ", %d ms KF (Fixed)", pVDS->PHVF.uCurrentVideoKeyframeIntervalMs); + snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "EC: %s %s%d / %d / %u / %d", szCurrentProfile, + (pActiveModel->video_link_profiles[pVDS->PHVF.uCurrentVideoLinkProfile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_AUTO_EC_SCHEME)?"(A) ":"", pVDS->PHVF.uCurrentBlockDataPackets, pVDS->PHVF.uCurrentBlockECPackets, uECSpread, pVDS->PHVF.uCurrentBlockPacketSize); } else { - snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "EC: %s %s%d/%d/%u/%d", szCurrentProfile, - (pActiveModel->video_link_profiles[pVDS->PHVF.uCurrentVideoLinkProfile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_AUTO_EC_SCHEME)?"(A)":"", pVDS->PHVF.uCurrentBlockDataPackets, pVDS->PHVF.uCurrentBlockECPackets, uECSpread, pVDS->PHVF.uCurrentBlockPacketSize); - sprintf(szBuff2, ", %d ms KF (Auto)", pVDS->PHVF.uCurrentVideoKeyframeIntervalMs); + snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "EC: %s %s %d / %d / %u / %d", szCurrentProfile, + (pActiveModel->video_link_profiles[pVDS->PHVF.uCurrentVideoLinkProfile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_AUTO_EC_SCHEME)?"(A) ":"", pVDS->PHVF.uCurrentBlockDataPackets, pVDS->PHVF.uCurrentBlockECPackets, uECSpread, pVDS->PHVF.uCurrentBlockPacketSize); } if ( bECChanged && g_bOSDElementChangeNotification ) if ( pActiveModel->osd_params.osd_flags3[pActiveModel->osd_params.layout] & OSD_FLAG3_HIGHLIGHT_CHANGING_ELEMENTS ) osd_set_colors_text(get_Color_OSDElementChanged()); - y += height_text*s_OSDStatsLineSpacing*0.1; if ( (! bECChanged) || (g_TimeNow >= s_uTimeLastECSchemeChangedTime + g_uOSDElementChangeTimeout/2) || (bECChanged && ((g_TimeNow/g_uOSDElementChangeBlinkInterval)%2))) g_pRenderEngine->drawText(xPos, y, s_idFontStatsSmall, szBuff); if ( bECChanged ) osd_set_colors(); - - if ( 0 != szBuff2[0] ) - { - float fWEC = g_pRenderEngine->textWidth(s_idFontStatsSmall, szBuff); - g_pRenderEngine->drawText(xPos + fWEC, y, s_idFontStatsSmall, szBuff2); - } - y += height_text*s_OSDStatsLineSpacing*0.9; + y += height_text_small*s_OSDStatsLineSpacing; } + // Stream info 2 + // -------------------------------------------------- // -------------------------------------- - // Begin - Dynamic params + // Retr, adaptive info - if ( bIsCompact || bIsNormal || bIsExtended ) + if ( bIsNormal || bIsExtended ) { strcpy(szBuff, "Retransmissions: "); float wtmp = g_pRenderEngine->textWidth(s_idFontStats, szBuff); g_pRenderEngine->drawText(xPos, y, s_idFontStats, szBuff); - if ( ! (pVDS->uCurrentVideoProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_RETRANSMISSIONS) ) - { - strcpy(szBuff, "Off"); - g_pRenderEngine->setColors(get_Color_IconWarning()); - g_pRenderEngine->drawText(xPos + wtmp, y, s_idFontStats, szBuff); - osd_set_colors(); - } - else + if ( pVDS->uCurrentVideoProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_RETRANSMISSIONS ) { char szBuff3[64]; strcpy(szBuff3, "On"); @@ -631,15 +576,16 @@ float osd_render_stats_video_decode(float xPos, float yPos, int iDeveloperMode, ControllerSettings* pCS = get_ControllerSettings(); if ( (NULL != g_pSM_RadioStats) && (NULL != pCS) && (0 != pCS->iDisableRetransmissionsAfterControllerLinkLostMiliseconds) ) { - // To fix - /* u32 uDelta = (u32)pCS->iDisableRetransmissionsAfterControllerLinkLostMiliseconds; - if ( g_TimeNow > g_pSM_RadioStats->uTimeLastReceivedAResponseFromVehicle + uDelta ) + if ( g_TimeNow > g_pSM_RadioStats->uLastTimeReceivedAckFromAVehicle + uDelta ) { - sprintf(szBuff3, "Off (Link Lost %u ms)", g_TimeNow - g_pSM_RadioStats->uTimeLastReceivedAResponseFromVehicle); + u32 uLinkLostMilisec = g_TimeNow - g_pSM_RadioStats->uLastTimeReceivedAckFromAVehicle; + if ( uLinkLostMilisec < 2000 ) + sprintf(szBuff3, "Off (Link Lost %u ms)", uLinkLostMilisec); + else + sprintf(szBuff3, "Off (Link Lost %u sec)", uLinkLostMilisec/1000); g_pRenderEngine->setColors(get_Color_IconWarning()); } - */ } g_pRenderEngine->drawText(xPos + wtmp, y, s_idFontStats, szBuff3); @@ -651,16 +597,16 @@ float osd_render_stats_video_decode(float xPos, float yPos, int iDeveloperMode, sprintf(szBuff3, " Max %d ms", 5*(((pVDS->uCurrentVideoProfileEncodingFlags) & 0xFF00) >> 8)); g_pRenderEngine->drawText(xPos + wtmp, y, s_idFontStats, szBuff3); - if ( bIsNormal || bIsExtended ) - { - y += height_text*s_OSDStatsLineSpacing; - sprintf(szBuff3, " Retry %d ms", pCS->nRetryRetransmissionAfterTimeoutMS); - g_pRenderEngine->drawText(xPos + wtmp, y, s_idFontStats, szBuff3); - } + + } + else + { + strcpy(szBuff, "Off"); + g_pRenderEngine->setColors(get_Color_IconWarning()); + g_pRenderEngine->drawText(xPos + wtmp, y, s_idFontStats, szBuff); + osd_set_colors(); } y += height_text*s_OSDStatsLineSpacing; // line 1 - - //g_VehiclesRuntimeInfo[osd_get_current_data_source_vehicle_index()].bGotFCTelemetry strcpy(szBuff, "Adaptive Video: "); wtmp = g_pRenderEngine->textWidth(s_idFontStats, szBuff); @@ -686,293 +632,54 @@ float osd_render_stats_video_decode(float xPos, float yPos, int iDeveloperMode, } y += height_text*s_OSDStatsLineSpacing; // line 2 - - char szVideoLevelRecv[64]; - strcpy(szVideoLevelRecv, str_get_video_profile_name(pVDS->PHVF.uCurrentVideoLinkProfile)); - snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "Auto Quantisation (for %s): ", szVideoLevelRecv); - wtmp = g_pRenderEngine->textWidth(s_idFontStats, szBuff); - g_pRenderEngine->drawText(xPos, y, s_idFontStats, szBuff); - - if ( pVDS->uCurrentVideoProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_VIDEO_ADAPTIVE_H264_QUANTIZATION ) - { - sprintf(szBuff, "On "); - g_pRenderEngine->setColors(get_Color_IconSucces()); - g_pRenderEngine->drawText(xPos + wtmp, y, s_idFontStats, szBuff); - wtmp += g_pRenderEngine->textWidth(s_idFontStats, szBuff); - osd_set_colors(); - - sprintf(szBuff, "(%d)", (int)(pVDS->PHVF.uVideoStatusFlags2 & 0xFF)); - g_pRenderEngine->drawText(xPos + wtmp, y, s_idFontStats, szBuff); - wtmp += g_pRenderEngine->textWidth(s_idFontStats, szBuff); - - //sprintf(szBuff3, " Dynamic %d", pActiveModel->video_params.videoAdjustmentStrength); - //g_pRenderEngine->drawText(xPos + wtmp, y, s_idFontStats, szBuff3); - } - else - { - g_pRenderEngine->setColors(get_Color_IconWarning()); - g_pRenderEngine->drawText(xPos + wtmp, y, s_idFontStats, "Off"); - osd_set_colors(); - } - - y += height_text*s_OSDStatsLineSpacing; // line 3 - - strcpy(szBuff, "Keyframes: "); - wtmp = g_pRenderEngine->textWidth(s_idFontStats, szBuff); - g_pRenderEngine->drawText(xPos, y, s_idFontStats, szBuff); - - if ( ! (pActiveModel->video_link_profiles[pActiveModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_KEYFRAME) ) - { - char szBuff3[64]; - sprintf(szBuff3, "Fixed"); - g_pRenderEngine->setColors(get_Color_IconWarning()); - g_pRenderEngine->drawText(xPos + wtmp, y, s_idFontStats, szBuff3); - wtmp += g_pRenderEngine->textWidth(s_idFontStats, szBuff3); - osd_set_colors(); - sprintf(szBuff, " %d ms", pActiveModel->video_link_profiles[pActiveModel->video_params.user_selected_video_link_profile].keyframe_ms ); - g_pRenderEngine->drawText(xPos + wtmp, y, s_idFontStats, szBuff); - } - else - { - char szBuff3[64]; - sprintf(szBuff3, "Auto"); - g_pRenderEngine->setColors(get_Color_IconSucces()); - g_pRenderEngine->drawText(xPos + wtmp, y, s_idFontStats, szBuff3); - wtmp += g_pRenderEngine->textWidth(s_idFontStats, szBuff3); - - static int sl_iLastKeyframeValue = 0; - static u32 sl_uLastKeyframeValueChange = 0; - if ( pVDS->PHVF.uCurrentVideoKeyframeIntervalMs != sl_iLastKeyframeValue ) - { - sl_iLastKeyframeValue = pVDS->PHVF.uCurrentVideoKeyframeIntervalMs; - sl_uLastKeyframeValueChange = g_TimeNow; - } - - if ( g_TimeNow < sl_uLastKeyframeValueChange+1000 ) - g_pRenderEngine->setColors(get_Color_OSDChangedValue()); - else - osd_set_colors(); - sprintf(szBuff, " %d ms", pVDS->PHVF.uCurrentVideoKeyframeIntervalMs ); - g_pRenderEngine->drawText(xPos + wtmp, y, s_idFontStats, szBuff); - osd_set_colors(); - } - y += height_text*s_OSDStatsLineSpacing; // line 4 - - // To fix or remove - /* - char szBuff2[64]; - str_format_bitrate((int)(pVDS->uLastSetVideoBitrate & VIDEO_BITRATE_FIELD_MASK), szBuff); - if ( pVDS->uLastSetVideoBitrate & VIDEO_BITRATE_FLAG_ADJUSTED ) - snprintf(szBuff2, sizeof(szBuff2)/sizeof(szBuff2[0]), "(Adj) %s", szBuff); - else - snprintf(szBuff2, sizeof(szBuff2)/sizeof(szBuff2[0]), "(Def) %s", szBuff); - - snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "Set bitrate: %s", szBuff2); - g_pRenderEngine->drawText(xPos, y, s_idFontStats, szBuff); - y += height_text*s_OSDStatsLineSpacing; - */ - - strcpy(szBuff, "Video Level (Req / Ack / Recv): "); - wtmp = g_pRenderEngine->textWidth(s_idFontStats, szBuff); - g_pRenderEngine->drawText(xPos, y, s_idFontStats, szBuff); - y += height_text*s_OSDStatsLineSpacing; // line 5 - - char szVideoLevelRequested[64]; - char szVideoLevelAck[64]; - // To fix or remove - //strcpy(szVideoLevelRequested, osd_format_video_adaptive_level(pActiveModel, g_SM_RouterVehiclesRuntimeInfo.vehicles_adaptive_video[iIndexRouterRuntimeInfo].iCurrentTargetLevelShift) ); - //strcpy(szVideoLevelAck, osd_format_video_adaptive_level(pActiveModel, pVDS->iLastAckVideoLevelShift) ); - szVideoLevelRequested[0] = 0; - szVideoLevelAck[0] = 0; - - int diffEC = pVDS->PHVF.uCurrentBlockECPackets - pActiveModel->video_link_profiles[pVDS->PHVF.uCurrentVideoLinkProfile].block_fecs; - if ( diffEC > 0 ) - { - char szTmp[16]; - sprintf(szTmp, "-%d", diffEC); - strcat(szVideoLevelRecv, szTmp); - } - else if ( pVDS->PHVF.uVideoStatusFlags2 & VIDEO_STATUS_FLAGS2_IS_ON_LOWER_BITRATE ) - strcat(szVideoLevelRecv, "-"); - - snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "%s / %s / %s", szVideoLevelRequested, szVideoLevelAck, szVideoLevelRecv); - - static u32 sl_uLastTimeChangedVideoLevelInfo = 0; - static char sl_szLastVideoLevelInfo[128]; - if ( 0 == sl_uLastTimeChangedVideoLevelInfo ) - sl_szLastVideoLevelInfo[0] = 0; - if ( 0 != strcmp(szBuff, sl_szLastVideoLevelInfo) ) - { - strcpy(sl_szLastVideoLevelInfo, szBuff); - sl_uLastTimeChangedVideoLevelInfo = g_TimeNow; - } - - if ( g_TimeNow < sl_uLastTimeChangedVideoLevelInfo + 1000 ) - g_pRenderEngine->setColors(get_Color_OSDChangedValue()); - g_pRenderEngine->drawText(xPos, y, s_idFontStats, szBuff); - osd_set_colors(); - y += height_text*s_OSDStatsLineSpacing; // line 6 - - y += 0.2*height_text*s_OSDStatsLineSpacing; } - - // End - Dynamic params + // Retr, adaptive info // -------------------------------------- - int maxPacketsCount = 1; - // To fix or remove - //if ( 0 < pVDS->maxPacketsInBuffers ) - // maxPacketsCount = pVDS->maxPacketsInBuffers; - - float fWarningFullPercent = 0.5; - - - // --------------------------------------- - // Begin - Draw Rx packets buffer - - if ( bIsExtended ) - { - y += height_text*0.1; - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Buffers:"); - float wPrefix = g_pRenderEngine->textWidth(s_idFontStats, "Buffers:") + 0.02*scale; - - float hBar = 0.014*scale; - width -= wPrefix; - osd_set_colors_background_fill(); - g_pRenderEngine->setStrokeSize(OSD_STRIKE_WIDTH); - g_pRenderEngine->setStroke(255,255,255,1.0); - if ( pVDS->iCurrentPacketsInBuffers > fWarningFullPercent*maxPacketsCount ) - g_pRenderEngine->setStroke(250,0,0, s_fOSDStatsGraphLinesAlpha); - g_pRenderEngine->drawRoundRect(xPos+wPrefix, y, width, hBar, 0.003*scale); - wPrefix += 2.0/g_pRenderEngine->getScreenWidth(); - width -= 4.0/g_pRenderEngine->getScreenWidth(); - y += 2.0/g_pRenderEngine->getScreenHeight(); - hBar -= 4.0/g_pRenderEngine->getScreenHeight(); - - float fBarScale = width/100.0; - // To fix or remove - /* - int packs = pVDS->maxPacketsInBuffers; - if ( packs > 0 ) - fBarScale = width/(float)(packs+1); // max buffer length - - g_pRenderEngine->setFill(145,45,45, s_fOSDStatsGraphLinesAlpha); - g_pRenderEngine->setStroke(0,0,0,0); - g_pRenderEngine->setStrokeSize(0); - */ - - // To fix or remove - /* - g_pRenderEngine->setStrokeSize(OSD_STRIKE_WIDTH); - double* pc = get_Color_OSDText(); - g_pRenderEngine->setStroke(pc[0], pc[1], pc[2], s_fOSDStatsGraphLinesAlpha); - if ( pVDS->currentPacketsInBuffers > s_iPeakTotalPacketsInBuffer ) - s_iPeakTotalPacketsInBuffer = pVDS->currentPacketsInBuffers; - packs = pVDS->maxPacketsInBuffers; - if ( s_iPeakTotalPacketsInBuffer > packs ) - s_iPeakTotalPacketsInBuffer = packs+1; - g_pRenderEngine->drawLine(xPos + wPrefix + fBarScale*s_iPeakTotalPacketsInBuffer, y, xPos + wPrefix + fBarScale*s_iPeakTotalPacketsInBuffer, y+hBar); - g_pRenderEngine->drawLine(xPos + wPrefix + fBarScale*s_iPeakTotalPacketsInBuffer+wPixel, y, xPos + wPrefix + fBarScale*s_iPeakTotalPacketsInBuffer+wPixel, y+hBar); - */ - - //if ( 0 == (s_iPeakCountRender % 3) ) - if ( s_iPeakTotalPacketsInBuffer > 0 ) - s_iPeakTotalPacketsInBuffer--; - - // To fix or remove - //g_pRenderEngine->setStroke(pc[0], pc[1], pc[2], s_fOSDStatsGraphLinesAlpha); - //g_pRenderEngine->setFill(pc[0], pc[1], pc[2], s_fOSDStatsGraphLinesAlpha); - //g_pRenderEngine->drawRect(xPos+wPrefix+1.0/g_pRenderEngine->getScreenWidth(), y, fBarScale*pVDS->currentPacketsInBuffers-2.0/g_pRenderEngine->getScreenWidth(), hBar); - osd_set_colors(); - - // To fix or remove - /* - hBar += 4.0/g_pRenderEngine->getScreenHeight(); - sprintf(szBuff, "%d", pVDS->maxPacketsInBuffers); - g_pRenderEngine->drawText(xPos + wPrefix-2.0/g_pRenderEngine->getScreenWidth(), y+hBar, s_idFontStatsSmall, "0"); - g_pRenderEngine->drawTextLeft(xPos + wPrefix + width-2.0/g_pRenderEngine->getScreenWidth(), y+hBar, s_idFontStatsSmall, szBuff); - */ - y += hBar; - y += height_text*0.9; - } - - // End - Draw rx packets buffers - // --------------------------------------- - - int iHistoryStartRetransmissionsIndex = MAX_HISTORY_VIDEO_INTERVALS; - int iHistoryEndRetransmissionsIndex = 0; - int totalHistoryValues = MAX_HISTORY_VIDEO_INTERVALS; - - if ( ! bIsExtended ) - totalHistoryValues = MAX_HISTORY_VIDEO_INTERVALS*3/4; - -/* - if ( bIsSnapshot ) - { - while ( (totalHistoryValues > 10) && - (pVDSH->missingTotalPacketsAtPeriod[totalHistoryValues-1] == 0) && - (pCRS->history[totalHistoryValues-1].uCountRequestedPacketsForRetransmission == 0) ) - totalHistoryValues--; - iHistoryStartRetransmissionsIndex = totalHistoryValues; - totalHistoryValues += 5; - if ( totalHistoryValues > MAX_HISTORY_VIDEO_INTERVALS ) - totalHistoryValues = MAX_HISTORY_VIDEO_INTERVALS; - - while ( (iHistoryEndRetransmissionsIndex < iHistoryStartRetransmissionsIndex) && - (pVDSH->missingTotalPacketsAtPeriod[iHistoryEndRetransmissionsIndex] == 0) && - (pCRS->history[iHistoryEndRetransmissionsIndex].uCountRequestedPacketsForRetransmission == 0) ) - iHistoryEndRetransmissionsIndex++; - - if ( totalHistoryValues < 24 ) - totalHistoryValues = 24; - } -*/ //------------------------------------ // Begin - Output history video packets graph - float dxGraph = 0.01*scale; - width = widthMax - dxGraph; - float widthBar = width / totalHistoryValues; + int iIntervals = 1; + int iValuesPerInterval = 1; + if ( (pCS->nGraphVideoRefreshInterval > 0) && (g_SMControllerRTInfo.uUpdateIntervalMs > 0) ) + { + iIntervals = (SYSTEM_RT_INFO_INTERVALS * g_SMControllerRTInfo.uUpdateIntervalMs) / pCS->nGraphVideoRefreshInterval; + iValuesPerInterval = pCS->nGraphVideoRefreshInterval / g_SMControllerRTInfo.uUpdateIntervalMs; + } + + int iCountValues = 0; + int iIndex = g_SMControllerRTInfo.iCurrentIndex - (g_SMControllerRTInfo.iCurrentIndex % iValuesPerInterval); + float fSumPackets = 0.0; int maxGraphValue = 4; - for( int i=0; ioutputHistoryBlocksDiscardedPerPeriod[i] > maxGraphValue ) - maxGraphValue = pVDSH->outputHistoryBlocksDiscardedPerPeriod[i]; - if ( pVDSH->outputHistoryBlocksBadPerPeriod[i] > maxGraphValue ) - maxGraphValue = pVDSH->outputHistoryBlocksBadPerPeriod[i]; - if ( pVDSH->outputHistoryBlocksOkPerPeriod[i] > maxGraphValue ) - maxGraphValue = pVDSH->outputHistoryBlocksOkPerPeriod[i]; - if ( pVDSH->outputHistoryBlocksReconstructedPerPeriod[i] > maxGraphValue ) - maxGraphValue = pVDSH->outputHistoryBlocksReconstructedPerPeriod[i]; - if ( pVDSH->outputHistoryBlocksRetrasmitedPerPeriod[i] > maxGraphValue ) - maxGraphValue = pVDSH->outputHistoryBlocksRetrasmitedPerPeriod[i]; - //if ( pCRS->history[i].uCountRequestedRetransmissions > maxGraphValue ) - // maxGraphValue = pCRS->history[i].uCountRequestedRetransmissions; + for( int i=0; ioutputHistoryBlocksRetrasmitedPerPeriod[i] + pVDSH->outputHistoryBlocksReconstructedPerPeriod[i] > maxGraphValue ) - maxGraphValue = pVDSH->outputHistoryBlocksRetrasmitedPerPeriod[i] + pVDSH->outputHistoryBlocksReconstructedPerPeriod[i]; + iCountValues = 0; + if ( fSumPackets > maxGraphValue ) + maxGraphValue = fSumPackets; + + fSumPackets = 0.0; } y += height_text_small*0.2; - // To fix or remove - //sprintf(szBuff,"%d ms/bar, buff: max %d blocks", pVDSH->outputHistoryIntervalMs, pVDS->maxBlocksAllowedInBuffers); - szBuff[0] = 0; + + if ( bIsMinimal || bIsCompact ) + sprintf(szBuff,"%.1f sec, %d ms/bar", (float)iIntervals * (float)pCS->nGraphVideoRefreshInterval / 1000.0, pCS->nGraphVideoRefreshInterval); + else + sprintf(szBuff,"%d ms/bar %d x %d ms resolution (%d-%d bars)", pCS->nGraphVideoRefreshInterval, SYSTEM_RT_INFO_INTERVALS, g_SMControllerRTInfo.uUpdateIntervalMs, iIntervals, iValuesPerInterval); if ( bIsSnapshot ) - { - sprintf(szBuff,"%d ms/bar, dx: %d", pVDSH->outputHistoryIntervalMs, iHistoryEndRetransmissionsIndex); g_pRenderEngine->drawTextLeft(xPos+widthMax, y, s_idFontStats, szBuff); - } else - { g_pRenderEngine->drawTextLeft(xPos+widthMax, y-height_text_small*0.2, s_idFontStatsSmall, szBuff); - float w = g_pRenderEngine->textWidth(s_idFontStatsSmall, szBuff); - - sprintf(szBuff,"%.1f sec, ", (((float)totalHistoryValues) * pVDSH->outputHistoryIntervalMs)/1000.0); - g_pRenderEngine->drawTextLeft(xPos+widthMax-w, y-height_text_small*0.2, s_idFontStatsSmall, szBuff); - w += g_pRenderEngine->textWidth(s_idFontStatsSmall, szBuff); - } y += height_text_small*1.0; @@ -980,6 +687,9 @@ float osd_render_stats_video_decode(float xPos, float yPos, int iDeveloperMode, g_pRenderEngine->drawText(xPos, y-height_text_small*0.5, s_idFontStatsSmall, szBuff); g_pRenderEngine->drawText(xPos, y+hGraphHistory-height_text_small*0.5, s_idFontStatsSmall, "0"); + float dxGraph = 0.01*scale; + float fWidthGraph = widthMax - dxGraph; + double* pc = get_Color_OSDText(); g_pRenderEngine->setStrokeSize(OSD_STRIKE_WIDTH); g_pRenderEngine->setStroke(pc[0], pc[1], pc[2], s_fOSDStatsGraphLinesAlpha); @@ -987,182 +697,166 @@ float osd_render_stats_video_decode(float xPos, float yPos, int iDeveloperMode, g_pRenderEngine->drawLine(xPos+dxGraph, y, xPos + dxGraph + width, y); g_pRenderEngine->setStroke(pc[0], pc[1], pc[2], s_fOSDStatsGraphBottomLinesAlpha); g_pRenderEngine->setFill(pc[0], pc[1], pc[2], s_fOSDStatsGraphBottomLinesAlpha); - g_pRenderEngine->drawLine(xPos+dxGraph, y+hGraphHistory, xPos + dxGraph + width, y+hGraphHistory); + g_pRenderEngine->drawLine(xPos+dxGraph, y+hGraphHistory, xPos + dxGraph + fWidthGraph, y+hGraphHistory); float midLine = hGraphHistory/2.0; - for( float i=0; i<=width-2.0*wPixel; i+= 5*wPixel ) + for( float i=0; i<=fWidthGraph-2.0*wPixel; i+= 5*wPixel ) g_pRenderEngine->drawLine(xPos+dxGraph+i, y+midLine, xPos + dxGraph + i + 2.0*wPixel, y+midLine); - double colorECSingle[4] = {255,50,250, 1.0}; - double colorECMultiple[4] = {20,250,50, 1.0}; - double colorECMultiple2[4] = {20,100,20, 1.0}; + double colorECUsed[4] = {0,150,0, 1.0}; + double colorECMultiple[4] = {250,250,50, 1.0}; + double colorECMaxUsed[4] = {220,250,20, 1.0}; + double colorRetransmitted[4] = {40,20,255,1.0}; + double colorDropped[4] = {255,50,50,1.0}; g_pRenderEngine->setStrokeSize(0); - u32 maxHistoryPacketsGap = 0; - float hBarBad = 0.0; - float hBarMissing = 0.0; - float hBarReconstructed = 0.0; - float hBarOk = 0.0; - float hBarRetransmitted = 0.0; float yBottomGraph = y + hGraphHistory;// - 1.0/g_pRenderEngine->getScreenHeight(); + float widthBar = fWidthGraph / iIntervals; + float fWidthBarRect = widthBar-wPixel; + if ( fWidthBarRect < 2.0 * wPixel ) + fWidthBarRect = widthBar; + float xBarSt = xPos + widthMax - g_pRenderEngine->getPixelWidth(); float xBarMid = xBarSt + widthBar*0.5; float xBarEnd = xBarSt + widthBar - g_pRenderEngine->getPixelWidth(); - float fWidthBarRect = widthBar-wPixel; - if ( fWidthBarRect < 2.0 * wPixel ) - fWidthBarRect = widthBar; + iCountValues = 0; + iIndex = g_SMControllerRTInfo.iCurrentIndex - (g_SMControllerRTInfo.iCurrentIndex % iValuesPerInterval); + fSumPackets = 0.0; + float fSumECUsed = 0.0; + float fSumRetransmitted = 0.0; + float fSumDropped = 0.0; + float hBar = 0.0; + bool bECUsedMax = false; + + for( int i=0; i= pActiveModel->video_link_profiles[pVDS->PHVF.uCurrentVideoLinkProfile].block_fecs ) + bECUsedMax = true; + fSumPackets += g_SMControllerRTInfo.uOutputedVideoPackets[iIndex]; + fSumECUsed += g_SMControllerRTInfo.uOutputedVideoPacketsSingleECUsed[iIndex]; + fSumECUsed += g_SMControllerRTInfo.uOutputedVideoPacketsTwoECUsed[iIndex]; + fSumECUsed += g_SMControllerRTInfo.uOutputedVideoPacketsMultipleECUsed[iIndex]; + fSumRetransmitted += g_SMControllerRTInfo.uOutputedVideoPacketsRetransmitted[iIndex]; + fSumDropped += g_SMControllerRTInfo.uOutputedVideoPacketsSkippedBlocks[iIndex]; + iCountValues++; + if ( iCountValues < iValuesPerInterval ) + continue; - for( int i=0; ioutputHistoryBlocksDiscardedPerPeriod[i] > 0 ) + float percentTotal = (float)(fSumPackets)/(float)(maxGraphValue); + if ( percentTotal > 1.0 ) + percentTotal = 1.0; + float percentDropped = (float)(fSumDropped)/(float)(maxGraphValue); + if ( percentDropped > 1.0 ) + percentDropped = 1.0; + if ( percentTotal > 0.001 ) { - hBarBad = hGraph; - float hBarBadTop = yBottomGraph-hGraphHistory; - if ( pVDSH->outputHistoryBlocksOkPerPeriod[i] > 0 || - pVDSH->outputHistoryBlocksReconstructedPerPeriod[i] > 0 ) + hBar = hGraphHistory*percentTotal; + + // Clean packets + if ( (fSumRetransmitted < 1.0) && (fSumECUsed < 1.0) ) { - hBarBad = hGraphHistory*0.5; - if ( pVDSH->outputHistoryBlocksReconstructedPerPeriod[i] > 0 ) - g_pRenderEngine->setFill(colorECMultiple[0], colorECMultiple[1], colorECMultiple[2], s_fOSDStatsGraphLinesAlpha); + g_pRenderEngine->setFill(pc[0], pc[1], pc[2], s_fOSDStatsGraphLinesAlpha*0.9); + g_pRenderEngine->drawRect(xBarSt, yBottomGraph - hBar, fWidthBarRect, hBar); + } + // EC packets only + else if ( fSumRetransmitted < 1.0 ) + { + float fPercentEC = fSumECUsed / fSumPackets; + if ( fPercentEC < .25 ) + fPercentEC = .25; + if ( hBar < 0.5 * hGraphHistory ) + if ( fPercentEC < 0.4 ) + fPercentEC = 0.4; + if ( bECUsedMax ) + g_pRenderEngine->setFill(colorECMaxUsed[0], colorECMaxUsed[1], colorECMaxUsed[2], colorECMaxUsed[3]); else - g_pRenderEngine->setFill(pc[0], pc[1], pc[2], s_fOSDStatsGraphLinesAlpha); - g_pRenderEngine->drawRect(xBarSt, hBarBadTop + hBarBad, widthBar-wPixel, hBarBad); + g_pRenderEngine->setFill(pc[0], pc[1], pc[2], s_fOSDStatsGraphLinesAlpha*0.9); + g_pRenderEngine->drawRect(xBarSt, yBottomGraph - hBar, fWidthBarRect, hBar * (1.0 - fPercentEC)); + //g_pRenderEngine->setFill(colorRetransmitted[0], colorRetransmitted[1], colorRetransmitted[2], colorRetransmitted[3]); + g_pRenderEngine->setFill(colorECUsed[0], colorECUsed[1], colorECUsed[2], colorECUsed[3]); + g_pRenderEngine->drawRect(xBarSt, yBottomGraph - hBar * fPercentEC, fWidthBarRect, hBar * fPercentEC); + } + // Retr packets only + else if ( fSumECUsed < 1.0 ) + { + float fPercentRetr = fSumRetransmitted / fSumPackets; + if ( fPercentRetr < .25 ) + fPercentRetr = .25; + if ( hBar < 0.5 * hGraphHistory ) + if ( fPercentRetr < 0.4 ) + fPercentRetr = 0.4; + g_pRenderEngine->setFill(pc[0], pc[1], pc[2], s_fOSDStatsGraphLinesAlpha*0.9); + g_pRenderEngine->drawRect(xBarSt, yBottomGraph - hBar, fWidthBarRect, hBar * (1.0 - fPercentRetr)); + g_pRenderEngine->setFill(colorRetransmitted[0], colorRetransmitted[1], colorRetransmitted[2], colorRetransmitted[3]); + g_pRenderEngine->drawRect(xBarSt, yBottomGraph - hBar * fPercentRetr, fWidthBarRect, hBar * fPercentRetr); } - if ( pVDSH->outputHistoryReceivedVideoPackets[i] > 0 || pVDSH->outputHistoryReceivedVideoRetransmittedPackets[i] > 0 ) - g_pRenderEngine->setFill(240,220,0,0.85); + // Both EC and retr else - g_pRenderEngine->setFill(240,20,0,0.85); - g_pRenderEngine->drawRect(xBarSt, hBarBadTop, widthBar-wPixel, hBarBad); - continue; + { + float fPercentEC = fSumECUsed / fSumPackets; + if ( fPercentEC < .25 ) + fPercentEC = .25; + float fPercentRetr = fSumRetransmitted / fSumPackets; + if ( fPercentRetr < .25 ) + fPercentRetr = .25; + if ( fPercentEC + fPercentRetr > 1.0 ) + fPercentEC = 1.0 - fPercentRetr; + + if ( bECUsedMax ) + g_pRenderEngine->setFill(colorECMaxUsed[0], colorECMaxUsed[1], colorECMaxUsed[2], colorECMaxUsed[3]); + else + g_pRenderEngine->setFill(pc[0], pc[1], pc[2], s_fOSDStatsGraphLinesAlpha*0.9); + g_pRenderEngine->drawRect(xBarSt, yBottomGraph - hBar, fWidthBarRect, hBar * (1.0 - fPercentEC - fPercentRetr)); + + g_pRenderEngine->setFill(colorECUsed[0], colorECUsed[1], colorECUsed[2], colorECUsed[3]); + g_pRenderEngine->drawRect(xBarSt, yBottomGraph - hBar * (fPercentEC + fPercentRetr), fWidthBarRect, hBar * fPercentEC); + + g_pRenderEngine->setFill(colorRetransmitted[0], colorRetransmitted[1], colorRetransmitted[2], colorRetransmitted[3]); + g_pRenderEngine->drawRect(xBarSt, yBottomGraph - hBar * fPercentRetr, fWidthBarRect, hBar * fPercentRetr); + } } - u32 val = pVDSH->outputHistoryBlocksMaxPacketsGapPerPeriod[i]; - if ( val > maxHistoryPacketsGap ) - maxHistoryPacketsGap = val; - - hBarBad = 0.0; - hBarMissing = 0.0; - hBarReconstructed = 0.0; - hBarOk = 0.0; - hBarRetransmitted = 0.0; - float fPercentageUsed = 0.0; - - float percentBad = 0.0; - percentBad = (float)(pVDSH->outputHistoryBlocksBadPerPeriod[i])/(float)(maxGraphValue); - if ( percentBad > 1.0 ) percentBad = 1.0; - if ( percentBad > 0.001 ) + if ( percentDropped > 0.0001 ) { - hBarBad = hGraphHistory*percentBad; - g_pRenderEngine->setFill(240,220,0,0.65); - g_pRenderEngine->drawRect(xBarSt, yBottomGraph - hGraphHistory * fPercentageUsed - hBarBad, fWidthBarRect, hBarBad); - fPercentageUsed += percentBad; - if ( fPercentageUsed > 1.0 ) - fPercentageUsed = 1.0; + if ( percentDropped < 0.3 ) + percentDropped = 0.3; + hBar = hGraphHistory*percentDropped; + g_pRenderEngine->setFill(colorDropped[0], colorDropped[1], colorDropped[2], colorDropped[3]); + g_pRenderEngine->drawRect(xBarSt, yBottomGraph - hBar, fWidthBarRect, hBar); } - float percentMissing = (float)(pVDSH->outputHistoryBlocksMissingPerPeriod[i])/(float)(maxGraphValue); - if ( percentMissing > 1.0 ) percentMissing = 1.0; - if ( percentMissing > 0.001 ) - { - if ( percentMissing + fPercentageUsed > 1.0 ) - percentMissing = 1.0 - fPercentageUsed; - if ( percentMissing < 0.0 ) - percentMissing = 0.0; - hBarMissing = hGraphHistory*percentMissing; - g_pRenderEngine->setFill(240,0,0,0.74); - g_pRenderEngine->drawRect(xBarSt, yBottomGraph - hGraphHistory * fPercentageUsed - hBarMissing, fWidthBarRect, hBarMissing); - fPercentageUsed += percentMissing; - if ( fPercentageUsed > 1.0 ) - fPercentageUsed = 1.0; - } - - float percentOk = (float)(pVDSH->outputHistoryBlocksOkPerPeriod[i])/(float)(maxGraphValue); - if ( percentOk > 1.0 ) percentOk = 1.0; - if ( percentOk > 0.001 ) - { - if ( percentOk + fPercentageUsed > 1.0 ) - percentOk = 1.0 - fPercentageUsed; - if ( percentOk < 0.0 ) - percentOk = 0.0; - hBarOk = hGraphHistory*percentOk; - if ( pVDSH->outputHistoryBlocksReconstructedPerPeriod[i] > 0 ) - g_pRenderEngine->setFill(pc[0]*0.9, pc[1]*0.9, pc[2]*0.6, s_fOSDStatsGraphLinesAlpha*0.5); - else - g_pRenderEngine->setFill(pc[0], pc[1], pc[2], s_fOSDStatsGraphLinesAlpha*0.9); - - g_pRenderEngine->drawRect(xBarSt, yBottomGraph - hGraphHistory * fPercentageUsed - hBarOk, fWidthBarRect, hBarOk); - fPercentageUsed += percentOk; - if ( fPercentageUsed > 1.0 ) - fPercentageUsed = 1.0; - } - float percentRecon = (float)(pVDSH->outputHistoryBlocksReconstructedPerPeriod[i])/(float)(maxGraphValue); - if ( percentRecon > 1.0 ) percentRecon = 1.0; - if ( percentRecon > 0.001 ) - { - if ( percentRecon + fPercentageUsed > 1.0 ) - percentRecon = 1.0 - fPercentageUsed; - if ( percentRecon < 0.0 ) - percentRecon = 0.0; - hBarReconstructed = hGraphHistory*percentRecon; - if ( (pVDSH->outputHistoryBlocksReconstructedPerPeriod[i] == 1) && (pVDSH->outputHistoryMaxECPacketsUsedPerPeriod[i] == 1) ) - g_pRenderEngine->setFill(colorECSingle[0], colorECSingle[1], colorECSingle[2], s_fOSDStatsGraphLinesAlpha); - else if ( pVDSH->outputHistoryMaxECPacketsUsedPerPeriod[i] > 1 ) - g_pRenderEngine->setFill(colorECMultiple[0], colorECMultiple[1], colorECMultiple[2], s_fOSDStatsGraphLinesAlpha); - else - g_pRenderEngine->setFill(colorECMultiple2[0], colorECMultiple2[1], colorECMultiple2[2], s_fOSDStatsGraphLinesAlpha); - g_pRenderEngine->drawRect(xBarSt, yBottomGraph - hGraphHistory * fPercentageUsed - hBarReconstructed, fWidthBarRect, hBarReconstructed); - fPercentageUsed += percentRecon; - if ( fPercentageUsed > 1.0 ) - fPercentageUsed = 1.0; - } - - float percentRetrans = (float)(pVDSH->outputHistoryBlocksRetrasmitedPerPeriod[i])/(float)(maxGraphValue); - if ( percentRetrans > 1.0 ) percentRetrans = 1.0; - if ( percentRetrans > 0.001 ) - { - if ( percentRetrans + fPercentageUsed > 1.0 ) - fPercentageUsed = 1.0 - percentRetrans; - - hBarRetransmitted = hGraphHistory*percentRetrans; - g_pRenderEngine->setFill(20,20,230, s_fOSDStatsGraphLinesAlpha); - g_pRenderEngine->drawRect(xBarSt, yBottomGraph - hGraphHistory * fPercentageUsed - hBarRetransmitted, fWidthBarRect, hBarRetransmitted); - fPercentageUsed += percentRetrans; - if ( fPercentageUsed > 1.0 ) - fPercentageUsed = 1.0; - - } - /* - if ( 0 < pCRS->history[i].uCountRequestedRetransmissions ) - { - if ( pCRS->history[i].uCountReRequestedPacketsForRetransmission > 0 ) - g_pRenderEngine->setFill(10,50,250, s_fOSDStatsGraphLinesAlpha); - else - g_pRenderEngine->setFill(10,200,210, s_fOSDStatsGraphLinesAlpha); - - float hPR = hGraphHistory*(0.1 + 0.25*(float)(pCRS->history[i].uCountRequestedRetransmissions)/(float)(maxGraphValue)); - g_pRenderEngine->drawRect(xBarSt, y, fWidthBarRect, hPR); - } - */ + fSumPackets = 0.0; + fSumECUsed = 0.0; + fSumRetransmitted = 0.0; + fSumDropped = 0.0; + bECUsedMax = false; } +/* for( int i=totalHistoryValues; ioutputHistoryBlocksMaxPacketsGapPerPeriod[i]; if ( val > maxHistoryPacketsGap ) maxHistoryPacketsGap = val; } + */ y += hGraphHistory + height_text_small*0.3; + osd_set_colors(); // End history buffer //---------------------------------------------------------------- - osd_set_colors(); - +/* // Max EC packets used if ( pActiveModel->bDeveloperMode || s_bDebugStatsShowAll ) @@ -1373,15 +1067,6 @@ float osd_render_stats_video_decode(float xPos, float yPos, int iDeveloperMode, y += height_text*s_OSDStatsLineSpacing; } - // To fix or remove - /* - if ( bIsNormal || bIsExtended ) - { - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Discarded buff/seg/pack:"); - sprintf(szBuff, "%u/%u/%u", pVDS->total_DiscardedBuffers, pVDS->total_DiscardedSegments, pVDS->total_DiscardedLostPackets); - g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStats, szBuff); - y += height_text*s_OSDStatsLineSpacing; - } */ /* @@ -2291,873 +1976,253 @@ float osd_render_stats_efficiency(float xPos, float yPos, float scale) float width = osd_render_stats_efficiency_get_width(scale); float height = osd_render_stats_efficiency_get_height(scale); - char szBuff[128]; - - osd_set_colors_background_fill(g_fOSDStatsBgTransparency); - g_pRenderEngine->drawRoundRect(xPos, yPos, width, height, 1.5*POPUP_ROUND_MARGIN); - osd_set_colors(); - - xPos += s_fOSDStatsMargin*scale/g_pRenderEngine->getAspectRatio(); - yPos += s_fOSDStatsMargin*scale*0.7; - width -= 2*s_fOSDStatsMargin*scale/g_pRenderEngine->getAspectRatio(); - float rightMargin = xPos + width; - - g_pRenderEngine->drawText(xPos, yPos, s_idFontStats, "Efficiency Stats"); - - float y = yPos + height_text*1.3*s_OSDStatsLineSpacing; - - osd_set_colors(); - - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "mA/km:"); - float eff = 0.0; - if ( NULL != g_pCurrentModel && g_pCurrentModel->m_Stats.uCurrentFlightDistance > 500 ) - eff = (float)g_pCurrentModel->m_Stats.uCurrentFlightTotalCurrent/10.0/((float)g_pCurrentModel->m_Stats.uCurrentFlightDistance/100.0/1000.0); - sprintf(szBuff, "%d", (int)eff); - g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStats, szBuff); - y += height_text*s_OSDStatsLineSpacing; - - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "mA/h:"); - eff = 0; - if ( NULL != g_pCurrentModel && g_pCurrentModel->m_Stats.uCurrentFlightTime > 0 ) - eff = ( (float)g_pCurrentModel->m_Stats.uCurrentFlightTotalCurrent/10.0/((float)g_pCurrentModel->m_Stats.uCurrentFlightTime))*3600.0; - sprintf(szBuff, "%d", (int)eff); - g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStats, szBuff); - y += height_text*s_OSDStatsLineSpacing; - - return height; -} - -float osd_render_stats_video_stream_keyframe_info_get_height() -{ - float height_text = g_pRenderEngine->textHeight(s_idFontStats); - float height = 2.0 *s_fOSDStatsMargin*1.1 + 1.1*height_text*s_OSDStatsLineSpacing; - - float hGraph = height_text*2.0; - - ControllerSettings* pCS = get_ControllerSettings(); - - // stats - height += 7.0 * height_text*s_OSDStatsLineSpacing; - - Model* pActiveModel = osd_get_current_data_source_vehicle_model(); - - if ( (NULL != pActiveModel) && pActiveModel->bDeveloperMode ) - { - //height += 3.0 * height_text * s_OSDStatsLineSpacing; - //height += osd_render_stats_dev_adaptive_video_get_height(); - } - - // Minimal view - if ( pCS->iShowVideoStreamInfoCompactType == 2 ) - return height; - - height += 0.3*height_text*s_OSDStatsLineSpacing; - - // kb/frame - height += hGraph; - height += height_text; - - // camera source - height += hGraph; - height += 4*height_text*s_OSDStatsLineSpacing; - - // Compact view - if ( pCS->iShowVideoStreamInfoCompactType == 1 ) - return height; - - // Detailed view - - height += 4.0 * height_text*s_OSDStatsLineSpacing; - - // radio out - height += height_text*0.6; - height += hGraph; - height += 3*height_text*s_OSDStatsLineSpacing; - - // radio in - height += height_text*0.6; - height += hGraph; - height += 3*height_text*s_OSDStatsLineSpacing; - - // player output - height += height_text*0.6; - height += hGraph; - height += 3*height_text*s_OSDStatsLineSpacing; - - return height; -} - -float osd_render_stats_video_stream_keyframe_info_get_width() -{ - if ( g_fOSDStatsForcePanelWidth > 0.01 ) - return g_fOSDStatsForcePanelWidth; - float width = g_pRenderEngine->textWidth(s_idFontStats, "AAAAAAAA AAAAA AAAAA AAA"); - width += 2.0*s_fOSDStatsMargin/g_pRenderEngine->getAspectRatio(); - return width; -} - -float osd_render_stats_video_stream_keyframe_info(float xPos, float yPos) -{ - Model* pActiveModel = osd_get_current_data_source_vehicle_model(); - u32 uActiveVehicleId = osd_get_current_data_source_vehicle_id(); - - shared_mem_video_stream_stats* pVDS = NULL; - int iIndexRouterRuntimeInfo = -1; - - for( int i=0; itextHeight(s_idFontStats); - float height_text_small = g_pRenderEngine->textHeight(s_idFontStatsSmall); - - float hGraph = height_text*2.0; - float wPixel = g_pRenderEngine->getPixelWidth(); - - float width = osd_render_stats_video_stream_keyframe_info_get_width(); - float height = osd_render_stats_video_stream_keyframe_info_get_height(); - - char szBuff[128]; - - osd_set_colors_background_fill(g_fOSDStatsBgTransparency); - g_pRenderEngine->drawRoundRect(xPos, yPos, width, height, 1.5*POPUP_ROUND_MARGIN); - osd_set_colors(); - - - xPos += s_fOSDStatsMargin/g_pRenderEngine->getAspectRatio(); - yPos += s_fOSDStatsMargin*0.7; - width -= 2*s_fOSDStatsMargin/g_pRenderEngine->getAspectRatio(); - float widthMax = width; - float rightMargin = xPos + width; - - sprintf(szBuff, "Video Keyframe (%u FPS / ", pVDS->iCurrentVideoFPS); - if ( pActiveModel->isVideoLinkFixedOneWay() || ( ! (pActiveModel->video_link_profiles[pActiveModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_KEYFRAME)) ) - strcat(szBuff, "Fixed KF)"); - else - strcat(szBuff, "Auto KF)"); - - g_pRenderEngine->drawText(xPos, yPos, s_idFontStats, szBuff); - - float y = yPos + height_text*1.2*s_OSDStatsLineSpacing; - - osd_set_colors(); - - int iSlices = camera_get_active_camera_h264_slices(pActiveModel); - - float dxGraph = g_pRenderEngine->textWidth(s_idFontStatsSmall, "88 ms"); - float widthGraph = widthMax - dxGraph; - float widthBar = widthGraph / (float)MAX_FRAMES_SAMPLES; - - - if ( 0 == g_iDeltaVideoInfoBetweenVehicleController ) - if ( g_SM_VideoInfoStatsOutput.uLastIndex > MAX_FRAMES_SAMPLES/2 ) - { - g_iDeltaVideoInfoBetweenVehicleController = g_SM_VideoInfoStatsOutput.uLastIndex - g_VideoInfoStatsFromVehicleCameraOut.uLastIndex; - } - - static u32 s_uLastTimeKeyFrameValueChangedInOSD = 0; - static int s_iLastRequestedKeyFrameMsInOSD = 0; - // To fix or remove - //if ( g_SM_RouterVehiclesRuntimeInfo.vehicles_adaptive_video[iIndexRouterRuntimeInfo].iLastRequestedKeyFrameMs != pVDS->iLastAckKeyframeInterval ) - // s_uLastTimeKeyFrameValueChangedInOSD = g_TimeNow; - if ( s_iLastRequestedKeyFrameMsInOSD != g_SM_RouterVehiclesRuntimeInfo.vehicles_adaptive_video[iIndexRouterRuntimeInfo].iLastRequestedKeyFrameMs ) - { - s_iLastRequestedKeyFrameMsInOSD = g_SM_RouterVehiclesRuntimeInfo.vehicles_adaptive_video[iIndexRouterRuntimeInfo].iLastRequestedKeyFrameMs; - s_uLastTimeKeyFrameValueChangedInOSD = g_TimeNow; - } - bool bShowChanging = false; - if ( g_TimeNow < s_uLastTimeKeyFrameValueChangedInOSD + 1000 ) - bShowChanging = true; - - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Requested Keyframe:"); - if ( pActiveModel->isVideoLinkFixedOneWay() || (!(pActiveModel->video_link_profiles[pActiveModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_KEYFRAME)) ) - strcpy(szBuff, "None, Fixed"); - else - sprintf(szBuff, "%d ms", g_SM_RouterVehiclesRuntimeInfo.vehicles_adaptive_video[iIndexRouterRuntimeInfo].iLastRequestedKeyFrameMs); - if ( bShowChanging ) - g_pRenderEngine->setColors(get_Color_OSDChangedValue()); - g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStats, szBuff); - if ( bShowChanging ) - osd_set_colors(); - y += height_text*s_OSDStatsLineSpacing; - - // To fix or remove - /* - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Ack Keyframe:"); - if ( pVDS->iLastAckKeyframeInterval > 0 ) - sprintf(szBuff, "%d ms", pVDS->iLastAckKeyframeInterval); - else if ( pActiveModel->isVideoLinkFixedOneWay() || ( !(pActiveModel->video_link_profiles[pActiveModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_KEYFRAME)) ) - strcpy(szBuff, "None, Fixed"); - else - sprintf(szBuff, "%d ms", pVDS->iLastAckKeyframeInterval); - */ - - if ( bShowChanging ) - g_pRenderEngine->setColors(get_Color_OSDChangedValue()); - g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStats, szBuff); - if ( bShowChanging ) - osd_set_colors(); - y += height_text*s_OSDStatsLineSpacing; - - - int iKeyframeSizeBitsSum = 0; - int iKeyframeCount = 0; - for( int i=0; i 1 ) - iKeyframeSizeBitsSum /= iKeyframeCount; - - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Recv KF:"); - sprintf(szBuff, "%d ms", (int)pVDS->PHVF.uCurrentVideoKeyframeIntervalMs); - g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStats, szBuff); - y += height_text*s_OSDStatsLineSpacing; - - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Recv KF:"); - sprintf(szBuff, "x%d ms @ %d kbits/keyfr", g_VideoInfoStatsFromVehicleCameraOut.uKeyframeIntervalMs, iKeyframeSizeBitsSum); - g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStats, szBuff); - y += height_text*s_OSDStatsLineSpacing; - - u32 uMaxValue = 0; - u32 uMinValue = MAX_U32; - for( int i=0; i uMaxValue ) - uMaxValue = g_VideoInfoStatsFromVehicleCameraOut.uFramesTypesAndSizes[i] & 0x7F; - } - if ( uMinValue == MAX_U32 ) - uMinValue = 0; - if ( uMaxValue <= uMinValue ) - uMaxValue = uMinValue+4; - - uMinValue *= 8; - uMaxValue *= 8; - - u32 uMaxFrameKb = uMaxValue; - - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Avg/Max Frame size:"); - y += height_text*s_OSDStatsLineSpacing; - sprintf(szBuff, "%d / %u kbits", g_VideoInfoStatsFromVehicleCameraOut.uAverageFrameSize/1000, uMaxFrameKb); - g_pRenderEngine->drawText(xPos, y, s_idFontStats, szBuff); - y += height_text*s_OSDStatsLineSpacing; - - sprintf(szBuff, "%u kbits", g_VideoInfoStatsFromVehicleCameraOut.uAveragePFrameSize/1000); - _osd_stats_draw_line(xPos, rightMargin, y, s_idFontStats, "Avg P-frame size:", szBuff); - y += height_text*s_OSDStatsLineSpacing; - - // End minimal view - //-------------------------------------------------- - if ( pCS->iShowVideoStreamInfoCompactType == 2 ) - return height; - - sprintf(szBuff, "%d/%u", iSlices, g_VideoInfoStatsFromVehicleCameraOut.uDetectedSlices); - _osd_stats_draw_line(xPos, rightMargin, y, s_idFontStats, "Slices (set/detected):", szBuff); - y += height_text*s_OSDStatsLineSpacing; - - //-------------------------------------------------------------------------- - // Compact view - - // kb/frame - - sprintf(szBuff, "Camera source (%u FPS)", g_VideoInfoStatsFromVehicleCameraOut.uDetectedFPS); - g_pRenderEngine->drawText(xPos, y, s_idFontStats, szBuff); - y += height_text*1.2; - - float yBottomGraph = y + hGraph; - yBottomGraph = ((int)(yBottomGraph/g_pRenderEngine->getPixelHeight())) * g_pRenderEngine->getPixelHeight(); - - sprintf(szBuff, "%d kb", (int)uMaxValue); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y-height_text_small*0.6, s_idFontStatsSmall, szBuff); - - sprintf(szBuff, "%d kb", (int)(uMaxValue+uMinValue)/2); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y+hGraph*0.5-height_text_small*0.6, s_idFontStatsSmall,szBuff); - - sprintf(szBuff, "%d kb", (int)uMinValue); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y+hGraph-height_text_small*0.6, s_idFontStatsSmall,szBuff); - - g_pRenderEngine->setStrokeSize(OSD_STRIKE_WIDTH); - g_pRenderEngine->drawLine(xPos, y, xPos + widthGraph, y); - g_pRenderEngine->drawLine(xPos, y+hGraph, xPos + widthGraph, y+hGraph); - - for( float i=0; i<=widthGraph-2.0*wPixel; i+= 5*wPixel ) - g_pRenderEngine->drawLine(xPos+i, y+0.5*hGraph, xPos + i + 2.0*wPixel, y+0.5*hGraph); - - g_pRenderEngine->setStrokeSize(2.1); - - float xBarStart = xPos; - for( int i=0; isetStroke(70,70,250,0.96); - g_pRenderEngine->setFill(70,70,250,0.96); - g_pRenderEngine->setStrokeSize(2.1); - } - - g_pRenderEngine->drawRect(xBarStart, y+hGraph-hBar, widthBar, hBar); - - if ( g_VideoInfoStatsFromVehicleCameraOut.uFramesTypesAndSizes[iRealIndex] & (1<<7) ) - { - osd_set_colors(); - g_pRenderEngine->setStrokeSize(2.1); - } - } - xBarStart += widthBar; - - if ( iRealIndex == (int)g_VideoInfoStatsFromVehicleCameraOut.uLastIndex ) - { - g_pRenderEngine->setStroke(250,250,50,0.9); - g_pRenderEngine->drawLine(xBarStart, y, xBarStart, y+hGraph); - osd_set_colors(); - g_pRenderEngine->setStrokeSize(2.1); - } - } - - y += hGraph + height_text*0.4; - - y += height_text*0.4; - - // ------------------------------------------------------------------------ - // Camera source info - - - yBottomGraph = y + hGraph; - yBottomGraph = ((int)(yBottomGraph/g_pRenderEngine->getPixelHeight())) * g_pRenderEngine->getPixelHeight(); - - uMaxValue = 0; - uMinValue = MAX_U32; - for( int i=0; i uMaxValue ) - uMaxValue = (g_VideoInfoStatsFromVehicleCameraOut.uFramesDuration[i] & 0x7F); - } - if ( uMinValue == MAX_U32 ) - uMinValue = 0; - if ( uMaxValue <= uMinValue ) - uMaxValue = uMinValue+4; - - sprintf(szBuff, "%d ms", (int)uMaxValue); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y-height_text_small*0.6, s_idFontStatsSmall, szBuff); - - sprintf(szBuff, "%d ms", (int)(uMaxValue+uMinValue)/2); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y+hGraph*0.5-height_text_small*0.6, s_idFontStatsSmall,szBuff); - - sprintf(szBuff, "%d ms", (int)uMinValue); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y+hGraph-height_text_small*0.6, s_idFontStatsSmall,szBuff); - - g_pRenderEngine->setStrokeSize(OSD_STRIKE_WIDTH); - g_pRenderEngine->drawLine(xPos, y, xPos + widthGraph, y); - g_pRenderEngine->drawLine(xPos, y+hGraph, xPos + widthGraph, y+hGraph); - - for( float i=0; i<=widthGraph-2.0*wPixel; i+= 5*wPixel ) - g_pRenderEngine->drawLine(xPos+i, y+0.5*hGraph, xPos + i + 2.0*wPixel, y+0.5*hGraph); - - g_pRenderEngine->setStrokeSize(2.1); - - u32 uPrevValue = 0; - int iIndexPrev = 0; - xBarStart = xPos; - for( int i=0; isetStroke(70,70,250,0.96); - g_pRenderEngine->setFill(70,70,250,0.96); - g_pRenderEngine->setStrokeSize(2.1); - } - - g_pRenderEngine->drawLine(xBarStart, y+hGraph-hBar, xBarStart+widthBar, y+hGraph-hBar); - - if ( (i != 0) && ( (g_VideoInfoStatsFromVehicleCameraOut.uFramesDuration[iRealIndex] & 0x7F) != uPrevValue ) ) - { - float hBarPrev = hGraph*(float)(uPrevValue-uMinValue)/(float)(uMaxValue - uMinValue); - - if ( iIndexPrev >= 0 && iIndexPrev < MAX_FRAMES_SAMPLES ) - if ( g_VideoInfoStatsFromVehicleCameraOut.uFramesTypesAndSizes[iIndexPrev] & (1<<7) ) - { - g_pRenderEngine->setStroke(70,70,250,0.96); - g_pRenderEngine->setFill(70,70,250,0.96); - g_pRenderEngine->setStrokeSize(2.1); - } - - g_pRenderEngine->drawLine(xBarStart, y+hGraph-hBarPrev, xBarStart, y+hGraph-hBar); - - if ( iIndexPrev >= 0 && iIndexPrev < MAX_FRAMES_SAMPLES ) - if ( g_VideoInfoStatsFromVehicleCameraOut.uFramesTypesAndSizes[iIndexPrev] & (1<<7) ) - { - osd_set_colors(); - g_pRenderEngine->setStrokeSize(2.1); - } - } - - if ( g_VideoInfoStatsFromVehicleCameraOut.uFramesDuration[iRealIndex] & (1<<7) ) - { - g_pRenderEngine->setStroke(70,250,70,1); - g_pRenderEngine->drawLine(xBarStart, y, xBarStart, y+hGraph); - osd_set_colors(); - } - - if ( g_VideoInfoStatsFromVehicleCameraOut.uFramesTypesAndSizes[iRealIndex] & (1<<7) ) - { - osd_set_colors(); - g_pRenderEngine->setStrokeSize(2.1); - } - } - uPrevValue = g_VideoInfoStatsFromVehicleCameraOut.uFramesDuration[iRealIndex] & 0x7F; - iIndexPrev = iRealIndex; - xBarStart += widthBar; - - if ( iRealIndex == (int)g_VideoInfoStatsFromVehicleCameraOut.uLastIndex ) - { - g_pRenderEngine->setStroke(250,250,50,0.9); - g_pRenderEngine->drawLine(xBarStart, y, xBarStart, y+hGraph); - osd_set_colors(); - g_pRenderEngine->setStrokeSize(2.1); - } - } - - y += hGraph + height_text*0.4; + char szBuff[128]; + osd_set_colors_background_fill(g_fOSDStatsBgTransparency); + g_pRenderEngine->drawRoundRect(xPos, yPos, width, height, 1.5*POPUP_ROUND_MARGIN); + osd_set_colors(); - g_pRenderEngine->drawText(xPos, y, s_idFontStatsSmall, "Avg/Min/Max frame:"); - sprintf(szBuff, "%d / %d / %d ms", g_VideoInfoStatsFromVehicleCameraOut.uAverageFrameTime, uMinValue, uMaxValue); - g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStatsSmall, szBuff); - y += height_text_small*s_OSDStatsLineSpacing; + xPos += s_fOSDStatsMargin*scale/g_pRenderEngine->getAspectRatio(); + yPos += s_fOSDStatsMargin*scale*0.7; + width -= 2*s_fOSDStatsMargin*scale/g_pRenderEngine->getAspectRatio(); + float rightMargin = xPos + width; + + g_pRenderEngine->drawText(xPos, yPos, s_idFontStats, "Efficiency Stats"); - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Max deviation from avg:"); - strcpy(szBuff, "N/A"); - sprintf(szBuff, "%d ms", g_VideoInfoStatsFromVehicleCameraOut.uMaxFrameDeltaTime); + float y = yPos + height_text*1.3*s_OSDStatsLineSpacing; + + osd_set_colors(); + + g_pRenderEngine->drawText(xPos, y, s_idFontStats, "mA/km:"); + float eff = 0.0; + if ( NULL != g_pCurrentModel && g_pCurrentModel->m_Stats.uCurrentFlightDistance > 500 ) + eff = (float)g_pCurrentModel->m_Stats.uCurrentFlightTotalCurrent/10.0/((float)g_pCurrentModel->m_Stats.uCurrentFlightDistance/100.0/1000.0); + sprintf(szBuff, "%d", (int)eff); g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStats, szBuff); y += height_text*s_OSDStatsLineSpacing; - // End compact mode - //----------------------------------------------- - if ( pCS->iShowVideoStreamInfoCompactType == 1 ) - return height; + g_pRenderEngine->drawText(xPos, y, s_idFontStats, "mA/h:"); + eff = 0; + if ( NULL != g_pCurrentModel && g_pCurrentModel->m_Stats.uCurrentFlightTime > 0 ) + eff = ( (float)g_pCurrentModel->m_Stats.uCurrentFlightTotalCurrent/10.0/((float)g_pCurrentModel->m_Stats.uCurrentFlightTime))*3600.0; + sprintf(szBuff, "%d", (int)eff); + g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStats, szBuff); + y += height_text*s_OSDStatsLineSpacing; - //----------------------------------------- - // Full mode - y += height_text*0.4; - + return height; +} - // ----------------------------------------------------------- - // Radio output info +float osd_render_stats_video_stream_h264_frames_info_get_height() +{ + float height_text = g_pRenderEngine->textHeight(s_idFontStats); + float height = 2.0 *s_fOSDStatsMargin*1.1 + 1.1*height_text*s_OSDStatsLineSpacing; - sprintf(szBuff, "Radio output (%u FPS)", g_VideoInfoStatsFromVehicleRadioOut.uDetectedFPS); - g_pRenderEngine->drawText(xPos, y, s_idFontStats, szBuff); - y += height_text*1.2; + float hGraph = height_text*4.0; - yBottomGraph = y + hGraph; - yBottomGraph = ((int)(yBottomGraph/g_pRenderEngine->getPixelHeight())) * g_pRenderEngine->getPixelHeight(); - - uMaxValue = 0; - uMinValue = MAX_U32; - for( int i=0; i uMaxValue ) - uMaxValue = (g_VideoInfoStatsFromVehicleRadioOut.uFramesDuration[i] & 0x7F); - } - if ( uMinValue == MAX_U32 ) - uMinValue = 0; - if ( uMaxValue <= uMinValue ) - uMaxValue = uMinValue+4; - + ControllerSettings* pCS = get_ControllerSettings(); - sprintf(szBuff, "%d ms", (int)uMaxValue); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y-height_text_small*0.6, s_idFontStatsSmall, szBuff); - - sprintf(szBuff, "%d ms", (int)(uMaxValue+uMinValue)/2); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y+hGraph*0.5-height_text_small*0.6, s_idFontStatsSmall,szBuff); - - sprintf(szBuff, "%d ms", (int)uMinValue); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y+hGraph-height_text_small*0.6, s_idFontStatsSmall,szBuff); - - g_pRenderEngine->setStrokeSize(OSD_STRIKE_WIDTH); - g_pRenderEngine->drawLine(xPos, y, xPos + widthGraph, y); - g_pRenderEngine->drawLine(xPos, y+hGraph, xPos +widthGraph, y+hGraph); + // stats + height += 5.0 * height_text*s_OSDStatsLineSpacing; - for( float i=0; i<=widthGraph-2.0*wPixel; i+= 5*wPixel ) - g_pRenderEngine->drawLine(xPos+i, y+0.5*hGraph, xPos + i + 2.0*wPixel, y+0.5*hGraph); + height += 0.5*height_text; + height += hGraph; + return height; +} + +float osd_render_stats_video_stream_h264_frames_info_get_width() +{ + if ( g_fOSDStatsForcePanelWidth > 0.01 ) + return g_fOSDStatsForcePanelWidth; + float width = g_pRenderEngine->textWidth(s_idFontStats, "AAAAAAAA AAAAA AAAAA AAA"); + width += 2.0*s_fOSDStatsMargin/g_pRenderEngine->getAspectRatio(); + return width; +} + +float osd_render_stats_video_stream_h264_frames_info(float xPos, float yPos) +{ + Model* pActiveModel = osd_get_current_data_source_vehicle_model(); + u32 uActiveVehicleId = osd_get_current_data_source_vehicle_id(); - g_pRenderEngine->setStrokeSize(2.1); + shared_mem_video_stream_stats* pVDS = NULL; + int iIndexRouterRuntimeInfo = -1; - - uPrevValue = 0; - iIndexPrev = 0; - xBarStart = xPos; - for( int i=0; isetStroke(70,70,250,0.96); - g_pRenderEngine->setFill(70,70,250,0.96); - g_pRenderEngine->setStrokeSize(2.1); - } - - g_pRenderEngine->drawLine(xBarStart, y+hGraph-hBar, xBarStart+widthBar, y+hGraph-hBar); - - if ( (i != 0) && ( (g_VideoInfoStatsFromVehicleRadioOut.uFramesDuration[iRealIndex] & 0x7F) != uPrevValue ) ) - { - float hBarPrev = hGraph*(float)(uPrevValue-uMinValue)/(float)(uMaxValue - uMinValue); - - if ( iIndexPrev >= 0 && iIndexPrev < MAX_FRAMES_SAMPLES ) - if ( g_VideoInfoStatsFromVehicleRadioOut.uFramesTypesAndSizes[iIndexPrev] & (1<<7) ) - { - g_pRenderEngine->setStroke(70,70,250,0.96); - g_pRenderEngine->setFill(70,70,250,0.96); - g_pRenderEngine->setStrokeSize(2.1); - } - - g_pRenderEngine->drawLine(xBarStart, y+hGraph-hBarPrev, xBarStart, y+hGraph-hBar); - - if ( iIndexPrev >= 0 && iIndexPrev < MAX_FRAMES_SAMPLES ) - if ( g_VideoInfoStatsFromVehicleRadioOut.uFramesTypesAndSizes[iIndexPrev] & (1<<7) ) - { - osd_set_colors(); - g_pRenderEngine->setStrokeSize(2.1); - } - } - - if ( g_VideoInfoStatsFromVehicleRadioOut.uFramesTypesAndSizes[iRealIndex] & (1<<7) ) - { - osd_set_colors(); - g_pRenderEngine->setStrokeSize(2.1); - } - } - uPrevValue = g_VideoInfoStatsFromVehicleRadioOut.uFramesDuration[iRealIndex] & 0x7F; - iIndexPrev = iRealIndex; - xBarStart += widthBar; - - if ( iRealIndex == (int)g_VideoInfoStatsFromVehicleRadioOut.uLastIndex ) - { - g_pRenderEngine->setStroke(250,250,50,0.9); - g_pRenderEngine->drawLine(xBarStart, y, xBarStart, y+hGraph); - osd_set_colors(); - g_pRenderEngine->setStrokeSize(2.1); - } + if ( g_SM_VideoDecodeStats.video_streams[i].uVehicleId == uActiveVehicleId ) + pVDS = &(g_SM_VideoDecodeStats.video_streams[i]); } + for( int i=0; idrawText(xPos, y, s_idFontStatsSmall, "Avg/Min/Max frame:"); - strcpy(szBuff, "N/A"); - sprintf(szBuff, "%d / %d / %d ms", g_VideoInfoStatsFromVehicleRadioOut.uAverageFrameTime, uMinValue, uMaxValue); - g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStatsSmall, szBuff); - y += height_text_small*s_OSDStatsLineSpacing; + ControllerSettings* pCS = get_ControllerSettings(); - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Max deviation from avg:"); - strcpy(szBuff, "N/A"); - sprintf(szBuff, "%d ms", g_VideoInfoStatsFromVehicleRadioOut.uMaxFrameDeltaTime); - g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStats, szBuff); - y += height_text*s_OSDStatsLineSpacing; + float height_text = g_pRenderEngine->textHeight(s_idFontStats); + float height_text_small = g_pRenderEngine->textHeight(s_idFontStatsSmall); - y += height_text*0.4; + float hGraph = height_text*4.0; + float wPixel = g_pRenderEngine->getPixelWidth(); - - // ----------------------------------------------------------- - // Radio In graph + float width = osd_render_stats_video_stream_h264_frames_info_get_width(); + float height = osd_render_stats_video_stream_h264_frames_info_get_height(); - sprintf(szBuff, "Radio In (%u FPS)", g_SM_VideoInfoStatsRadioIn.uDetectedFPS); + char szBuff[128]; - g_pRenderEngine->drawText(xPos, y, s_idFontStats, szBuff); - y += height_text*1.2; + osd_set_colors_background_fill(g_fOSDStatsBgTransparency); + g_pRenderEngine->drawRoundRect(xPos, yPos, width, height, 1.5*POPUP_ROUND_MARGIN); + osd_set_colors(); + g_pRenderEngine->setColors(get_Color_Dev()); - yBottomGraph = y + hGraph; - yBottomGraph = ((int)(yBottomGraph/g_pRenderEngine->getPixelHeight())) * g_pRenderEngine->getPixelHeight(); - - uMaxValue = 0; - uMinValue = MAX_U32; - for( int i=0; i uMaxValue ) - uMaxValue = (g_SM_VideoInfoStatsRadioIn.uFramesDuration[i] & 0x7F); - } - if ( uMinValue == MAX_U32 ) - uMinValue = 0; - if ( uMaxValue <= uMinValue ) - uMaxValue = uMinValue+4; - - sprintf(szBuff, "%d ms", (int)uMaxValue); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y-height_text_small*0.6, s_idFontStatsSmall, szBuff); - - sprintf(szBuff, "%d ms", (int)(uMaxValue+uMinValue)/2); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y+hGraph*0.5-height_text_small*0.6, s_idFontStatsSmall,szBuff); + xPos += s_fOSDStatsMargin/g_pRenderEngine->getAspectRatio(); + yPos += s_fOSDStatsMargin*0.7; + width -= 2*s_fOSDStatsMargin/g_pRenderEngine->getAspectRatio(); + float widthMax = width; + float rightMargin = xPos + width; + + sprintf(szBuff, "Video Frames %u FPS / ", pVDS->iCurrentVideoFPS); + if ( pActiveModel->isVideoLinkFixedOneWay() || ( ! (pActiveModel->video_link_profiles[pActiveModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_KEYFRAME)) ) + strcat(szBuff, "Fixed KF"); + else + strcat(szBuff, "Auto KF"); - sprintf(szBuff, "%d ms", (int)uMinValue); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y+hGraph-height_text_small*0.6, s_idFontStatsSmall,szBuff); + g_pRenderEngine->drawText(xPos, yPos, s_idFontStats, szBuff); - g_pRenderEngine->setStrokeSize(OSD_STRIKE_WIDTH); - g_pRenderEngine->drawLine(xPos, y, xPos + widthGraph, y); - g_pRenderEngine->drawLine(xPos, y+hGraph, xPos +widthGraph, y+hGraph); + float y = yPos + height_text*1.2*s_OSDStatsLineSpacing; - for( float i=0; i<=widthGraph-2.0*wPixel; i+= 5*wPixel ) - g_pRenderEngine->drawLine(xPos+i, y+0.5*hGraph, xPos + i + 2.0*wPixel, y+0.5*hGraph); - - g_pRenderEngine->setStrokeSize(2.1); + int iSlices = camera_get_active_camera_h264_slices(pActiveModel); - uPrevValue = 0; - iIndexPrev = 0; - xBarStart = xPos; - for( int i=0; itextWidth(s_idFontStatsSmall, "888 kb"); + float widthGraph = widthMax - dxGraph; + float widthBar = widthGraph / (float)MAX_FRAMES_SAMPLES; + + static u32 s_uLastTimeKeyFrameValueChangedInOSD = 0; + static u32 s_uLastKeyFrameValueInOSD = 0; + if ( s_uLastKeyFrameValueInOSD != pVDS->PHVF.uCurrentVideoKeyframeIntervalMs ) { - if ( i != (int)g_SM_VideoInfoStatsRadioIn.uLastIndex+1 ) - { - float hBar = hGraph*(float)((g_SM_VideoInfoStatsRadioIn.uFramesDuration[i] & 0x7F) -uMinValue)/(float)(uMaxValue - uMinValue); - - if ( g_SM_VideoInfoStatsRadioIn.uFramesTypesAndSizes[i] & (1<<7) ) - { - g_pRenderEngine->setStroke(70,70,250,0.96); - g_pRenderEngine->setFill(70,70,250,0.96); - g_pRenderEngine->setStrokeSize(2.1); - } - - g_pRenderEngine->drawLine(xBarStart, y+hGraph-hBar, xBarStart+widthBar, y+hGraph-hBar); - - - if ( (i != 0) && ( (g_SM_VideoInfoStatsRadioIn.uFramesDuration[i] &0x7F) != uPrevValue ) ) - { - float hBarPrev = hGraph*(float)(uPrevValue-uMinValue)/(float)(uMaxValue - uMinValue); - - if ( iIndexPrev >= 0 && iIndexPrev < MAX_FRAMES_SAMPLES ) - if ( g_SM_VideoInfoStatsRadioIn.uFramesTypesAndSizes[iIndexPrev] & (1<<7) ) - { - g_pRenderEngine->setStroke(70,70,250,0.96); - g_pRenderEngine->setFill(70,70,250,0.96); - g_pRenderEngine->setStrokeSize(2.1); - } - - g_pRenderEngine->drawLine(xBarStart, y+hGraph-hBarPrev, xBarStart, y+hGraph-hBar); - - if ( iIndexPrev >= 0 && iIndexPrev < MAX_FRAMES_SAMPLES ) - if ( g_SM_VideoInfoStatsRadioIn.uFramesTypesAndSizes[iIndexPrev] & (1<<7) ) - { - osd_set_colors(); - g_pRenderEngine->setStrokeSize(2.1); - } - } - - if ( g_SM_VideoInfoStatsRadioIn.uFramesTypesAndSizes[i] & (1<<7) ) - { - osd_set_colors(); - g_pRenderEngine->setStrokeSize(2.1); - } - } - - uPrevValue = g_SM_VideoInfoStatsRadioIn.uFramesDuration[i] & 0x7F; - iIndexPrev = i; - xBarStart += widthBar; - - if ( i == (int)g_SM_VideoInfoStatsRadioIn.uLastIndex ) - { - g_pRenderEngine->setStroke(250,250,50,0.9); - g_pRenderEngine->drawLine(xBarStart, y, xBarStart, y+hGraph); - osd_set_colors(); - g_pRenderEngine->setStrokeSize(2.1); - } + s_uLastKeyFrameValueInOSD = pVDS->PHVF.uCurrentVideoKeyframeIntervalMs; + s_uLastTimeKeyFrameValueChangedInOSD = g_TimeNow; } + bool bShowChanging = false; + if ( g_TimeNow < s_uLastTimeKeyFrameValueChangedInOSD + 1000 ) + bShowChanging = true; - y += hGraph + height_text*0.4; - - g_pRenderEngine->drawText(xPos, y, s_idFontStatsSmall, "Avg/Min/Max frame:"); - sprintf(szBuff, "%d / %d / %d ms", g_SM_VideoInfoStatsRadioIn.uAverageFrameTime, uMinValue, uMaxValue); - g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStatsSmall, szBuff); - y += height_text_small*s_OSDStatsLineSpacing; - - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Max deviation from avg:"); - sprintf(szBuff, "%d ms", g_SM_VideoInfoStatsRadioIn.uMaxFrameDeltaTime); + g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Recv KF:"); + sprintf(szBuff, "%d ms", (int)pVDS->PHVF.uCurrentVideoKeyframeIntervalMs); + if ( bShowChanging ) + g_pRenderEngine->setColors(get_Color_OSDChangedValue()); g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStats, szBuff); + if ( bShowChanging ) + { + osd_set_colors(); + g_pRenderEngine->setColors(get_Color_Dev()); + } y += height_text*s_OSDStatsLineSpacing; + sprintf(szBuff, "%u kBytes (%d pkts)", (g_SM_VideoFramesStatsOutput.uAverageIFrameSizeBytes)/1000, 1 + g_SM_VideoFramesStatsOutput.uAverageIFrameSizeBytes / g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].video_data_length); + _osd_stats_draw_line(xPos, rightMargin, y, s_idFontStats, "Avg Iframe size:", szBuff); + y += height_text*s_OSDStatsLineSpacing; - // ----------------------------------------------------------- - // Player output info + sprintf(szBuff, "%u kBytes (%d pkts)", (g_SM_VideoFramesStatsOutput.uAveragePFrameSizeBytes)/1000, 1 + g_SM_VideoFramesStatsOutput.uAveragePFrameSizeBytes / g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].video_data_length); + _osd_stats_draw_line(xPos, rightMargin, y, s_idFontStats, "Avg Pframe size:", szBuff); + y += height_text*s_OSDStatsLineSpacing; - sprintf(szBuff, "Player output (%u FPS)", g_SM_VideoInfoStatsOutput.uDetectedFPS); - g_pRenderEngine->drawText(xPos, y, s_idFontStats, szBuff); - y += height_text*1.2; + // End minimal view + //-------------------------------------------------- + //if ( pCS->iShowVideoStreamInfoCompactType == 2 ) + // return height; - yBottomGraph = y + hGraph; - yBottomGraph = ((int)(yBottomGraph/g_pRenderEngine->getPixelHeight())) * g_pRenderEngine->getPixelHeight(); - - uMaxValue = 0; - uMinValue = MAX_U32; + sprintf(szBuff, "%d/%u", iSlices, g_SM_VideoFramesStatsOutput.uDetectedSlices); + _osd_stats_draw_line(xPos, rightMargin, y, s_idFontStats, "Slices (set/detected):", szBuff); + y += height_text*s_OSDStatsLineSpacing; + + sprintf(szBuff, "%d",g_SM_VideoFramesStatsOutput.uDetectedFPS); + _osd_stats_draw_line(xPos, rightMargin, y, s_idFontStats, "Detected FPS:", szBuff); + y += height_text*s_OSDStatsLineSpacing; + y += height_text*0.5; + u32 uMaxValue = 0; + u32 uMinValue = MAX_U32; for( int i=0; i uMaxValue ) - uMaxValue = (g_SM_VideoInfoStatsOutput.uFramesDuration[i] & 0x7F); + if ( g_SM_VideoFramesStatsOutput.uFramesSizes[i] < uMinValue ) + uMinValue = g_SM_VideoFramesStatsOutput.uFramesSizes[i]; + if ( g_SM_VideoFramesStatsOutput.uFramesSizes[i] > uMaxValue ) + uMaxValue = g_SM_VideoFramesStatsOutput.uFramesSizes[i]; } if ( uMinValue == MAX_U32 ) uMinValue = 0; if ( uMaxValue <= uMinValue ) uMaxValue = uMinValue+4; + + float yBottomGraph = y + hGraph; + yBottomGraph = ((int)(yBottomGraph/g_pRenderEngine->getPixelHeight())) * g_pRenderEngine->getPixelHeight(); + + sprintf(szBuff, "%d kB", (int)uMaxValue); + g_pRenderEngine->drawText(xPos+widthGraph+8.0*wPixel, y-height_text_small*0.1, s_idFontStatsSmall, szBuff); - sprintf(szBuff, "%d ms", (int)uMaxValue); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y-height_text_small*0.6, s_idFontStatsSmall, szBuff); - - sprintf(szBuff, "%d ms", (int)(uMaxValue+uMinValue)/2); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y+hGraph*0.5-height_text_small*0.6, s_idFontStatsSmall,szBuff); + sprintf(szBuff, "%d kB", (int)(uMaxValue+uMinValue)/2); + g_pRenderEngine->drawText(xPos+widthGraph+8.0*wPixel, y+hGraph*0.5-height_text_small*0.6, s_idFontStatsSmall,szBuff); - sprintf(szBuff, "%d ms", (int)uMinValue); - g_pRenderEngine->drawText(xPos+widthGraph+4.0*wPixel, y+hGraph-height_text_small*0.6, s_idFontStatsSmall,szBuff); + sprintf(szBuff, "%d kB", (int)uMinValue); + g_pRenderEngine->drawText(xPos+widthGraph+8.0*wPixel, y+hGraph-height_text_small*0.9, s_idFontStatsSmall,szBuff); + g_pRenderEngine->setColors(get_Color_Dev()); g_pRenderEngine->setStrokeSize(OSD_STRIKE_WIDTH); g_pRenderEngine->drawLine(xPos, y, xPos + widthGraph, y); - g_pRenderEngine->drawLine(xPos, y+hGraph, xPos +widthGraph, y+hGraph); + g_pRenderEngine->drawLine(xPos, y+hGraph, xPos + widthGraph, y+hGraph); - for( float i=0; i<=widthGraph-2.0*wPixel; i+= 5*wPixel ) - g_pRenderEngine->drawLine(xPos+i, y+0.5*hGraph, xPos + i + 2.0*wPixel, y+0.5*hGraph); + for( float i=0; i<=widthGraph-2.0*wPixel; i+= 7*wPixel ) + g_pRenderEngine->drawLine(xPos+i, y+0.5*hGraph, xPos + i + 4.0*wPixel, y+0.5*hGraph); g_pRenderEngine->setStrokeSize(2.1); - uPrevValue = 0; - iIndexPrev = 0; - xBarStart = xPos; + float xBarStart = xPos; + double* pc1 = get_Color_OSDText(); + for( int i=0; isetStroke(70,70,250,0.96); - g_pRenderEngine->setFill(70,70,250,0.96); - g_pRenderEngine->setStrokeSize(2.1); - } - - g_pRenderEngine->drawLine(xBarStart, y+hGraph-hBar, xBarStart+widthBar, y+hGraph-hBar); - - - if ( (i != 0) && ( (g_SM_VideoInfoStatsOutput.uFramesDuration[i] & 0x7F) != uPrevValue ) ) - { - float hBarPrev = hGraph*(float)(uPrevValue-uMinValue)/(float)(uMaxValue - uMinValue); - - if ( iIndexPrev >= 0 && iIndexPrev < MAX_FRAMES_SAMPLES ) - if ( g_SM_VideoInfoStatsOutput.uFramesTypesAndSizes[iIndexPrev] & (1<<7) ) - { - g_pRenderEngine->setStroke(70,70,250,0.96); - g_pRenderEngine->setFill(70,70,250,0.96); - g_pRenderEngine->setStrokeSize(2.1); - } - - g_pRenderEngine->drawLine(xBarStart, y+hGraph-hBarPrev, xBarStart, y+hGraph-hBar); - - if ( iIndexPrev >= 0 && iIndexPrev < MAX_FRAMES_SAMPLES ) - if ( g_SM_VideoInfoStatsOutput.uFramesTypesAndSizes[iIndexPrev] & (1<<7) ) - { - osd_set_colors(); - g_pRenderEngine->setStrokeSize(2.1); - } - } - - if ( g_SM_VideoInfoStatsOutput.uFramesTypesAndSizes[i] & (1<<7) ) - { - osd_set_colors(); - g_pRenderEngine->setStrokeSize(2.1); - } + g_pRenderEngine->setStroke(250,250,50,0.9); + g_pRenderEngine->drawLine(xBarStart, y, xBarStart, y+hGraph); + osd_set_colors(); + xBarStart += widthBar; + continue; } - uPrevValue = g_SM_VideoInfoStatsOutput.uFramesDuration[i] & 0x7F; - iIndexPrev = i; - xBarStart += widthBar; + if ( g_SM_VideoFramesStatsOutput.uFramesSizes[i] == 0 ) + { + xBarStart += widthBar; + continue; + } - if ( i == (int)g_SM_VideoInfoStatsOutput.uLastIndex ) + int iFrameType = (g_SM_VideoFramesStatsOutput.uFramesTypesAndDuration[i] & 0xC0) >> 6; + u32 uValue = g_SM_VideoFramesStatsOutput.uFramesSizes[i]; + float hBar = (hGraph * (float)uValue) / (float)uMaxValue; + if ( iFrameType == 1 ) { + g_pRenderEngine->setFill(50,70,250,0.9); + g_pRenderEngine->setStroke(50,70,250,0.9); + } + else if ( iFrameType != 0 ) + { + g_pRenderEngine->setFill(250,250,50,0.9); g_pRenderEngine->setStroke(250,250,50,0.9); - g_pRenderEngine->drawLine(xBarStart, y, xBarStart, y+hGraph); - osd_set_colors(); - g_pRenderEngine->setStrokeSize(2.1); } + else + { + g_pRenderEngine->setFill(pc1); + g_pRenderEngine->setStroke(pc1[0], pc1[1], pc1[2], pc1[3]); + } + g_pRenderEngine->drawRect(xBarStart, yBottomGraph - hBar, widthBar, hBar); + xBarStart += widthBar; } + osd_set_colors(); y += hGraph + height_text*0.4; - - g_pRenderEngine->drawText(xPos, y, s_idFontStatsSmall, "Avg/Min/Max frame:"); - sprintf(szBuff, "%d / %d / %d ms", g_SM_VideoInfoStatsOutput.uAverageFrameTime, uMinValue, uMaxValue); - g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStatsSmall, szBuff); - y += height_text_small*s_OSDStatsLineSpacing; - - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Max deviation from avg:"); - sprintf(szBuff, "%d ms", g_SM_VideoInfoStatsOutput.uMaxFrameDeltaTime); - g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStats, szBuff); - y += height_text*s_OSDStatsLineSpacing; - - - // ------------------------- - // Stats - - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Deviation cam/tx/rx now:"); - y += height_text*s_OSDStatsLineSpacing; - - sprintf(szBuff, "%u / %u / %d / %d ms", g_VideoInfoStatsFromVehicleCameraOut.uMaxFrameDeltaTime, g_VideoInfoStatsFromVehicleRadioOut.uMaxFrameDeltaTime, g_SM_VideoInfoStatsRadioIn.uMaxFrameDeltaTime, g_SM_VideoInfoStatsOutput.uMaxFrameDeltaTime ); - g_pRenderEngine->drawText(xPos, y, s_idFontStats, szBuff); - y += height_text*s_OSDStatsLineSpacing; - - if ( g_TimeNow > g_RouterIsReadyTimestamp + 6000 ) - { - if ( g_VideoInfoStatsFromVehicleCameraOut.uMaxFrameDeltaTime > s_uOSDMaxFrameDeviationCamera ) - s_uOSDMaxFrameDeviationCamera = g_VideoInfoStatsFromVehicleCameraOut.uMaxFrameDeltaTime; - if ( g_VideoInfoStatsFromVehicleRadioOut.uMaxFrameDeltaTime > s_uOSDMaxFrameDeviationTx ) - s_uOSDMaxFrameDeviationTx = g_VideoInfoStatsFromVehicleRadioOut.uMaxFrameDeltaTime; - - if ( g_SM_VideoInfoStatsRadioIn.uMaxFrameDeltaTime > s_uOSDMaxFrameDeviationRx ) - s_uOSDMaxFrameDeviationRx = g_SM_VideoInfoStatsRadioIn.uMaxFrameDeltaTime; - - if ( g_SM_VideoInfoStatsOutput.uMaxFrameDeltaTime > s_uOSDMaxFrameDeviationPlayer ) - s_uOSDMaxFrameDeviationPlayer = g_SM_VideoInfoStatsOutput.uMaxFrameDeltaTime; - } - - g_pRenderEngine->drawText(xPos, y, s_idFontStats, "Max dev cam/tx/rx all:"); - y += height_text*s_OSDStatsLineSpacing; - - sprintf(szBuff, "%u / %u / %d / %d ms", s_uOSDMaxFrameDeviationCamera, s_uOSDMaxFrameDeviationTx, s_uOSDMaxFrameDeviationRx, s_uOSDMaxFrameDeviationPlayer ); - g_pRenderEngine->drawText(xPos, y, s_idFontStats, szBuff); - y += height_text*s_OSDStatsLineSpacing; - return height; } @@ -4242,22 +3307,21 @@ void _osd_render_stats_panels_horizontal() xStats -= osd_render_stats_video_bitrate_history_get_width() + xSpacing; } - // To fix or remove - /* + if ( s_bDebugStatsShowAll || (g_pCurrentModel->osd_params.osd_flags2[osd_get_current_layout_index()] & OSD_FLAG2_SHOW_STATS_VIDEO) ) { - float hStat = osd_render_stats_video_decode_get_height(g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, &g_SM_VDS_history, &g_SM_ControllerRetransmissionsStats, fStatsSize); - osd_render_stats_video_decode(xStats, yStats-hStat, g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, &g_SM_VDS_history, &g_SM_ControllerRetransmissionsStats, fStatsSize); - xStats -= osd_render_stats_video_decode_get_width(g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, &g_SM_VDS_history, &g_SM_ControllerRetransmissionsStats, fStatsSize) + xSpacing; + float hStat = osd_render_stats_video_decode_get_height(g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, fStatsSize); + osd_render_stats_video_decode(xStats, yStats-hStat, g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, fStatsSize); + xStats -= osd_render_stats_video_decode_get_width(g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, fStatsSize) + xSpacing; if ( p->iDebugShowVideoSnapshotOnDiscard ) if ( s_uOSDSnapshotTakeTime > 1 && g_TimeNow < s_uOSDSnapshotTakeTime + 15000 ) { - hStat = osd_render_stats_video_decode_get_height(g_pCurrentModel->bDeveloperMode, true, &s_OSDSnapshot_RadioStats, &s_OSDSnapshot_VideoDecodeStats, &s_OSDSnapshot_VideoDecodeHist, &s_OSDSnapshot_ControllerVideoRetransmissionsStats, fStatsSize); - osd_render_stats_video_decode(xStats, yStats-hStat, g_pCurrentModel->bDeveloperMode, true, &s_OSDSnapshot_RadioStats, &s_OSDSnapshot_VideoDecodeStats, &s_OSDSnapshot_VideoDecodeHist, &s_OSDSnapshot_ControllerVideoRetransmissionsStats, fStatsSize); - xStats -= osd_render_stats_video_decode_get_width(g_pCurrentModel->bDeveloperMode, true, &s_OSDSnapshot_RadioStats, &s_OSDSnapshot_VideoDecodeStats, &s_OSDSnapshot_VideoDecodeHist, &s_OSDSnapshot_ControllerVideoRetransmissionsStats, fStatsSize) + xSpacing; + hStat = osd_render_stats_video_decode_get_height(g_pCurrentModel->bDeveloperMode, true, &s_OSDSnapshot_RadioStats, &s_OSDSnapshot_VideoDecodeStats, fStatsSize); + osd_render_stats_video_decode(xStats, yStats-hStat, g_pCurrentModel->bDeveloperMode, true, &s_OSDSnapshot_RadioStats, &s_OSDSnapshot_VideoDecodeStats, fStatsSize); + xStats -= osd_render_stats_video_decode_get_width(g_pCurrentModel->bDeveloperMode, true, &s_OSDSnapshot_RadioStats, &s_OSDSnapshot_VideoDecodeStats, fStatsSize) + xSpacing; } } - */ + if ( s_bDebugStatsShowAll || (g_pCurrentModel->osd_params.osd_flags2[osd_get_current_layout_index()] & OSD_FLAG2_SHOW_STATS_RADIO_LINKS) ) if ( g_bIsRouterReady ) { @@ -4499,23 +3563,21 @@ void _osd_render_stats_panels_vertical() fMaxColumnWidth = osd_render_stats_rc_get_width(fStatsSize); } - // To fix or remove (retransmissions stats) - /* + if ( s_bDebugStatsShowAll || (g_pCurrentModel->osd_params.osd_flags2[osd_get_current_layout_index()] & OSD_FLAG2_SHOW_STATS_VIDEO) ) { - if ( yStats + osd_render_stats_video_decode_get_height(g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, &g_SM_VDS_history, &g_SM_ControllerRetransmissionsStats, fStatsSize) > yMax ) + if ( yStats + osd_render_stats_video_decode_get_height(g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, fStatsSize) > yMax ) { yStats = yMin; xStats -= fMaxColumnWidth + fSpacingH; fMaxColumnWidth = 0.0; } - osd_render_stats_video_decode(xStats - osd_render_stats_video_decode_get_width(g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, &g_SM_VDS_history, &g_SM_ControllerRetransmissionsStats, fStatsSize), yStats, pCS->iDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, &g_SM_VDS_history, &g_SM_ControllerRetransmissionsStats, fStatsSize); - yStats += osd_render_stats_video_decode_get_height(g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, &g_SM_VDS_history, &g_SM_ControllerRetransmissionsStats, fStatsSize); + osd_render_stats_video_decode(xStats - osd_render_stats_video_decode_get_width(g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, fStatsSize), yStats, pCS->iDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, fStatsSize); + yStats += osd_render_stats_video_decode_get_height(g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, fStatsSize); yStats += fSpacingV; - if ( fMaxColumnWidth < osd_render_stats_video_decode_get_width(g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, &g_SM_VDS_history, &g_SM_ControllerRetransmissionsStats, fStatsSize) ) - fMaxColumnWidth = osd_render_stats_video_decode_get_width(g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, &g_SM_VDS_history, &g_SM_ControllerRetransmissionsStats, fStatsSize); + if ( fMaxColumnWidth < osd_render_stats_video_decode_get_width(g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, fStatsSize) ) + fMaxColumnWidth = osd_render_stats_video_decode_get_width(g_pCurrentModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, fStatsSize); } - */ if ( p->iDebugShowFullRXStats ) osd_render_stats_full_rx_port(); @@ -4973,23 +4035,21 @@ void osd_render_stats_panels() s_iCountOSDStatsBoundingBoxes++; } - // To fix or remove (retransmissions stats) - /* + if ( s_bDebugStatsShowAll || (pModel->osd_params.osd_flags2[osd_get_current_layout_index()] & OSD_FLAG2_SHOW_STATS_VIDEO) ) { s_iOSDStatsBoundingBoxesIds[s_iCountOSDStatsBoundingBoxes] = 6; - s_iOSDStatsBoundingBoxesW[s_iCountOSDStatsBoundingBoxes] = osd_render_stats_video_decode_get_width(pModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, &g_SM_VDS_history, &g_SM_ControllerRetransmissionsStats, 1.0); - s_iOSDStatsBoundingBoxesH[s_iCountOSDStatsBoundingBoxes] = osd_render_stats_video_decode_get_height(pModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, &g_SM_VDS_history, &g_SM_ControllerRetransmissionsStats, 1.0); + s_iOSDStatsBoundingBoxesW[s_iCountOSDStatsBoundingBoxes] = osd_render_stats_video_decode_get_width(pModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, 1.0); + s_iOSDStatsBoundingBoxesH[s_iCountOSDStatsBoundingBoxes] = osd_render_stats_video_decode_get_height(pModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, 1.0); s_iCountOSDStatsBoundingBoxes++; } - */ if ( p->iDebugShowVideoSnapshotOnDiscard ) if ( g_bHasVideoDecodeStatsSnapshot ) { s_iOSDStatsBoundingBoxesIds[s_iCountOSDStatsBoundingBoxes] = 11; - s_iOSDStatsBoundingBoxesW[s_iCountOSDStatsBoundingBoxes] = osd_render_stats_video_decode_get_width(pModel->bDeveloperMode, true, &s_OSDSnapshot_RadioStats, &s_OSDSnapshot_VideoDecodeStats, &s_OSDSnapshot_VideoDecodeHist, 1.0); - s_iOSDStatsBoundingBoxesH[s_iCountOSDStatsBoundingBoxes] = osd_render_stats_video_decode_get_height(pModel->bDeveloperMode, true, &s_OSDSnapshot_RadioStats, &s_OSDSnapshot_VideoDecodeStats, &s_OSDSnapshot_VideoDecodeHist, 1.0); + s_iOSDStatsBoundingBoxesW[s_iCountOSDStatsBoundingBoxes] = osd_render_stats_video_decode_get_width(pModel->bDeveloperMode, true, &s_OSDSnapshot_RadioStats, &s_OSDSnapshot_VideoDecodeStats, 1.0); + s_iOSDStatsBoundingBoxesH[s_iCountOSDStatsBoundingBoxes] = osd_render_stats_video_decode_get_height(pModel->bDeveloperMode, true, &s_OSDSnapshot_RadioStats, &s_OSDSnapshot_VideoDecodeStats, 1.0); s_iCountOSDStatsBoundingBoxes++; } @@ -5001,11 +4061,11 @@ void osd_render_stats_panels() s_iCountOSDStatsBoundingBoxes++; } - if ( s_bDebugStatsShowAll || (pModel->osd_params.osd_flags[osd_get_current_layout_index()] & OSD_FLAG_SHOW_STATS_VIDEO_KEYFRAMES_INFO) ) + if ( s_bDebugStatsShowAll || (pModel->bDeveloperMode && (pModel->osd_params.osd_flags[osd_get_current_layout_index()] & OSD_FLAG_SHOW_STATS_VIDEO_H264_FRAMES_INFO)) ) { s_iOSDStatsBoundingBoxesIds[s_iCountOSDStatsBoundingBoxes] = 12; - s_iOSDStatsBoundingBoxesW[s_iCountOSDStatsBoundingBoxes] = osd_render_stats_video_stream_keyframe_info_get_width(); - s_iOSDStatsBoundingBoxesH[s_iCountOSDStatsBoundingBoxes] = osd_render_stats_video_stream_keyframe_info_get_height(); + s_iOSDStatsBoundingBoxesW[s_iCountOSDStatsBoundingBoxes] = osd_render_stats_video_stream_h264_frames_info_get_width(); + s_iOSDStatsBoundingBoxesH[s_iCountOSDStatsBoundingBoxes] = osd_render_stats_video_stream_h264_frames_info_get_height(); s_iCountOSDStatsBoundingBoxes++; } @@ -5120,18 +4180,18 @@ void osd_render_stats_panels() if ( s_iOSDStatsBoundingBoxesIds[i] == 5 ) osd_render_stats_video_bitrate_history(s_iOSDStatsBoundingBoxesX[i], s_iOSDStatsBoundingBoxesY[i]); - // To fix or remove - //if ( s_iOSDStatsBoundingBoxesIds[i] == 6 ) - // osd_render_stats_video_decode(s_iOSDStatsBoundingBoxesX[i], s_iOSDStatsBoundingBoxesY[i], pModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, &g_SM_VDS_history, &g_SM_ControllerRetransmissionsStats, 1.0); + if ( s_iOSDStatsBoundingBoxesIds[i] == 6 ) + osd_render_stats_video_decode(s_iOSDStatsBoundingBoxesX[i], s_iOSDStatsBoundingBoxesY[i], pModel->bDeveloperMode, false, &g_SM_RadioStats, &g_SM_VideoDecodeStats, 1.0); - //if ( s_iOSDStatsBoundingBoxesIds[i] == 11 ) - // osd_render_stats_video_decode(s_iOSDStatsBoundingBoxesX[i], s_iOSDStatsBoundingBoxesY[i], pModel->bDeveloperMode, true, &s_OSDSnapshot_RadioStats, &s_OSDSnapshot_VideoDecodeStats, &s_OSDSnapshot_VideoDecodeHist, &s_OSDSnapshot_ControllerVideoRetransmissionsStats, 1.0); + if ( s_iOSDStatsBoundingBoxesIds[i] == 11 ) + osd_render_stats_video_decode(s_iOSDStatsBoundingBoxesX[i], s_iOSDStatsBoundingBoxesY[i], pModel->bDeveloperMode, true, &s_OSDSnapshot_RadioStats, &s_OSDSnapshot_VideoDecodeStats, 1.0); if ( s_iOSDStatsBoundingBoxesIds[i] == 12 ) { - osd_render_stats_video_stream_keyframe_info(s_iOSDStatsBoundingBoxesX[i], s_iOSDStatsBoundingBoxesY[i]); + osd_render_stats_video_stream_h264_frames_info(s_iOSDStatsBoundingBoxesX[i], s_iOSDStatsBoundingBoxesY[i]); // Developer stats + /* if ( pModel->bDeveloperMode ) { float heightAdaptive = osd_render_stats_dev_adaptive_video_get_height(); @@ -5147,6 +4207,7 @@ void osd_render_stats_panels() osd_render_stats_dev_adaptive_video_info(xPosAdaptive, yPosAdaptive, widthAdaptive); } + */ } if ( s_iOSDStatsBoundingBoxesIds[i] == 7 ) diff --git a/code/r_central/osd/osd_stats_radio.cpp b/code/r_central/osd/osd_stats_radio.cpp index de22f7cc..7987c9e6 100644 --- a/code/r_central/osd/osd_stats_radio.cpp +++ b/code/r_central/osd/osd_stats_radio.cpp @@ -496,7 +496,7 @@ float osd_render_stats_radio_interfaces( float xPos, float yPos, const char* szT float ySt = y; bool bIsTxCard = false; - if ( 1 < pStats->countLocalRadioInterfaces ) + //if ( 1 < pStats->countLocalRadioInterfaces ) if ( (iLocalRadioLinkId >= 0) && (pStats->radio_links[iLocalRadioLinkId].lastTxInterfaceIndex == i) ) bIsTxCard = true; @@ -634,21 +634,22 @@ float osd_render_stats_radio_interfaces( float xPos, float yPos, const char* szT osd_set_colors(); - if ( bIsTxCard && (iCountInterfacesAssignedToCurrentLocalLink>1) ) + if ( bIsTxCard && (iCountInterfacesAssignedToCurrentLocalLink>1) && (1 < pStats->countLocalRadioInterfaces) ) g_pRenderEngine->drawIcon(xPos, y-height_text*0.2, hGraph*0.7/g_pRenderEngine->getAspectRatio() , hGraph*0.7, g_idIconUplink2); y += hGraph; y += height_text*0.2; - char szBuffD[64]; - char szBuffU[64]; - str_format_bitrate(pStats->radio_interfaces[i].rxBytesPerSec * 8, szBuffD); - str_format_bitrate(pStats->radio_interfaces[i].txBytesPerSec * 8, szBuffU); - snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "%s / %s", szBuffU, szBuffD); + //char szBuffD[64]; + //char szBuffU[64]; + //str_format_bitrate(pStats->radio_interfaces[i].rxBytesPerSec * 8, szBuffD); + //str_format_bitrate(pStats->radio_interfaces[i].txBytesPerSec * 8, szBuffU); + //snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "%s / %s", szBuffU, szBuffD); + str_format_bitrate(pStats->radio_interfaces[i].rxBytesPerSec * 8, szBuff); g_pRenderEngine->drawTextLeft(rightMargin, y, s_idFontStats, szBuff); float fWT = g_pRenderEngine->textWidth(s_idFontStats, szBuff); - if ( bIsTxCard ) + if ( bIsTxCard && (1 < pStats->countLocalRadioInterfaces) ) { float fIconH = height_text*1.14; float fIconW = 0.6 * fIconH / g_pRenderEngine->getAspectRatio(); @@ -657,44 +658,50 @@ float osd_render_stats_radio_interfaces( float xPos, float yPos, const char* szT szName[0] = 0; - controllerGetCardUserDefinedNameOrType(pNICInfo, szName); + controllerGetCardUserDefinedNameOrShortType(pNICInfo, szName); strcpy(szBuff,szName); sprintf(szName, "%s%s", pNICInfo->szUSBPort, (controllerIsCardInternal(pNICInfo->szMAC)?"":"(Ext)")); g_pRenderEngine->drawText(xPos, y, s_idFontStats, szName); float fW = g_pRenderEngine->textWidth(s_idFontStats, szName); + fW += height_text_small*0.3; if ( 0 != szBuff[0] ) { snprintf(szName, sizeof(szName)/sizeof(szName[0]), "(%s)", szBuff); - g_pRenderEngine->drawText(xPos + fW + height_text_small*0.2, y + 0.5*(height_text-height_text_small), s_idFontStatsSmall, szName); - fW += height_text_small*0.2 + g_pRenderEngine->textWidth(s_idFontStatsSmall, szName); - } + g_pRenderEngine->drawText(xPos + fW, y + 0.5*(height_text-height_text_small), s_idFontStatsSmall, szName); + fW += height_text_small*0.3 + g_pRenderEngine->textWidth(s_idFontStatsSmall, szName); + } - y += height_text*s_OSDStatsLineSpacing; - - szName[0] = 0; + szBuff[0] = 0; if ( pStats->radio_interfaces[i].openedForWrite && pStats->radio_interfaces[i].openedForRead ) { if ( bIsTxCard ) - strcpy(szName, "RX/TX"); + strcpy(szBuff, "RX/TX"); else - strcpy(szName,"RX"); + strcpy(szBuff,"RX"); } else if ( pStats->radio_interfaces[i].openedForWrite ) - strcpy(szName,"TX Only"); + strcpy(szBuff,"TX Only"); else if ( pStats->radio_interfaces[i].openedForRead ) - strcpy(szName,"RX Only"); + strcpy(szBuff,"RX Only"); else - strcpy(szName,"NOT USED"); + strcpy(szBuff,"NOT USED"); + g_pRenderEngine->drawText(xPos + fW, y + 0.5*(height_text-height_text_small), s_idFontStatsSmall, szBuff); + fW += height_text_small*0.3 + g_pRenderEngine->textWidth(s_idFontStatsSmall, szBuff); + y += height_text*s_OSDStatsLineSpacing; + + // Line 2 + szName[0] = 0; + szBuff[0] = 0; char szLinePrefix[128]; //sprintf(szLinePrefix, "Link %d", iLocalRadioLinkId+1); sprintf(szLinePrefix, "%s", str_format_frequency(pStats->radio_interfaces[i].uCurrentFrequencyKhz)); if ( ! hardware_radio_index_is_sik_radio(i) ) - snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "%s, %s, %d dbm", szLinePrefix, szName, (int)g_fOSDDbm[i] ); + snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "%s %d dbm", szLinePrefix, (int)g_fOSDDbm[i] ); else - snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "%s, %s", szLinePrefix, szName); + snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "%s", szLinePrefix); if ( controllerIsCardDisabled(pNICInfo->szMAC) ) snprintf(szBuff, sizeof(szBuff)/sizeof(szBuff[0]), "DISABLED"); @@ -719,14 +726,18 @@ float osd_render_stats_radio_interfaces( float xPos, float yPos, const char* szT szDRV[0] = 0; szDRD[0] = 0; str_getDataRateDescriptionNoSufix(pStats->radio_interfaces[i].lastRecvDataRateVideo, szDRV); - str_getDataRateDescription(pStats->radio_interfaces[i].lastRecvDataRateData, 0, szDRD); - snprintf(szDR, sizeof(szDR)/sizeof(szDR[0]), " V/D: %s/%s", szDRV, szDRD); + if ( pStats->radio_interfaces[i].lastRecvDataRateData < 0 ) + str_getDataRateDescriptionNoSufix(pStats->radio_interfaces[i].lastRecvDataRateData, szDRD); + else + str_getDataRateDescription(pStats->radio_interfaces[i].lastRecvDataRateData, 0, szDRD); + snprintf(szDR, sizeof(szDR)/sizeof(szDR[0]), " %s/%s", szDRV, szDRD); strcat(szBuff, szDR); } g_pRenderEngine->drawText(xPos, y, s_idFontStats, szBuff); y += height_text*s_OSDStatsLineSpacing; + // Line 3 if ( pActiveModel->bDeveloperMode || s_bDebugStatsShowAll ) { g_pRenderEngine->setColors(get_Color_Dev()); diff --git a/code/r_central/osd/osd_warnings.cpp b/code/r_central/osd/osd_warnings.cpp index b7f5e174..c262097d 100644 --- a/code/r_central/osd/osd_warnings.cpp +++ b/code/r_central/osd/osd_warnings.cpp @@ -191,9 +191,11 @@ void osd_warnings_render() bool bHasTelemetryFromFC = vehicle_runtime_has_received_fc_telemetry(g_VehiclesRuntimeInfo[i].uVehicleId); bool bShowFCTelemetryAlarm = false; + if ( pairing_isStarted() ) if ( g_VehiclesRuntimeInfo[i].pModel->telemetry_params.fc_telemetry_type != TELEMETRY_TYPE_NONE ) if ( ! bHasTelemetryFromFC ) if ( ! g_VehiclesRuntimeInfo[i].bLinkLost ) + if ( g_VehiclesRuntimeInfo[i].pModel->is_spectator || g_VehiclesRuntimeInfo[i].bPairedConfirmed ) bShowFCTelemetryAlarm = true; if ( s_bDebugOSDShowAll ) diff --git a/code/r_central/pairing.cpp b/code/r_central/pairing.cpp index 2a8e0f32..a01a8254 100644 --- a/code/r_central/pairing.cpp +++ b/code/r_central/pairing.cpp @@ -135,7 +135,7 @@ bool _pairing_start() g_bMenuPopupUpdateVehicleShown = false; - s_uTimeToSetAffinities = g_TimeNow + 3000; + s_uTimeToSetAffinities = g_TimeNow + 4000; log_line("-----------------------------------------"); log_line("Started pairing processes successfully."); @@ -155,6 +155,8 @@ bool pairing_start_normal() g_iSearchSiKLBT = -1; g_iSearchSiKMCSTR = -1; g_bDidAnUpdate = false; + g_bMustNegociateRadioLinksFlag = false; + g_bAskedForNegociateRadioLink = false; onEventBeforePairing(); @@ -347,30 +349,33 @@ void _pairing_open_shared_mem() } if ( NULL == g_pSM_VideoLinkStats ) iAnyFailed++; -*/ + */ + ruby_signal_alive(); for( int i=0; i<20; i++ ) { - if ( NULL != g_pSM_VideoInfoStatsOutput ) + if ( NULL != g_pSM_VideoFramesStatsOutput ) break; - g_pSM_VideoInfoStatsOutput = shared_mem_video_info_stats_open_for_read(); + g_pSM_VideoFramesStatsOutput = shared_mem_video_frames_stats_open_for_read(); hardware_sleep_ms(5); iAnyNewOpen++; } - if ( NULL == g_pSM_VideoInfoStatsOutput ) + if ( NULL == g_pSM_VideoFramesStatsOutput ) iAnyFailed++; + /* ruby_signal_alive(); for( int i=0; i<20; i++ ) { if ( NULL != g_pSM_VideoInfoStatsRadioIn ) break; - g_pSM_VideoInfoStatsRadioIn = shared_mem_video_info_stats_radio_in_open_for_read(); + g_pSM_VideoInfoStatsRadioIn = shared_mem_video_frames_stats_radio_in_open_for_read(); hardware_sleep_ms(5); iAnyNewOpen++; } if ( NULL == g_pSM_VideoInfoStatsRadioIn ) iAnyFailed++; + */ ruby_signal_alive(); for( int i=0; i<20; i++ ) @@ -408,19 +413,6 @@ void _pairing_open_shared_mem() if ( NULL == g_pSM_RadioRxQueueInfo ) iAnyFailed++; - - ruby_signal_alive(); - for( int i=0; i<20; i++ ) - { - if ( NULL != g_pSM_VDS_history ) - break; - g_pSM_VDS_history = shared_mem_video_stream_stats_history_rx_processors_open(true); - hardware_sleep_ms(5); - iAnyNewOpen++; - } - if ( NULL == g_pSM_VDS_history ) - iAnyFailed++; - ruby_signal_alive(); if ( (NULL != g_pCurrentModel) && (!g_bSearching) ) @@ -488,11 +480,11 @@ void _pairing_close_shared_mem() //shared_mem_video_link_stats_close(g_pSM_VideoLinkStats); //g_pSM_VideoLinkStats = NULL; - shared_mem_video_info_stats_close(g_pSM_VideoInfoStatsOutput); - g_pSM_VideoInfoStatsOutput = NULL; + shared_mem_video_frames_stats_close(g_pSM_VideoFramesStatsOutput); + g_pSM_VideoFramesStatsOutput = NULL; - shared_mem_video_info_stats_radio_in_close(g_pSM_VideoInfoStatsRadioIn); - g_pSM_VideoInfoStatsRadioIn = NULL; + //shared_mem_video_frames_stats_radio_in_close(g_pSM_VideoInfoStatsRadioIn); + //g_pSM_VideoInfoStatsRadioIn = NULL; shared_mem_video_link_graphs_close(g_pSM_VideoLinkGraphs); g_pSM_VideoLinkGraphs = NULL; @@ -500,9 +492,6 @@ void _pairing_close_shared_mem() shared_mem_video_stream_stats_rx_processors_close(g_pSM_VideoDecodeStats); g_pSM_VideoDecodeStats = NULL; - shared_mem_video_stream_stats_history_rx_processors_close(g_pSM_VDS_history); - g_pSM_VDS_history = NULL; - shared_mem_radio_rx_queue_info_close(g_pSM_RadioRxQueueInfo); g_pSM_RadioRxQueueInfo = NULL; diff --git a/code/r_central/popup.cpp b/code/r_central/popup.cpp index 6f379d4d..cff63aae 100644 --- a/code/r_central/popup.cpp +++ b/code/r_central/popup.cpp @@ -317,6 +317,7 @@ Popup::Popup(const char* title, float x, float y, float timeoutSec) m_fPadding = 0.0; m_fPaddingX = 0.0; m_fPaddingY = 0.0; + m_uCreatedTime = g_TimeNow; } Popup::Popup(const char* title, float x, float y, float maxWidth, float timeoutSec) @@ -361,6 +362,7 @@ Popup::Popup(const char* title, float x, float y, float maxWidth, float timeoutS m_fPadding = 0.0; m_fPaddingX = 0.0; m_fPaddingY = 0.0; + m_uCreatedTime = g_TimeNow; } @@ -402,6 +404,8 @@ Popup::Popup(bool bCentered, const char* title, float timeoutSec) if ( m_bCentered ) m_bBottomAlign = false; + + m_uCreatedTime = g_TimeNow; } @@ -600,6 +604,11 @@ void Popup::addLine(const char* szLine) m_bInvalidated = true; } +u32 Popup::getCreationTime() +{ + return m_uCreatedTime; +} + bool Popup::hasDisabledAutoRemove() { return m_bDisableAutoRemove; diff --git a/code/r_central/popup.h b/code/r_central/popup.h index 336ee6b4..3177a62e 100644 --- a/code/r_central/popup.h +++ b/code/r_central/popup.h @@ -35,6 +35,7 @@ class Popup void setLine(int iLine, const char* szLine); char* getLine(int iLine); + u32 getCreationTime(); bool hasDisabledAutoRemove(); void disableAutoRemove(); int getLinesCount(); @@ -91,6 +92,7 @@ class Popup float m_fTimeoutSeconds; u32 m_uTimeoutEndTime; u32 m_StartTime; + u32 m_uCreatedTime; virtual void computeSize(); }; diff --git a/code/r_central/process_router_messages.cpp b/code/r_central/process_router_messages.cpp index 0006d094..acf6a32d 100644 --- a/code/r_central/process_router_messages.cpp +++ b/code/r_central/process_router_messages.cpp @@ -143,7 +143,7 @@ void stop_pipes_to_router() log_line("[Router COMM] Stopped IPC to/from router."); } -void send_model_changed_message_to_router(u32 uChangeType, u8 uExtraParam) +int send_model_changed_message_to_router(u32 uChangeType, u8 uExtraParam) { t_packet_header PH; radio_packet_init(&PH, PACKET_COMPONENT_LOCAL_CONTROL, PACKET_TYPE_LOCAL_CONTROL_MODEL_CHANGED, STREAM_ID_DATA); @@ -152,10 +152,10 @@ void send_model_changed_message_to_router(u32 uChangeType, u8 uExtraParam) u8 buffer[MAX_PACKET_TOTAL_SIZE]; memcpy(buffer, (u8*)&PH, sizeof(t_packet_header)); - send_packet_to_router(buffer, PH.total_length); + return send_packet_to_router(buffer, PH.total_length); } -void send_control_message_to_router(u8 packet_type, u32 extraParam) +int send_control_message_to_router(u8 packet_type, u32 extraParam) { t_packet_header PH; radio_packet_init(&PH, PACKET_COMPONENT_LOCAL_CONTROL, packet_type, STREAM_ID_DATA); @@ -165,10 +165,10 @@ void send_control_message_to_router(u8 packet_type, u32 extraParam) u8 buffer[MAX_PACKET_TOTAL_SIZE]; memcpy(buffer, (u8*)&PH, sizeof(t_packet_header)); - send_packet_to_router(buffer, PH.total_length); + return send_packet_to_router(buffer, PH.total_length); } -void send_control_message_to_router_and_data(u8 packet_type, u8* pData, int nDataLength) +int send_control_message_to_router_and_data(u8 packet_type, u8* pData, int nDataLength) { t_packet_header PH; radio_packet_init(&PH, PACKET_COMPONENT_LOCAL_CONTROL, packet_type, STREAM_ID_DATA); @@ -181,20 +181,23 @@ void send_control_message_to_router_and_data(u8 packet_type, u8* pData, int nDat if ( nDataLength > 0 ) memcpy(&(buffer[sizeof(t_packet_header)]), pData, nDataLength); - send_packet_to_router(buffer, PH.total_length); + return send_packet_to_router(buffer, PH.total_length); } -void send_packet_to_router(u8* pPacket, int nLength) +int send_packet_to_router(u8* pPacket, int nLength) { if ( (NULL == pPacket) || (nLength <= 0) ) - return; + return 0; if ( -1 == s_fIPCToRouter ) { log_softerror_and_alarm("[Router COMM] No IPC to router to send message to."); - return; + return 0; } - ruby_ipc_channel_send_message(s_fIPCToRouter, pPacket, nLength); + int iRes = ruby_ipc_channel_send_message(s_fIPCToRouter, pPacket, nLength); + if ( iRes != nLength ) + log_softerror_and_alarm("[Router COM] Failed to send message to router (msg size: %d bytes), error: %d", nLength, iRes); + return iRes; } t_structure_vehicle_info* _get_runtime_info_for_packet(u8* pPacketBuffer) @@ -1003,10 +1006,10 @@ int _process_received_message_from_router(u8* pPacketBuffer) if ( pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_VIDEO_INFO_STATS ) { - if ( pPH->total_length != sizeof(t_packet_header) + 2*sizeof(shared_mem_video_info_stats) ) - return 0; - memcpy((u8*)&g_VideoInfoStatsFromVehicleCameraOut, (u8*)(pPacketBuffer + sizeof(t_packet_header)), sizeof(shared_mem_video_info_stats)); - memcpy((u8*)&g_VideoInfoStatsFromVehicleRadioOut, (u8*)(pPacketBuffer + sizeof(t_packet_header) + sizeof(shared_mem_video_info_stats)), sizeof(shared_mem_video_info_stats)); + //if ( pPH->total_length != sizeof(t_packet_header) + 2*sizeof(shared_mem_video_frames_stats) ) + // return 0; + //memcpy((u8*)&g_VideoInfoStatsFromVehicleCameraOut, (u8*)(pPacketBuffer + sizeof(t_packet_header)), sizeof(shared_mem_video_frames_stats)); + //memcpy((u8*)&g_VideoInfoStatsFromVehicleRadioOut, (u8*)(pPacketBuffer + sizeof(t_packet_header) + sizeof(shared_mem_video_frames_stats)), sizeof(shared_mem_video_frames_stats)); return 0; } diff --git a/code/r_central/process_router_messages.h b/code/r_central/process_router_messages.h index aba477e2..5130ef93 100644 --- a/code/r_central/process_router_messages.h +++ b/code/r_central/process_router_messages.h @@ -5,9 +5,9 @@ void start_pipes_to_router(); void stop_pipes_to_router(); -void send_model_changed_message_to_router(u32 uChangeType, u8 uExtraParam); -void send_control_message_to_router(u8 packet_type, u32 extraParam); -void send_control_message_to_router_and_data(u8 packet_type, u8* pData, int nDataLength); -void send_packet_to_router(u8* pPacket, int nLength); +int send_model_changed_message_to_router(u32 uChangeType, u8 uExtraParam); +int send_control_message_to_router(u8 packet_type, u32 extraParam); +int send_control_message_to_router_and_data(u8 packet_type, u8* pData, int nDataLength); +int send_packet_to_router(u8* pPacket, int nLength); int try_read_messages_from_router(u32 uMaxMiliseconds); diff --git a/code/r_central/ruby_central.cpp b/code/r_central/ruby_central.cpp index 8a886202..daff5b91 100644 --- a/code/r_central/ruby_central.cpp +++ b/code/r_central/ruby_central.cpp @@ -62,7 +62,7 @@ #include "../base/config.h" #include "../base/ctrl_settings.h" #include "../base/ctrl_interfaces.h" -#include "../base/controller_utils.h" +#include "../utils/utils_controller.h" #include "../base/plugins_settings.h" #include "../base/vehicle_rt_info.h" //#include "../base/radio_utils.h" @@ -79,6 +79,7 @@ #endif #include "../common/string_utils.h" +#include "../common/strings_table.h" #include "../common/relay_utils.h" #include "../common/favorites.h" @@ -144,7 +145,7 @@ static u32 s_uTimeFreezeOSD = 0; shared_mem_process_stats* s_pProcessStatsCentral = NULL; -Popup popupNoModel("No vehicle defined or linked to!", 0.22, 0.45, 5); +Popup popupNoModel("No vehicle defined or linked to!", 0.2, 0.45, 5); Popup popupStartup("System starting. Please wait.", 0.05, 0.16, 0); static char s_szFileHDMIChanged[128]; @@ -1315,17 +1316,21 @@ void ruby_load_models() // Recreate active model file ruby_set_active_model_id(g_uActiveControllerModelVID); } - FILE* fd = fopen(szFile, "rb"); if ( NULL != fd ) { fscanf(fd, "%u", &g_uActiveControllerModelVID); fclose(fd); + log_line("Controller current active model id is: %u", g_uActiveControllerModelVID); } + else + log_softerror_and_alarm("Can't access active model id file (%s)", szFile); if ( ! controllerHasModelWithId(g_uActiveControllerModelVID) ) + { + log_line("Controller does not have a model for current active controller model id %u. Reset active model id to 0.", g_uActiveControllerModelVID); ruby_set_active_model_id(0); - + } if ( g_bFirstModelPairingDone ) { if ( (0 == getControllerModelsCount()) && ( 0 == getControllerModelsSpectatorCount()) ) @@ -1428,18 +1433,6 @@ void start_loop() popupStartup.addLine("Getting radio hardware info..."); hardware_enumerate_radio_interfaces(); - ControllerSettings* pCS = get_ControllerSettings(); - - if ( hardware_radio_has_atheros_cards() ) - if ( pCS->iTXPowerAtheros > 0 ) - hardware_radio_set_txpower_atheros(pCS->iTXPowerAtheros); - if ( hardware_radio_has_rtl8812au_cards() ) - if ( pCS->iTXPowerRTL8812AU > 0 ) - hardware_radio_set_txpower_rtl8812au(pCS->iTXPowerRTL8812AU); - if ( hardware_radio_has_rtl8812eu_cards() ) - if ( pCS->iTXPowerRTL8812EU ) - hardware_radio_set_txpower_rtl8812eu(pCS->iTXPowerRTL8812EU); - log_line("Finished executing start up sequence step: %d", s_StartSequence); s_StartSequence = START_SEQ_NICS; return; @@ -1641,14 +1634,14 @@ void start_loop() { if ( 0 == getControllerModelsCount() ) { - popupNoModel.setTitle("Info"); + popupNoModel.setTitle("Info No Vehicles"); popupNoModel.addLine("You have no vehicles linked to this controller."); popupNoModel.addLine("Press [Menu] key and then select 'Search' to search for a vehicle to connect to."); popupNoModel.setIconId(g_idIconInfo,get_Color_IconWarning()); } else { - popupNoModel.setTitle("Info"); + popupNoModel.setTitle("Info No Active Vehicle"); popupNoModel.addLine("You have no vehicle selected as active."); popupNoModel.addLine("Press [Menu] key and then select 'My Vehicles' to select the vehicle to connect to."); popupNoModel.setIconId(g_idIconInfo,get_Color_IconWarning()); @@ -1848,31 +1841,14 @@ void start_loop() int iMajor = 0; int iMinor = 0; get_Ruby_BaseVersion(&iMajor, &iMinor); - if ( iMajor < 6 ) - { - Popup* p = new Popup(true, "Can't update from version older than 6.0. You need to do a full install of version 6.0 or a newer one.", 10); - p->setIconId(g_idIconError, get_Color_IconError()); - popups_add_topmost(p); - } - - #if defined(HW_PLATFORM_RADXA_ZERO3) - FILE* fd = try_open_base_version_file(NULL); - if ( NULL == fd ) + if ( (iMajor < 10) || ((iMajor == 10) && (iMinor < 1)) ) { - iMajor = 9; - iMinor = 3; + MenuConfirmation* pMC = new MenuConfirmation(getString(0), getString(1), 0, true); + pMC->addTopLine(getString(3)); + pMC->setIconId(g_idIconWarning); + pMC->m_yPos = 0.3; + add_menu_to_stack(pMC); } - else - fclose(fd); - if ( (iMajor < 9) || ((iMajor == 9) && (iMinor < 4))) - { - char szText[128]; - sprintf(szText, "You have a deprecated version (%d.%d). Please do a full install of your controller, to version 9.4 or newer.", iMajor, iMinor); - Popup* p = new Popup(true, szText, 10); - p->setIconId(g_idIconError, get_Color_IconError()); - popups_add_topmost(p); - } - #endif if ( g_iBootCount == 2 ) { @@ -1944,15 +1920,14 @@ void packets_scope_input_loop() void clear_shared_mems() { - memset(&g_SM_VideoInfoStatsOutput, 0, sizeof(shared_mem_video_info_stats)); - memset(&g_SM_VideoInfoStatsRadioIn, 0, sizeof(shared_mem_video_info_stats)); - memset(&g_VideoInfoStatsFromVehicleCameraOut, 0, sizeof(shared_mem_video_info_stats)); - memset(&g_VideoInfoStatsFromVehicleRadioOut, 0, sizeof(shared_mem_video_info_stats)); + memset(&g_SM_VideoFramesStatsOutput, 0, sizeof(shared_mem_video_frames_stats)); + //memset(&g_SM_VideoInfoStatsRadioIn, 0, sizeof(shared_mem_video_frames_stats)); + //memset(&g_VideoInfoStatsFromVehicleCameraOut, 0, sizeof(shared_mem_video_frames_stats)); + //memset(&g_VideoInfoStatsFromVehicleRadioOut, 0, sizeof(shared_mem_video_frames_stats)); memset(&g_SM_HistoryRxStats, 0, sizeof(shared_mem_radio_stats_rx_hist)); memset(&g_SM_HistoryRxStatsVehicle, 0, sizeof(shared_mem_radio_stats_rx_hist)); memset(&g_SM_AudioDecodeStats, 0, sizeof(shared_mem_audio_decode_stats)); memset(&g_SM_VideoDecodeStats, 0, sizeof(shared_mem_video_stream_stats_rx_processors)); - memset(&g_SM_VDS_history, 0, sizeof(shared_mem_video_stream_stats_history_rx_processors)); memset(&g_SMControllerRTInfo, 0, sizeof(controller_runtime_info)); memset(&g_SMVehicleRTInfo, 0, sizeof(vehicle_runtime_info)); @@ -2075,20 +2050,19 @@ void synchronize_shared_mems() memcpy((u8*)&g_SM_AudioDecodeStats, g_pSM_AudioDecodeStats, sizeof(shared_mem_audio_decode_stats)); if ( NULL != g_pCurrentModel ) - if ( g_pCurrentModel->osd_params.osd_flags[g_pCurrentModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_KEYFRAMES_INFO) + if ( g_pCurrentModel->bDeveloperMode ) + if ( g_pCurrentModel->osd_params.osd_flags[g_pCurrentModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_H264_FRAMES_INFO) { - if ( NULL != g_pSM_VideoInfoStatsOutput ) - if ( g_TimeNow >= g_SM_VideoInfoStatsOutput.uTimeLastUpdate + 200 ) - memcpy((u8*)&g_SM_VideoInfoStatsOutput, g_pSM_VideoInfoStatsOutput, sizeof(shared_mem_video_info_stats)); - if ( NULL != g_pSM_VideoInfoStatsRadioIn ) - if ( g_TimeNow >= g_SM_VideoInfoStatsRadioIn.uTimeLastUpdate + 200 ) - memcpy((u8*)&g_SM_VideoInfoStatsRadioIn, g_pSM_VideoInfoStatsRadioIn, sizeof(shared_mem_video_info_stats)); + if ( NULL != g_pSM_VideoFramesStatsOutput ) + if ( g_TimeNow >= g_SM_VideoFramesStatsOutput.uLastTimeStatsUpdate + 200 ) + memcpy((u8*)&g_SM_VideoFramesStatsOutput, g_pSM_VideoFramesStatsOutput, sizeof(shared_mem_video_frames_stats)); + //if ( NULL != g_pSM_VideoInfoStatsRadioIn ) + //if ( g_TimeNow >= g_SM_VideoInfoStatsRadioIn.uLastTimeStatsUpdate + 200 ) + // memcpy((u8*)&g_SM_VideoInfoStatsRadioIn, g_pSM_VideoInfoStatsRadioIn, sizeof(shared_mem_video_frames_stats)); } if ( NULL != g_pSM_VideoDecodeStats ) memcpy((u8*)&g_SM_VideoDecodeStats, g_pSM_VideoDecodeStats, sizeof(shared_mem_video_stream_stats_rx_processors)); - if ( NULL != g_pSM_VDS_history ) - memcpy((u8*)&g_SM_VDS_history, g_pSM_VDS_history, sizeof(shared_mem_video_stream_stats_history_rx_processors)); if ( NULL != g_pSM_RadioRxQueueInfo ) memcpy((u8*)&g_SM_RadioRxQueueInfo, g_pSM_RadioRxQueueInfo, sizeof(shared_mem_radio_rx_queue_info)); // To fix @@ -2108,7 +2082,9 @@ void ruby_processing_loop(bool bNoKeys) ControllerSettings* pCS = get_ControllerSettings(); hardware_sleep_ms(10); + try_read_messages_from_router(7); + keyboard_consume_input_events(); u32 uSumEvent = keyboard_get_triggered_input_events(); @@ -2117,6 +2093,7 @@ void ruby_processing_loop(bool bNoKeys) handle_commands_loop(); pairing_loop(); + synchronize_shared_mems(); if ( g_bIsRouterPacketsHistoryGraphOn ) @@ -2555,11 +2532,17 @@ int main(int argc, char *argv[]) void ruby_set_active_model_id(u32 uVehicleId) { g_uActiveControllerModelVID = uVehicleId; - Model* pModel = findModelWithId(uVehicleId, 62); - if ( NULL == pModel ) - log_line("Ruby: Set active model vehicle id to %u (no model found on controller for this VID)", g_uActiveControllerModelVID ); + Model* pModel = NULL; + if ( uVehicleId != 0 ) + { + pModel = findModelWithId(uVehicleId, 62); + if ( NULL == pModel ) + log_line("Ruby: Set active model vehicle id to %u (no model found on controller for this VID)", g_uActiveControllerModelVID ); + else + log_line("Ruby: Set active model vehicle id to %u, %s", g_uActiveControllerModelVID, (pModel->is_spectator)?"spectator mode":"control mode"); + } else - log_line("Ruby: Set active model vehicle id to %u, %s", g_uActiveControllerModelVID, (pModel->is_spectator)?"spectator mode":"control mode"); + log_line("Ruby: Set active model vehicle id to 0"); char szFile[128]; strcpy(szFile, FOLDER_CONFIG); diff --git a/code/r_central/shared_vars.cpp b/code/r_central/shared_vars.cpp index 3a311867..9fb2564c 100644 --- a/code/r_central/shared_vars.cpp +++ b/code/r_central/shared_vars.cpp @@ -80,3 +80,6 @@ int g_iMustSendCurrentActiveOSDLayoutCounter = 0; CorePluginSettings g_listVehicleCorePlugins[MAX_CORE_PLUGINS_COUNT]; int g_iVehicleCorePluginsCount = 0; + +bool g_bMustNegociateRadioLinksFlag = false; +bool g_bAskedForNegociateRadioLink = false; \ No newline at end of file diff --git a/code/r_central/shared_vars.h b/code/r_central/shared_vars.h index 4e5e4387..57f8abc2 100644 --- a/code/r_central/shared_vars.h +++ b/code/r_central/shared_vars.h @@ -76,3 +76,5 @@ extern int g_iMustSendCurrentActiveOSDLayoutCounter; extern CorePluginSettings g_listVehicleCorePlugins[MAX_CORE_PLUGINS_COUNT]; extern int g_iVehicleCorePluginsCount; +extern bool g_bMustNegociateRadioLinksFlag; +extern bool g_bAskedForNegociateRadioLink; diff --git a/code/r_central/shared_vars_ipc.cpp b/code/r_central/shared_vars_ipc.cpp index 846f084f..8c880303 100644 --- a/code/r_central/shared_vars_ipc.cpp +++ b/code/r_central/shared_vars_ipc.cpp @@ -69,21 +69,16 @@ shared_mem_radio_stats_rx_hist g_SM_HistoryRxStatsVehicle; shared_mem_audio_decode_stats* g_pSM_AudioDecodeStats = NULL; shared_mem_audio_decode_stats g_SM_AudioDecodeStats; -shared_mem_video_info_stats* g_pSM_VideoInfoStatsOutput = NULL; -shared_mem_video_info_stats g_SM_VideoInfoStatsOutput; - -shared_mem_video_info_stats* g_pSM_VideoInfoStatsRadioIn = NULL; -shared_mem_video_info_stats g_SM_VideoInfoStatsRadioIn; - -shared_mem_video_info_stats g_VideoInfoStatsFromVehicleCameraOut; -shared_mem_video_info_stats g_VideoInfoStatsFromVehicleRadioOut; +shared_mem_video_frames_stats* g_pSM_VideoFramesStatsOutput = NULL; +shared_mem_video_frames_stats g_SM_VideoFramesStatsOutput; +//shared_mem_video_frames_stats* g_pSM_VideoInfoStatsRadioIn = NULL; +//shared_mem_video_frames_stats g_SM_VideoInfoStatsRadioIn; +//shared_mem_video_frames_stats g_VideoInfoStatsFromVehicleCameraOut; +//shared_mem_video_frames_stats g_VideoInfoStatsFromVehicleRadioOut; shared_mem_video_stream_stats_rx_processors* g_pSM_VideoDecodeStats = NULL; shared_mem_video_stream_stats_rx_processors g_SM_VideoDecodeStats; -shared_mem_video_stream_stats_history_rx_processors* g_pSM_VDS_history = NULL; -shared_mem_video_stream_stats_history_rx_processors g_SM_VDS_history; - shared_mem_radio_rx_queue_info* g_pSM_RadioRxQueueInfo = NULL; shared_mem_radio_rx_queue_info g_SM_RadioRxQueueInfo; diff --git a/code/r_central/shared_vars_ipc.h b/code/r_central/shared_vars_ipc.h index 3d62bb71..5e332155 100644 --- a/code/r_central/shared_vars_ipc.h +++ b/code/r_central/shared_vars_ipc.h @@ -46,21 +46,16 @@ extern shared_mem_radio_stats_rx_hist g_SM_HistoryRxStatsVehicle; extern shared_mem_audio_decode_stats* g_pSM_AudioDecodeStats; extern shared_mem_audio_decode_stats g_SM_AudioDecodeStats; -extern shared_mem_video_info_stats* g_pSM_VideoInfoStatsOutput; -extern shared_mem_video_info_stats g_SM_VideoInfoStatsOutput; - -extern shared_mem_video_info_stats* g_pSM_VideoInfoStatsRadioIn; -extern shared_mem_video_info_stats g_SM_VideoInfoStatsRadioIn; - -extern shared_mem_video_info_stats g_VideoInfoStatsFromVehicleCameraOut; -extern shared_mem_video_info_stats g_VideoInfoStatsFromVehicleRadioOut; +extern shared_mem_video_frames_stats* g_pSM_VideoFramesStatsOutput; +extern shared_mem_video_frames_stats g_SM_VideoFramesStatsOutput; +//extern shared_mem_video_frames_stats* g_pSM_VideoInfoStatsRadioIn; +//extern shared_mem_video_frames_stats g_SM_VideoInfoStatsRadioIn; +//extern shared_mem_video_frames_stats g_VideoInfoStatsFromVehicleCameraOut; +//extern shared_mem_video_frames_stats g_VideoInfoStatsFromVehicleRadioOut; extern shared_mem_video_stream_stats_rx_processors* g_pSM_VideoDecodeStats; extern shared_mem_video_stream_stats_rx_processors g_SM_VideoDecodeStats; -extern shared_mem_video_stream_stats_history_rx_processors* g_pSM_VDS_history; -extern shared_mem_video_stream_stats_history_rx_processors g_SM_VDS_history; - extern shared_mem_radio_rx_queue_info* g_pSM_RadioRxQueueInfo; extern shared_mem_radio_rx_queue_info g_SM_RadioRxQueueInfo; diff --git a/code/r_central/shared_vars_state.cpp b/code/r_central/shared_vars_state.cpp index 093ae56d..96af0845 100644 --- a/code/r_central/shared_vars_state.cpp +++ b/code/r_central/shared_vars_state.cpp @@ -72,7 +72,6 @@ bool g_bGotStatsVehicleTx = false; bool g_bHasVideoDecodeStatsSnapshot = false; -int g_iDeltaVideoInfoBetweenVehicleController = 0; u32 g_uLastControllerAlarmIOFlags = 0; bool g_bChangedOSDStatsFontSize = false; diff --git a/code/r_central/shared_vars_state.h b/code/r_central/shared_vars_state.h index f09f9fea..fa6c187d 100644 --- a/code/r_central/shared_vars_state.h +++ b/code/r_central/shared_vars_state.h @@ -170,8 +170,6 @@ extern bool g_bGotStatsVehicleTx; extern bool g_bHasVideoDecodeStatsSnapshot; -extern int g_iDeltaVideoInfoBetweenVehicleController; - extern u32 g_uLastControllerAlarmIOFlags; extern bool g_bChangedOSDStatsFontSize; diff --git a/code/r_central/ui_alarms.cpp b/code/r_central/ui_alarms.cpp index 7a3d5bb6..00ecb474 100644 --- a/code/r_central/ui_alarms.cpp +++ b/code/r_central/ui_alarms.cpp @@ -229,15 +229,39 @@ void alarms_add_from_vehicle(u32 uVehicleId, u32 uAlarms, u32 uFlags1, u32 uFlag if ( uAlarms & ALARM_ID_VIDEO_CAPTURE_MALFUNCTION ) { + static u32 s_uTimeLastCaptureMalfunctionAlarm = 0; + + if ( g_TimeNow < s_uTimeLastCaptureMalfunctionAlarm + 10000 ) + return; + s_uTimeLastCaptureMalfunctionAlarm = g_TimeNow; + uIconId = g_idIconCamera; - strcpy(szAlarmText, "Video capture process on vehicle is malfunctioning."); - strcpy(szAlarmText2, "Reinstall your vehicle firmware."); - if ( uFlags1 == 1 ) + if ( 0 == (uFlags1 & 0xFF) ) + { + strcpy(szAlarmText, "Video capture process on vehicle is malfunctioning."); + strcpy(szAlarmText2, "Reinstall your vehicle firmware."); + } + else if ( 1 == (uFlags1 & 0xFF) ) { strcpy(szAlarmText, "Video capture process on vehicle is not responding."); strcpy(szAlarmText2, "Vehicle will restart now..."); } + else if ( 2 == (uFlags1 & 0xFF) ) + { + u32 uSkipped = (uFlags1 >> 8) & 0xFF; + u32 uDelta1 = uFlags2 & 0xFF; + u32 uDelta2 = (uFlags2 >> 8) & 0xFF; + u32 uDelta3 = (uFlags2 >> 16) & 0xFF; + sprintf(szAlarmText, "Video capture process skipped %u packets from H264/H265 encoder.", uSkipped); + sprintf(szAlarmText2, "Please contact Ruby developers. Delta times: %u ms, %u ms, %u ms", uDelta1, uDelta2, uDelta3); + bShowAsWarning = true; + } + else + { + strcpy(szAlarmText, "Video capture process on vehicle is malfunctioning."); + strcpy(szAlarmText2, "A generic error occured. Reinstall your vehicle firmware."); + } } @@ -460,7 +484,11 @@ void alarms_add_from_vehicle(u32 uVehicleId, u32 uAlarms, u32 uFlags1, u32 uFlag bShowAsWarning = true; if ( bShowAsWarning ) + { warnings_add(0, szAlarmText, uIconId); + if ( 0 != szAlarmText2[0] ) + warnings_add(0, szAlarmText2, uIconId); + } else { Popup* p = _get_next_available_alarm_popup(szAlarmText, 7); diff --git a/code/r_start/first_boot.cpp b/code/r_start/first_boot.cpp index 2ce9c884..4debf296 100644 --- a/code/r_start/first_boot.cpp +++ b/code/r_start/first_boot.cpp @@ -47,6 +47,21 @@ Model s_ModelFirstBoot; void do_first_boot_pre_initialization() { + log_line("---------------------------------------"); + log_line("Do first time boot preinitialization..."); + + hardware_install_drivers(); + + #if defined HW_PLATFORM_RASPBERRY + printf("\nRuby doing first time ever initialization on Raspberry. Please wait...\n"); + fflush(stdout); + + hw_execute_bash_command("sync", NULL); + + printf("\nRuby done doing first time ever initialization on Raspberry.\n"); + fflush(stdout); + #endif + #if defined HW_PLATFORM_RADXA_ZERO3 printf("\nRuby doing first time ever initialization on Radxa. Please wait...\n"); @@ -58,28 +73,6 @@ void do_first_boot_pre_initialization() //log_enable_stdout(); log_add_file("/tmp/ruby/log_first_radxa.log"); hw_execute_bash_command("echo \"\nRuby doing first time ever initialization on Radxa...\n\" > /tmp/ruby/log_first_radxa.log", NULL); - if ( access("/home/88XXau_wfb.ko", R_OK) != -1 ) - { - hw_execute_bash_command("cp -rf /home/88XXau_wfb.ko /lib/modules/$(uname -r)/kernel/drivers/net/wireless/", NULL); - hw_execute_bash_command("rmmod 88XXau_wfb 2>&1 1>/dev/null", NULL); - hw_execute_bash_command("insmod /lib/modules/$(uname -r)/kernel/drivers/net/wireless/88XXau_wfb.ko 2>&1 1>/dev/null", NULL); - } - if ( access("/home/8812eu_radxa.ko", R_OK) != -1 ) - { - hw_execute_bash_command("cp -rf /home/8812eu_radxa.ko /lib/modules/$(uname -r)/kernel/drivers/net/wireless/", NULL); - //Radxa EU driver will be loaded by hardware_radio_load_radio_modules() - //hw_execute_bash_command("sudo modprobe cfg80211", NULL); - //hw_execute_bash_command("insmod /lib/modules/$(uname -r)/kernel/drivers/net/wireless/8812eu_radxa.ko rtw_tx_pwr_by_rate=0 rtw_tx_pwr_lmt_enable=0", NULL); - } - hw_execute_bash_command("depmod -a", NULL); - hw_execute_bash_command("lsusb", NULL); - hw_execute_bash_command("sudo modprobe -f 88XXau_wfb 2>&1 1>/dev/null", NULL); - hw_execute_bash_command("sudo modprobe -f 8812eu_radxa.ko 2>&1 1>/dev/null", NULL); - hw_execute_bash_command("sudo modprobe -r aic8800_fdrv 2>&1 1>/dev/null", NULL); - hw_execute_bash_command("sudo modprobe -r aic8800_bsp 2>&1 1>/dev/null", NULL); - hw_execute_bash_command("lsusb", NULL); - hw_execute_bash_command("lsmod", NULL); - hw_execute_bash_command("ip link", NULL); char szComm[256]; sprintf(szComm, "mkdir -p %s", FOLDER_CONFIG); @@ -100,6 +93,9 @@ void do_first_boot_pre_initialization() hw_execute_bash_command("fw_setenv sensor", NULL); hardware_set_default_sigmastar_cpu_freq(); #endif + + log_line("Done first time boot preinitialization."); + log_line("---------------------------------------"); } @@ -267,10 +263,23 @@ void do_first_boot_initialization(bool bIsVehicle, u32 uBoardType) // execute_bash_command("raspi-config --expand-rootfs > /dev/null 2>&1", NULL); - hardware_radio_set_txpower_rtl8812au(DEFAULT_RADIO_TX_POWER); - hardware_radio_set_txpower_rtl8812eu(DEFAULT_RADIO_TX_POWER); - hardware_radio_set_txpower_atheros(DEFAULT_RADIO_TX_POWER); - + for( int i=0; iisConfigurable ) + continue; + + if ( hardware_radio_driver_is_rtl8812au_card(pRadioHWInfo->iRadioDriver) ) + hardware_radio_set_txpower_raw_rtl8812au(i, 10); + if ( hardware_radio_driver_is_rtl8812eu_card(pRadioHWInfo->iRadioDriver) ) + hardware_radio_set_txpower_raw_rtl8812eu(i, 10); + if ( hardware_radio_driver_is_atheros_card(pRadioHWInfo->iRadioDriver) ) + hardware_radio_set_txpower_raw_atheros(i, 10); + } log_line("First boot initialization completed."); log_line("---------------------------------------------------------"); } @@ -341,7 +350,6 @@ Model* first_boot_create_default_model(bool bIsVehicle, u32 uBoardType) } for( int i=0; i&1", pRadioHWInfo->szName ); sprintf(szComm, "ip link set dev %s up", pRadioHWInfo->szName ); hw_execute_bash_command(szComm, szOutput); @@ -222,7 +217,14 @@ bool _configure_radio_interface(int iInterfaceIndex, u32 uDelayMS) if ( pRadioHWInfo->iRadioType == RADIO_TYPE_ATHEROS ) _configure_radio_interface_atheros(iInterfaceIndex, pRadioHWInfo, uDelayMS); else + { _configure_radio_interface_realtek(iInterfaceIndex, pRadioHWInfo, uDelayMS); + // Set a default minimum tx power + if ( hardware_radio_driver_is_rtl8812au_card(pRadioHWInfo->iRadioDriver) ) + hardware_radio_set_txpower_raw_rtl8812au(iInterfaceIndex, 10); + if ( hardware_radio_driver_is_rtl8812eu_card(pRadioHWInfo->iRadioDriver) ) + hardware_radio_set_txpower_raw_rtl8812eu(iInterfaceIndex, 10); + } if ( hardware_radioindex_supports_frequency(iInterfaceIndex, DEFAULT_FREQUENCY58) ) { @@ -380,6 +382,7 @@ int init_Radios() fclose(fd); hardware_save_radio_info(); + log_line("Configuring radios COMPLETED."); log_line("================================================================="); log_line("Radio interfaces and frequencies assigned:"); diff --git a/code/r_start/r_start_vehicle.cpp b/code/r_start/r_start_vehicle.cpp index 5a2ea719..9d41fed8 100644 --- a/code/r_start/r_start_vehicle.cpp +++ b/code/r_start/r_start_vehicle.cpp @@ -56,12 +56,13 @@ #include "../base/hw_procs.h" #include "../base/utils.h" #include "../base/ruby_ipc.h" +#include "../base/tx_powers.h" #include "../common/string_utils.h" #include "../r_vehicle/launchers_vehicle.h" #include "../r_vehicle/video_source_csi.h" #include "../r_vehicle/shared_vars.h" #include "../r_vehicle/timers.h" -#include "../r_vehicle/utils_vehicle.h" +#include "../utils/utils_vehicle.h" #include "../r_vehicle/hw_config_check.h" #include "r_start_vehicle.h" @@ -107,7 +108,7 @@ void _set_default_sik_params_for_vehicle(Model* pModel) { u32 uFreq = pModel->radioLinksParams.link_frequency_khz[iLinkIndex]; hardware_radio_sik_set_frequency_txpower_airspeed_lbt_ecc(pRadioHWInfo, - uFreq, pModel->radioInterfacesParams.txPowerSiK, + uFreq, pModel->radioInterfacesParams.interface_raw_power[i], pModel->radioLinksParams.link_datarate_data_bps[iLinkIndex], (u32)((pModel->radioLinksParams.link_radio_flags[iLinkIndex] & RADIO_FLAGS_SIK_ECC)?1:0), (u32)((pModel->radioLinksParams.link_radio_flags[iLinkIndex] & RADIO_FLAGS_SIK_LBT)?1:0), @@ -180,6 +181,7 @@ bool _check_radio_config(Model* pModel) log_line("[HW Radio Check] Full radio configuration before doing any changes:"); log_full_current_radio_configuration(pModel); + if ( check_update_hardware_nics_vehicle(pModel) ) { log_line("[HW Radio Check] Hardware radio interfaces configuration check complete and configuration was changed. This is the new hardware radio interfaces and radio links configuration:"); @@ -190,6 +192,19 @@ bool _check_radio_config(Model* pModel) else log_line("[HW Radio Check] No radio hardware configuration change detected. No change."); + for( int i=0; i> 8) & 0xFF; + int iCardModel = modelVehicle.radioInterfacesParams.interface_card_model[i]; + int iMaxPowerRaw = tx_powers_get_max_usable_power_raw_for_card(iDriver, iCardModel); + + if ( modelVehicle.radioInterfacesParams.interface_raw_power[i] > iMaxPowerRaw ) + { + modelVehicle.radioInterfacesParams.interface_raw_power[i] = iMaxPowerRaw; + bMustSave = true; + } + } + if ( pModel->check_update_radio_links() ) { _set_default_sik_params_for_vehicle(pModel); @@ -377,7 +392,7 @@ void _launch_vehicle_processes() int r_start_vehicle(int argc, char *argv[]) { - log_init("Vehicle"); + log_init("RubyVehicle"); log_arguments(argc, argv); bool noWatchDog = false; @@ -537,6 +552,8 @@ int r_start_vehicle(int argc, char *argv[]) #ifdef HW_PLATFORM_OPENIPC_CAMERA modelVehicle.audio_params.has_audio_device = false; modelVehicle.audio_params.enabled = false; + hw_execute_bash_command("ulimit -i 1024", NULL); + hw_execute_bash_command("ulimit -l 1024", NULL); #endif log_line("Start sequence: Finished detecting audio device. %s", modelVehicle.audio_params.has_audio_device?"Audio capture device found.":"No audio capture devices found."); @@ -604,40 +621,29 @@ int r_start_vehicle(int argc, char *argv[]) modelVehicle.saveToFile(szFile, false); } - for( int i=0; i> 8 ) & 0x0F; + int iPortId = ( modelVehicle.hardwareInterfacesInfo.serial_port_supported_and_usage[i] >> 8 ) & 0x0F; // USB serial - if ( modelVehicle.hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_EXTRNAL_USB ) + if ( modelVehicle.hardwareInterfacesInfo.serial_port_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_EXTRNAL_USB ) { char szPort[32]; sprintf(szPort, "/dev/ttyUSB%d", iPortId); - hardware_configure_serial(szPort, (long)modelVehicle.hardwareInterfacesInfo.serial_bus_speed[i]); + hardware_configure_serial(szPort, (long)modelVehicle.hardwareInterfacesInfo.serial_port_speed[i]); } // Hardware serial else { char szPort[32]; sprintf(szPort, "/dev/serial%d", iPortId); - hardware_configure_serial(szPort, (long)modelVehicle.hardwareInterfacesInfo.serial_bus_speed[i]); + hardware_configure_serial(szPort, (long)modelVehicle.hardwareInterfacesInfo.serial_port_speed[i]); } } } - if ( hardware_radio_has_atheros_cards() ) - if ( modelVehicle.radioInterfacesParams.txPowerAtheros > 0 ) - hardware_radio_set_txpower_atheros((int)modelVehicle.radioInterfacesParams.txPowerAtheros); - if ( hardware_radio_has_rtl8812au_cards() ) - if ( modelVehicle.radioInterfacesParams.txPowerRTL8812AU > 0 ) - hardware_radio_set_txpower_rtl8812au((int)modelVehicle.radioInterfacesParams.txPowerRTL8812AU); - if ( hardware_radio_has_rtl8812eu_cards() ) - if ( modelVehicle.radioInterfacesParams.txPowerRTL8812EU > 0 ) - hardware_radio_set_txpower_rtl8812eu((int)modelVehicle.radioInterfacesParams.txPowerRTL8812EU); - - #ifdef HW_PLATFORM_RASPBERRY hw_launch_process("./ruby_alive"); #endif diff --git a/code/r_start/ruby_start.cpp b/code/r_start/ruby_start.cpp index a0e70ef8..70001f20 100644 --- a/code/r_start/ruby_start.cpp +++ b/code/r_start/ruby_start.cpp @@ -49,10 +49,12 @@ #include "../base/vehicle_settings.h" #include "../radio/radioflags.h" #include "../base/ruby_ipc.h" +#include "../base/tx_powers.h" #if defined(HW_PLATFORM_RASPBERRY) || defined(HW_PLATFORM_RADXA_ZERO3) #include "../base/ctrl_settings.h" -#include "../base/controller_utils.h" +#include "../utils/utils_controller.h" +#include "../base/ctrl_interfaces.h" #endif #include "../common/string_utils.h" @@ -68,6 +70,7 @@ static sem_t* s_pSemaphoreStarted = NULL; static int s_iBootCount = 0; static bool g_bDebug = false; +static bool g_bIsFirstBoot = false; static bool s_isVehicle = false; bool s_bQuit = false; Model modelVehicle; @@ -264,20 +267,6 @@ void _check_files() if ( access( "/etc/modprobe.d/ath9k_hw.conf.org", R_OK ) == -1 ) {failed = true; strcat(szFilesMissing, " Atheros_config");} } - - if ( access( "/etc/modprobe.d/rtl8812au.conf.org", R_OK ) == -1 ) - { - hw_execute_bash_command("cp -rf /etc/modprobe.d/rtl8812au.conf /etc/modprobe.d/rtl8812au.conf.org", NULL); - if ( access( "/etc/modprobe.d/rtl8812au.conf.org", R_OK ) == -1 ) - {failed = true; strcat(szFilesMissing, " RTL_config");} - } - - if ( access( "/etc/modprobe.d/rtl88XXau.conf.org", R_OK ) == -1 ) - { - hw_execute_bash_command("cp -rf /etc/modprobe.d/rtl88XXau.conf /etc/modprobe.d/rtl88XXau.conf.org", NULL); - if ( access( "/etc/modprobe.d/rtl88XXau.conf.org", R_OK ) == -1 ) - {failed = true; strcat(szFilesMissing, " RTL_XX_config");} - } #endif if ( failed ) @@ -490,6 +479,111 @@ void _test_log(int argc, char *argv[]) } +void _check_power_levels_of_current_cards(radio_hw_info_t* pRadioInfoArrayPrev, int iCountPrev) +{ + bool bNewCards = false; + + for( int i=0; iisSupported ) + continue; + if ( ! hardware_radio_is_wifi_radio(pRadioHWInfo) ) + continue; + + for( int k=0; kszMAC[0] ) + if ( 0 == strcmp(pRadioHWInfo->szMAC, pRadioInfoArrayPrev[k].szMAC) ) + { + bFound = true; + break; + } + } + + if ( ! bFound ) + { + log_line("Radio hardware interface %d: %s (%s, MAC: %s) is new in the system.", + i+1, pRadioHWInfo->szName, pRadioHWInfo->szDriver, pRadioHWInfo->szMAC); + bNewCards = true; + } + } + + if ( ! bNewCards ) + { + log_line("No new supported high capacity radio hardware cards found in the system."); + return; + } + + log_line("Checking power levels as there are new hardware radio interfaces on the system..."); + + if ( s_isVehicle ) + { + //bool bUpdated = false; + for( int i=0; i> 8) & 0xFF; + int iCardModel = modelVehicle.radioInterfacesParams.interface_card_model[i]; + int iMaxPowerRaw = tx_powers_get_max_usable_power_raw_for_card(iDriver, iCardModel); + + if ( modelVehicle.radioInterfacesParams.interface_raw_power[i] > iMaxPowerRaw ) + { + modelVehicle.radioInterfacesParams.interface_raw_power[i] = iMaxPowerRaw; + //bUpdated = true; + } + } + } + else + { + #if defined(HW_PLATFORM_RASPBERRY) || defined(HW_PLATFORM_RADXA_ZERO3) + bool bUpdated = false; + int iMaximumRawCanBeSet = 10000; + for( int i=0; iszMAC); + if ( NULL == pCRII ) + continue; + + log_line("Checking radio interface %d: type: %s (%s)", + i+1, str_get_radio_card_model_string(pCRII->cardModel), (pCRII->cardModel > 0)?"autodetected":"user set"); + int iMaxRawPower = tx_powers_get_max_usable_power_raw_for_card(pRadioHWInfo->iRadioDriver, pCRII->cardModel); + log_line("Max raw power for radio card %d: %d, current raw power: %d", i+1, iMaxRawPower, pCRII->iRawPowerLevel); + + if ( iMaxRawPower < iMaximumRawCanBeSet ) + iMaximumRawCanBeSet = iMaxRawPower; + } + log_line("Maximum raw power that can be set: %d", iMaximumRawCanBeSet); + + for( int i=0; iszMAC); + if ( NULL == pCRII ) + continue; + + int iMaxRawPower = tx_powers_get_max_usable_power_raw_for_card(pRadioHWInfo->iRadioDriver, pCRII->cardModel); + if ( pCRII->iRawPowerLevel > iMaxRawPower ) + { + pCRII->iRawPowerLevel = iMaxRawPower; + bUpdated = true; + } + } + if ( bUpdated ) + save_ControllerSettings(); + #endif + } + log_line("Done checking power levels."); +} + void _log_platform(bool bNewLine) { #if defined(HW_PLATFORM_OPENIPC_CAMERA) @@ -507,39 +601,38 @@ void _log_platform(bool bNewLine) printf("\n"); } -void handle_sigint(int sig) -{ - log_line("Caught signal to stop: %d\n", sig); - s_bQuit = true; -} - -int main(int argc, char *argv[]) + +int _step_process_cmd_line(int argc, char* argv[]) { - signal(SIGPIPE, SIG_IGN); - signal(SIGINT, handle_sigint); - signal(SIGTERM, handle_sigint); - signal(SIGQUIT, handle_sigint); + if ( strcmp(argv[argc-1], "-ver") == 0 ) + { + printf("%d.%d (b%d) ", SYSTEM_SW_VERSION_MAJOR, SYSTEM_SW_VERSION_MINOR/10, SYSTEM_SW_BUILD_NUMBER); + _log_platform(false); + return 1; + } if ( strcmp(argv[argc-1], "-noop") == 0 ) { _log_platform(true); - return 0; + return 1; } if ( strcmp(argv[argc-1], "-vehicle") == 0 ) { r_start_vehicle(argc, argv); - return 0; + return 1; } if ( strcmp(argv[argc-1], "-rx_commands") == 0 ) { - return r_start_commands_rx(argc, argv); + r_start_commands_rx(argc, argv); + return 1; } if ( strcmp(argv[argc-1], "-rc") == 0 ) { - return r_start_rx_rc(argc, argv); + r_start_rx_rc(argc, argv); + return 1; } if ( (strcmp(argv[argc-1], "-initradio") == 0) || @@ -547,40 +640,37 @@ int main(int argc, char *argv[]) ((argc>1) && (strcmp(argv[1], "-initradio") == 0)) ) { r_initradio(argc, argv); - return 0; - } - - if ( strcmp(argv[argc-1], "-ver") == 0 ) - { - printf("%d.%d (b%d) ", SYSTEM_SW_VERSION_MAJOR, SYSTEM_SW_VERSION_MINOR/10, SYSTEM_SW_BUILD_NUMBER); - _log_platform(false); - return 0; + return 1; } if ( strcmp(argv[argc-1], "-test") == 0 ) { start_test(); - return 0; + return 1; } if ( strcmp(argv[argc-1], "-testlog") == 0 ) { _test_log(argc, argv); - return 0; + return 1; } if ( argc >= 2 ) if ( strcmp(argv[argc-2], "-testlog") == 0 ) { _test_log(argc, argv); - return 0; + return 1; } g_bDebug = false; if ( strcmp(argv[argc-1], "-debug") == 0 ) g_bDebug = true; - - char szBuff[256]; + return 0; +} + + +int _step_find_console() +{ char szComm[1024]; char szFile[256]; char *tty_name = ttyname(STDIN_FILENO); @@ -634,7 +724,7 @@ int main(int argc, char *argv[]) printf("\nRuby (v %d.%d b.%d) is starting...\n", SYSTEM_SW_VERSION_MAJOR, SYSTEM_SW_VERSION_MINOR/10, SYSTEM_SW_BUILD_NUMBER); fflush(stdout); sleep(8); - return -1; + return 0; } sprintf(szComm, "echo 'Ruby processes are starting...' >> /tmp/ruby_boot.log"); hw_execute_bash_command_silent(szComm, NULL); @@ -663,14 +753,14 @@ int main(int argc, char *argv[]) sprintf(szComm, "chmod 777 %s*", FOLDER_BINARIES); hw_execute_bash_command(szComm, NULL); - bool bIsFirstBoot = false; + g_bIsFirstBoot = false; strcpy(szFile, FOLDER_CONFIG); strcat(szFile, FILE_CONFIG_FIRST_BOOT); if ( access( szFile, R_OK ) != -1 ) - bIsFirstBoot = true; + g_bIsFirstBoot = true; if ( _init_timestamp_and_boot_count() ) - bIsFirstBoot = true; + g_bIsFirstBoot = true; initLogFiles(); @@ -685,12 +775,15 @@ int main(int argc, char *argv[]) } log_init("RubyStart"); - log_arguments(argc, argv); - log_line("Found good console, starting Ruby..."); + return 1; +} - printf("\nRuby: Start (v %d.%d b.%d) r%d\n", SYSTEM_SW_VERSION_MAJOR, SYSTEM_SW_VERSION_MINOR/10, SYSTEM_SW_BUILD_NUMBER, s_iBootCount); - fflush(stdout); + +int _step_check_file_system() +{ + char szComm[256]; + char szFile[MAX_FILE_PATH_SIZE]; bool readWriteOk = false; int readWriteRetryCount = 0; FILE* fd = NULL; @@ -704,7 +797,7 @@ int main(int argc, char *argv[]) if ( readWriteRetryCount > 50 ) { printf("\nError accessing the file system. Abort.\n\n"); - return 0; + return -1; } hardware_sleep_ms(100); @@ -799,7 +892,7 @@ int main(int argc, char *argv[]) continue; } - fprintf(fd, "Check for write access, succeeded on try number: %d (boot count: %d, Ruby on TTY name: %s)\n", readWriteRetryCount, s_iBootCount, ((tty_name != NULL)?tty_name:"N/A")); + fprintf(fd, "Check for write access, succeeded on try number: %d (boot count: %d)\n", readWriteRetryCount, s_iBootCount); strcpy(szFile, FOLDER_CONFIG); strcat(szFile, FILE_CONFIG_BOOT_COUNT); @@ -839,14 +932,17 @@ int main(int argc, char *argv[]) fd = fopen(szFile, "a+"); if ( NULL != fd ) { - fprintf(fd, "Starting run number %d; Starting Ruby on TTY name: %s\n\n", s_iBootCount, ((tty_name != NULL)?tty_name:"N/A")); + fprintf(fd, "Starting run number %d; Starting Ruby...\n\n", s_iBootCount); fclose(fd); fd = NULL; } - - //power_leds(0); - log_line("Files are ok, checking processes and init log files..."); + return 0; +} + +void _step_check_binaries_and_processes() +{ + char szComm[MAX_FILE_PATH_SIZE]; sprintf(szComm, "chmod 777 %s", FOLDER_BINARIES); hw_execute_bash_command(szComm, NULL); @@ -863,10 +959,6 @@ int main(int argc, char *argv[]) _check_files(); #endif - #if defined (HW_PLATFORM_RADXA_ZERO3) - hw_execute_bash_command("sed -i '/98:03:cf/d' /etc/udev/rules.d/98-custom-wifi.rules", NULL); - #endif - #if defined(HW_PLATFORM_OPENIPC_CAMERA) _log_openipc_info(); #endif @@ -874,16 +966,17 @@ int main(int argc, char *argv[]) log_line("Ruby: Start on verison %d.%d (b %d)", SYSTEM_SW_VERSION_MAJOR, SYSTEM_SW_VERSION_MINOR/10, SYSTEM_SW_BUILD_NUMBER); printf("Ruby: Start on verison %d.%d (b %d)\n", SYSTEM_SW_VERSION_MAJOR, SYSTEM_SW_VERSION_MINOR/10, SYSTEM_SW_BUILD_NUMBER); fflush(stdout); - u32 uBaseVersion = hardware_get_base_ruby_version(); - log_line("Ruby: Base version is %d.%d", (uBaseVersion >> 8) & 0xFF, uBaseVersion & 0xFF); - printf("Ruby: Base version is %d.%d\n", (uBaseVersion >> 8) & 0xFF, uBaseVersion & 0xFF); - fflush(stdout); - char szOutput[4096]; - szOutput[0] = 0; - if ( bIsFirstBoot ) - do_first_boot_pre_initialization(); + int iMajor, iMinor; + get_Ruby_BaseVersion(&iMajor, &iMinor); + + log_line("Ruby: Base version is %d.%d", iMajor, iMinor); + printf("Ruby: Base version is %d.%d\n", iMajor, iMinor); + fflush(stdout); +} +void _step_load_init_devices() +{ #ifdef HW_PLATFORM_RADXA_ZERO3 hw_execute_bash_command("ip link set wlx down 2>&1 1>/dev/null", NULL); #endif @@ -892,10 +985,7 @@ int main(int argc, char *argv[]) hw_execute_bash_command("modprobe i2c-dev", NULL); #endif - hardware_radio_load_radio_modules(1); - - hardware_sleep_ms(50); - + char szOutput[2048]; hw_execute_bash_command_raw("lsusb", szOutput); strcat(szOutput, "\n*END*\n"); log_line("USB Devices:"); @@ -912,13 +1002,88 @@ int main(int argc, char *argv[]) log_line(szOutput); #endif + #ifdef HW_CAPABILITY_I2C + + char szComm[256]; + u32 board_type = (hardware_getOnlyBoardType() & BOARD_TYPE_MASK); + + // Initialize I2C bus 0 for different boards types + + log_line("Initialize I2C busses..."); + sprintf(szComm, "current_dir=$PWD; cd %s/; ./camera_i2c_config 2>/dev/null; cd $current_dir", VEYE_COMMANDS_FOLDER); + hw_execute_bash_command(szComm, NULL); + if ( (board_type == BOARD_TYPE_PI3APLUS) || (board_type == BOARD_TYPE_PI3B) || (board_type == BOARD_TYPE_PI3BPLUS) || (board_type == BOARD_TYPE_PI4B) ) + { + log_line("Initializing I2C busses for Pi 3/4..."); + hw_execute_bash_command("raspi-gpio set 0 ip", NULL); + hw_execute_bash_command("raspi-gpio set 1 ip", NULL); + hw_execute_bash_command("raspi-gpio set 44 ip", NULL); + hw_execute_bash_command("raspi-gpio set 44 a1", NULL); + hw_execute_bash_command("raspi-gpio set 45 ip", NULL); + hw_execute_bash_command("raspi-gpio set 45 a1", NULL); + hardware_sleep_ms(200); + hw_execute_bash_command("i2cdetect -y 0 0x0F 0x0F", NULL); + hardware_sleep_ms(200); + log_line("Done initializing I2C busses for Pi 3/4."); + } + + log_line("Ruby: Finding external I2C devices add-ons..."); + printf("Ruby: Finding external I2C devices add-ons...\n"); + fflush(stdout); + hardware_i2c_reset_enumerated_flag(); + hardware_enumerate_i2c_busses(); + // Load existing settings first + hardware_i2c_load_device_settings(); + hardware_i2c_log_devices(); + // Save existing settings and any new devices + hardware_i2c_save_device_settings(); + int iKnown = hardware_get_i2c_found_count_known_devices(); + int iConfigurable = hardware_get_i2c_found_count_configurable_devices(); + if ( 0 == iKnown && 0 == iConfigurable ) + { + log_line("Ruby: Done finding external I2C devices add-ons. None known found." ); + printf("Ruby: Done finding external I2C devices add-ons. None known found.\n" ); + } + else + { + log_line("Ruby: Done finding external I2C devices add-ons. Found %d known devices of which %d are configurable.", iKnown, iConfigurable ); + printf("Ruby: Done finding external I2C devices add-ons. Found %d known devices of which %d are configurable.\n", iKnown, iConfigurable ); + } + #endif + + fflush(stdout); + + printf("Ruby: Finding serial ports...\n"); + log_line("Ruby: Finding serial ports..."); + fflush(stdout); + + hardware_init_serial_ports(); +} + +radio_hw_info_t sRadioInfoPrev[MAX_RADIO_INTERFACES]; +int iHwRadiosCountPrev = 0; +int iHwRadiosSupportedCountPrev = 0; + +void _step_load_init_radios() +{ + log_line("Loading previous radio configuration..."); + hardware_load_radio_info_into_buffers(&iHwRadiosCountPrev, &iHwRadiosSupportedCountPrev, &sRadioInfoPrev[0]); + log_line("Loaded previous radio configuration."); + + hardware_radio_load_radio_modules(1); + + hardware_sleep_ms(50); + + char szComm[256]; + char szBuff[256]; + char szOutput[2048]; int iCount = 0; bool bWiFiDetected = false; int iMaxWifiCardsToDetect = 4; int iWifiIndexToTry = 0; - while ( iCount < 5 ) + while ( iCount < 3 ) { iCount++; szOutput[0] = 0; @@ -993,94 +1158,22 @@ int main(int argc, char *argv[]) } } - sprintf(szComm, "rm -rf %s%s", FOLDER_RUBY_TEMP, FILE_CONFIG_SYSTEM_TYPE); - hw_execute_bash_command_silent(szComm, NULL); - sprintf(szComm, "rm -rf %s%s", FOLDER_RUBY_TEMP, FILE_CONFIG_CAMERA_TYPE); - hw_execute_bash_command_silent(szComm, NULL); - - init_hardware_only_status_led(); - - if ( access( FILE_FORCE_RESET, R_OK ) != -1 ) - { - unlink(FILE_FORCE_RESET); - hw_execute_bash_command("rm -rf config/*", NULL); - sprintf(szComm, "touch %s%s", FOLDER_CONFIG, FILE_CONFIG_FIRST_BOOT); - hw_execute_bash_command(szComm, NULL); - hardware_reboot(); - hardware_sleep_ms(900); - } - - board_type = (hardware_getOnlyBoardType() & BOARD_TYPE_MASK); - - #ifdef HW_CAPABILITY_I2C - // Initialize I2C bus 0 for different boards types - { - log_line("Initialize I2C busses..."); - sprintf(szComm, "current_dir=$PWD; cd %s/; ./camera_i2c_config 2>/dev/null; cd $current_dir", VEYE_COMMANDS_FOLDER); - hw_execute_bash_command(szComm, NULL); - if ( (board_type == BOARD_TYPE_PI3APLUS) || (board_type == BOARD_TYPE_PI3B) || (board_type == BOARD_TYPE_PI3BPLUS) || (board_type == BOARD_TYPE_PI4B) ) - { - log_line("Initializing I2C busses for Pi 3/4..."); - hw_execute_bash_command("raspi-gpio set 0 ip", NULL); - hw_execute_bash_command("raspi-gpio set 1 ip", NULL); - hw_execute_bash_command("raspi-gpio set 44 ip", NULL); - hw_execute_bash_command("raspi-gpio set 44 a1", NULL); - hw_execute_bash_command("raspi-gpio set 45 ip", NULL); - hw_execute_bash_command("raspi-gpio set 45 a1", NULL); - hardware_sleep_ms(200); - hw_execute_bash_command("i2cdetect -y 0 0x0F 0x0F", NULL); - hardware_sleep_ms(200); - log_line("Done initializing I2C busses for Pi 3/4."); - } - } - - log_line("Ruby: Finding external I2C devices add-ons..."); - printf("Ruby: Finding external I2C devices add-ons...\n"); - fflush(stdout); - hardware_i2c_reset_enumerated_flag(); - hardware_enumerate_i2c_busses(); - // Load existing settings first - hardware_i2c_load_device_settings(); - hardware_i2c_log_devices(); - // Save existing settings and any new devices - hardware_i2c_save_device_settings(); - int iKnown = hardware_get_i2c_found_count_known_devices(); - int iConfigurable = hardware_get_i2c_found_count_configurable_devices(); - if ( 0 == iKnown && 0 == iConfigurable ) + if ( hardware_has_eth() != NULL ) { - log_line("Ruby: Done finding external I2C devices add-ons. None known found." ); - printf("Ruby: Done finding external I2C devices add-ons. None known found.\n" ); + log_line("Device has an ETH port."); + printf("Ruby: Device has an ETH port.\n"); } else { - log_line("Ruby: Done finding external I2C devices add-ons. Found %d known devices of which %d are configurable.", iKnown, iConfigurable ); - printf("Ruby: Done finding external I2C devices add-ons. Found %d known devices of which %d are configurable.\n", iKnown, iConfigurable ); + log_line("Device does not have an ETH port."); + printf("Ruby: Device does not have an ETH port.\n"); } - #endif - - fflush(stdout); - - // Detect hardware - hardware_getCameraType(); - hardware_getBoardType(); - - #ifdef HW_PLATFORM_RASPBERRY - hw_execute_ruby_process(NULL, "ruby_initdhcp", NULL, NULL); - #endif - - detectSystemType(); - - hardware_release(); - - - log_line("Starting Ruby system..."); - fflush(stdout); - - printf("Ruby: Finding serial ports...\n"); - log_line("Ruby: Finding serial ports..."); fflush(stdout); +} - hardware_init_serial_ports(); +void _step_enumerate_radios() +{ + char szComm[256]; printf("Ruby: Enumerating supported 2.4/5.8Ghz radio interfaces...\n"); printf("\n"); @@ -1151,6 +1244,82 @@ int main(int argc, char *argv[]) printf("Ruby: Done finding radio interfaces.\n"); log_line("Ruby: Done finding radio interfaces."); fflush(stdout); +} + + +void handle_sigint(int sig) +{ + log_line("Caught signal to stop: %d\n", sig); + s_bQuit = true; +} + +int main(int argc, char *argv[]) +{ + signal(SIGPIPE, SIG_IGN); + signal(SIGINT, handle_sigint); + signal(SIGTERM, handle_sigint); + signal(SIGQUIT, handle_sigint); + + + if ( _step_process_cmd_line(argc, argv) ) + return 0; + + if ( ! _step_find_console() ) + return 0; + + log_arguments(argc, argv); + printf("\nRuby: Start (v %d.%d b.%d) r%d\n", SYSTEM_SW_VERSION_MAJOR, SYSTEM_SW_VERSION_MINOR/10, SYSTEM_SW_BUILD_NUMBER, s_iBootCount); + fflush(stdout); + + if ( _step_check_file_system() < 0 ) + return 0; + _step_check_binaries_and_processes(); + + char szComm[1204]; + char szOutput[4096]; + szOutput[0] = 0; + + if ( g_bIsFirstBoot ) + do_first_boot_pre_initialization(); + + _step_load_init_devices(); + _step_load_init_radios(); + + sprintf(szComm, "rm -rf %s%s", FOLDER_RUBY_TEMP, FILE_CONFIG_SYSTEM_TYPE); + hw_execute_bash_command_silent(szComm, NULL); + sprintf(szComm, "rm -rf %s%s", FOLDER_RUBY_TEMP, FILE_CONFIG_CAMERA_TYPE); + hw_execute_bash_command_silent(szComm, NULL); + + init_hardware_only_status_led(); + + if ( access( FILE_FORCE_RESET, R_OK ) != -1 ) + { + unlink(FILE_FORCE_RESET); + hw_execute_bash_command("rm -rf config/*", NULL); + sprintf(szComm, "touch %s%s", FOLDER_CONFIG, FILE_CONFIG_FIRST_BOOT); + hw_execute_bash_command(szComm, NULL); + hardware_reboot(); + hardware_sleep_ms(900); + } + + u32 board_type = (hardware_getOnlyBoardType() & BOARD_TYPE_MASK); + + // Detect hardware + hardware_getCameraType(); + hardware_getBoardType(); + + #if defined (HW_PLATFORM_RASPBERRY) || defined (HW_PLATFORM_RADXA_ZERO3) + hw_execute_ruby_process(NULL, "ruby_initdhcp", NULL, NULL); + #endif + + detectSystemType(); + + hardware_release(); + + log_line("Starting Ruby system..."); + fflush(stdout); + + _step_enumerate_radios(); // Reenable serial ports that where used for SiK radio and now are just regular serial ports @@ -1207,9 +1376,10 @@ int main(int argc, char *argv[]) log_line("Feature radio RxTx thread syncronization is: Off."); #endif - if ( bIsFirstBoot ) + if ( g_bIsFirstBoot ) do_first_boot_initialization(s_isVehicle, board_type); - + + char szFile[MAX_FILE_PATH_SIZE]; strcpy(szFile, FOLDER_CONFIG); strcat(szFile, FILE_CONFIG_CURRENT_VEHICLE_MODEL); if ( access( szFile, R_OK) == -1 ) @@ -1362,7 +1532,7 @@ int main(int argc, char *argv[]) strcpy(szFile, FOLDER_CONFIG); strcat(szFile, FILE_CONFIG_CURRENT_VERSION); - fd = fopen(szFile, "w"); + FILE* fd = fopen(szFile, "w"); if ( NULL != fd ) { fprintf(fd, "%u\n", (((u32)SYSTEM_SW_VERSION_MAJOR)<<8) | (u32)SYSTEM_SW_VERSION_MINOR | (((u32)SYSTEM_SW_BUILD_NUMBER)<<16)); @@ -1371,7 +1541,7 @@ int main(int argc, char *argv[]) else log_softerror_and_alarm("Failed to save current version id to file: %s",FILE_CONFIG_CURRENT_VERSION); - if ( bIsFirstBoot ) + if ( g_bIsFirstBoot ) { printf("\n\n\n"); printf("Ruby: First install initialization complete. Rebooting now...\n"); @@ -1458,6 +1628,10 @@ int main(int argc, char *argv[]) } hw_execute_ruby_process_wait(NULL, "ruby_start", szParams, NULL, 1); + log_line("Reloading hardware radio configuration after radio init step completed..."); + hardware_load_radio_info(); + _check_power_levels_of_current_cards(&sRadioInfoPrev[0], iHwRadiosCountPrev); + printf("Ruby: Starting main process...\n"); log_line("Starting main process..."); fflush(stdout); @@ -1562,7 +1736,6 @@ int main(int argc, char *argv[]) { log_line("Current model radio link %d is a SiK radio link. Use it to configure controller.", iSiKRadioLinkIndex+1); uFreq = modelVehicle.radioLinksParams.link_frequency_khz[iSiKRadioLinkIndex]; - uTxPower = modelVehicle.radioInterfacesParams.txPowerSiK, uDataRate = modelVehicle.radioLinksParams.link_datarate_data_bps[iSiKRadioLinkIndex], uECC = (modelVehicle.radioLinksParams.link_radio_flags[iSiKRadioLinkIndex] & RADIO_FLAGS_SIK_ECC)?1:0; uLBT = (modelVehicle.radioLinksParams.link_radio_flags[iSiKRadioLinkIndex] & RADIO_FLAGS_SIK_LBT)?1:0; @@ -1579,6 +1752,7 @@ int main(int argc, char *argv[]) log_softerror_and_alarm("Failed to get radio hardware info for radio interface %d.", i+1); continue; } + uTxPower = modelVehicle.radioInterfacesParams.interface_raw_power[i]; hardware_radio_sik_set_frequency_txpower_airspeed_lbt_ecc(pRadioHWInfo, uFreq, uTxPower, uDataRate, uECC, uLBT, uMCSTR, @@ -1612,7 +1786,6 @@ int main(int argc, char *argv[]) for( int i=0; i<5; i++ ) hardware_sleep_ms(500); - if ( ! g_bDebug ) for( int i=0; i<10; i++ ) hardware_sleep_ms(500); @@ -1693,7 +1866,10 @@ int main(int argc, char *argv[]) { log_error_and_alarm("ruby_tx_telemetry is not running"); bError = true; } if ( bError ) + { printf("Error: Some processes are not running.\n"); + log_line("Error: Some processes are not running."); + } else { u32 uTimeNow = get_current_timestamp_ms(); diff --git a/code/r_station/adaptive_video.cpp b/code/r_station/adaptive_video.cpp index 5027e313..cea5ad17 100644 --- a/code/r_station/adaptive_video.cpp +++ b/code/r_station/adaptive_video.cpp @@ -109,7 +109,8 @@ void _adaptive_video_send_video_profile_to_vehicle(int iVideoProfile, u32 uVehic memcpy(packet+sizeof(t_packet_header), (u8*)&(pRuntimeInfo->uVideoProfileRequestId), sizeof(u32)); memcpy(packet+sizeof(t_packet_header) + sizeof(u32), (u8*)&uVideoProfile, sizeof(u8)); memcpy(packet+sizeof(t_packet_header) + sizeof(u32) + sizeof(u8), (u8*)&uVideoStreamIndex, sizeof(u8)); - packets_queue_inject_packet_first(&s_QueueRadioPacketsHighPrio, packet); + for( int i=0; i<5; i++ ) + packets_queue_inject_packet_first(&s_QueueRadioPacketsHighPrio, packet); } void adaptive_video_switch_to_video_profile(int iVideoProfile, u32 uVehicleId) @@ -281,7 +282,7 @@ void _adaptive_video_check_vehicle(Model* pModel, type_global_state_vehicle_runt } } -void adaptive_video_periodic_loop() +void adaptive_video_periodic_loop(bool bForceSyncNow) { if ( (g_TimeNow < g_TimeStart + 4000) || g_bNegociatingRadioLinks ) return; @@ -323,7 +324,7 @@ void adaptive_video_periodic_loop() continue; // Use last rx time to back off on link lost - if ( g_TimeNow >= pRuntimeInfo->uLastTimeSentVideoProfileRequest+20 ) + if ( bForceSyncNow || (g_TimeNow >= pRuntimeInfo->uLastTimeSentVideoProfileRequest+20) ) { _adaptive_video_send_video_profile_to_vehicle(pRuntimeInfo->uPendingVideoProfileToSet, pRuntimeInfo->uVehicleId); } diff --git a/code/r_station/adaptive_video.h b/code/r_station/adaptive_video.h index e0be1e04..1c867aca 100644 --- a/code/r_station/adaptive_video.h +++ b/code/r_station/adaptive_video.h @@ -5,4 +5,4 @@ void adaptive_video_pause(u32 uMilisec); void adaptive_video_switch_to_video_profile(int iVideoProfile, u32 uVehicleId); void adaptive_video_received_video_profile_switch_confirmation(u32 uRequestId, u8 uVideoProfile, u32 uVehicleId, int iInterfaceIndex); -void adaptive_video_periodic_loop(); +void adaptive_video_periodic_loop(bool bForceSyncNow); diff --git a/code/r_station/packets_utils.cpp b/code/r_station/packets_utils.cpp index c0be1f79..56ebea92 100644 --- a/code/r_station/packets_utils.cpp +++ b/code/r_station/packets_utils.cpp @@ -319,14 +319,27 @@ bool _send_packet_to_serial_radio_interface(int iLocalRadioLinkId, int iRadioInt bool bPacketsSent = true; u8* pData = pPacketData; - int nLength = nPacketLength; - while ( nLength > 0 ) + int nRemainingLength = nPacketLength; + while ( nRemainingLength > 0 ) { t_packet_header* pPH = (t_packet_header*)pData; - if ( ! radio_can_send_packet_on_slow_link(iLocalRadioLinkId, pPH->packet_type, 1, g_TimeNow) ) + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pData; + u8 uPacketType = 0; + int iThisLen = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) { - nLength -= pPH->total_length; - pData += pPH->total_length; + uPacketType = pPHC->packet_type; + iThisLen = pPHC->total_length; + } + else + { + uPacketType = pPH->packet_type; + iThisLen = pPH->total_length; + } + if ( ! radio_can_send_packet_on_slow_link(iLocalRadioLinkId, uPacketType, 1, g_TimeNow) ) + { + nRemainingLength -= iThisLen; + pData += iThisLen; continue; } if ( iAirRate > 0 ) @@ -339,32 +352,39 @@ bool _send_packet_to_serial_radio_interface(int iLocalRadioLinkId, int iRadioInt log_line("Radio interface %d is tx overloaded: sending %d bytes/sec and air data rate is %d bytes/sec", iRadioInterfaceIndex+1, (int)g_SM_RadioStats.radio_interfaces[iRadioInterfaceIndex].txBytesPerSec, iAirRate); send_alarm_to_central(ALARM_ID_RADIO_LINK_DATA_OVERLOAD, (g_SM_RadioStats.radio_interfaces[iRadioInterfaceIndex].txBytesPerSec & 0xFFFFFF) | (((u32)iRadioInterfaceIndex)<<24), (u32)iAirRate); } - nLength -= pPH->total_length; - pData += pPH->total_length; + nRemainingLength -= iThisLen; + pData += iThisLen; continue; } if ( (iLocalRadioLinkId < 0) || (iLocalRadioLinkId >= MAX_RADIO_INTERFACES) ) iLocalRadioLinkId = 0; u16 uRadioLinkPacketIndex = radio_get_next_radio_link_packet_index(iLocalRadioLinkId); - pPH->radio_link_packet_index = uRadioLinkPacketIndex; - - if ( pPH->packet_flags & PACKET_FLAGS_BIT_HEADERS_ONLY_CRC ) - radio_packet_compute_crc((u8*)pPH, sizeof(t_packet_header)); + + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + radio_packet_compressed_compute_crc((u8*)pPHC, pPHC->total_length); else - radio_packet_compute_crc((u8*)pPH, pPH->total_length); + { + pPH->radio_link_packet_index = uRadioLinkPacketIndex; + if ( pPH->packet_flags & PACKET_FLAGS_BIT_HEADERS_ONLY_CRC ) + radio_packet_compute_crc((u8*)pPH, sizeof(t_packet_header)); + else + radio_packet_compute_crc((u8*)pPH, pPH->total_length); + } if ( pRadioHWInfo->openedForWrite ) { - int iWriteResult = radio_tx_send_serial_radio_packet(iRadioInterfaceIndex, (u8*)pPH, pPH->total_length); + int iWriteResult = radio_tx_send_serial_radio_packet(iRadioInterfaceIndex, pData, iThisLen); if ( iWriteResult > 0 ) { - int iTotalSent = pPH->total_length; + int iTotalSent = iThisLen; if ( 0 < g_pCurrentModel->radioLinksParams.iSiKPacketSize ) - iTotalSent += sizeof(t_packet_header_short) * (int) (pPH->total_length / g_pCurrentModel->radioLinksParams.iSiKPacketSize); - u32 uStreamId = (pPH->stream_packet_idx) >> PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + iTotalSent += sizeof(t_packet_header_short) * (int) (iThisLen / g_pCurrentModel->radioLinksParams.iSiKPacketSize); + u32 uStreamId = STREAM_ID_COMPRESSED; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + uStreamId = (pPH->stream_packet_idx) >> PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; radio_stats_update_on_packet_sent_on_radio_interface(&g_SM_RadioStats, g_TimeNow, iRadioInterfaceIndex, iTotalSent); - radio_stats_update_on_packet_sent_on_radio_link(&g_SM_RadioStats, g_TimeNow, iLocalRadioLinkId, (int)uStreamId, pPH->total_length, 1); + radio_stats_update_on_packet_sent_on_radio_link(&g_SM_RadioStats, g_TimeNow, iLocalRadioLinkId, (int)uStreamId, iThisLen, 1); } else { @@ -374,7 +394,7 @@ bool _send_packet_to_serial_radio_interface(int iLocalRadioLinkId, int iRadioInt { if ( hardware_radio_is_sik_radio(pRadioHWInfo) ) radio_links_flag_reinit_sik_interface(iRadioInterfaceIndex); - nLength = 0; + nRemainingLength = 0; break; } } @@ -384,8 +404,8 @@ bool _send_packet_to_serial_radio_interface(int iLocalRadioLinkId, int iRadioInt bPacketsSent = false; log_softerror_and_alarm("Radio serial interface %d is not opened for write. Can't send packet on it.", iRadioInterfaceIndex+1); } - nLength -= pPH->total_length; - pData += pPH->total_length; + nRemainingLength -= iThisLen; + pData += iThisLen; } return bPacketsSent; @@ -412,8 +432,11 @@ bool _send_packet_to_wifi_radio_interface(int iLocalRadioLinkId, int iRadioInter int nRateTx = compute_packet_uplink_datarate(iVehicleRadioLinkId, iRadioInterfaceIndex, &(g_pCurrentModel->radioLinksParams)); t_packet_header* pPH = (t_packet_header*)pPacketData; + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pPacketData; + + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) if ( pPH->packet_type == PACKET_TYPE_RUBY_PAIRING_REQUEST ) - nRateTx = DEFAULT_RADIO_DATARATE_DATA; + nRateTx = DEFAULT_RADIO_DATARATE_LOWEST; radio_set_out_datarate(nRateTx); if ( test_link_is_in_progress() ) @@ -443,17 +466,28 @@ bool _send_packet_to_wifi_radio_interface(int iLocalRadioLinkId, int iRadioInter memset(iTotalBytesOnEachStream, 0, MAX_RADIO_STREAMS*sizeof(int)); u8* pData = pPacketData; - int nLength = nPacketLength; - while ( nLength > 0 ) + int nRemainingLength = nPacketLength; + while ( nRemainingLength > 0 ) { pPH = (t_packet_header*)pData; - u32 uStreamId = (pPH->stream_packet_idx) >> PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; - + pPHC = (t_packet_header_compressed*)pData; + u32 uStreamId = 0; + int iThisLen = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + uStreamId = STREAM_ID_COMPRESSED; + iThisLen = pPHC->total_length; + } + else + { + uStreamId = (pPH->stream_packet_idx) >> PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + iThisLen = pPH->total_length; + } iCountChainedPackets[uStreamId]++; - iTotalBytesOnEachStream[uStreamId] += pPH->total_length; + iTotalBytesOnEachStream[uStreamId] += iThisLen; - nLength -= pPH->total_length; - pData += pPH->total_length; + nRemainingLength -= iThisLen; + pData += iThisLen; } for( int i=0; ipacket_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) if ( pPH->packet_type == PACKET_TYPE_SIK_CONFIG ) { u8 uVehicleLinkId = *(pPacketData + sizeof(t_packet_header)); @@ -508,18 +543,39 @@ int send_packet_to_radio_interfaces(u8* pPacketData, int nPacketLength, int iSen memset(iCountChainedPackets, 0, MAX_RADIO_STREAMS*sizeof(int)); memset(iTotalBytesOnEachStream, 0, MAX_RADIO_STREAMS*sizeof(int)); - u8 uFirstPacketType = 0; t_packet_header* pPHTemp = (t_packet_header*)pPacketData; - uFirstPacketType = pPHTemp->packet_type; - + t_packet_header_compressed* pPHCTemp = (t_packet_header_compressed*)pPacketData; + u8 uFirstPacketType = pPHTemp->packet_type; + if ( (pPHTemp->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + uFirstPacketType = pPHCTemp->packet_type; + u8 uPacketType = uFirstPacketType; + int iPacketLength = 0; + u32 uStreamId = 0; u8* pData = pPacketData; - int nLength = nPacketLength; + int nRemainingLength = nPacketLength; - while ( nLength > 0 ) + while ( nRemainingLength > 0 ) { iTotalPackets++; t_packet_header* pPH = (t_packet_header*)pData; + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pData; + + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + uPacketType = pPHC->packet_type; + iPacketLength = pPHC->total_length; + uDestVehicleId = pPHC->vehicle_id_dest; + uStreamId = STREAM_ID_COMPRESSED; + } + else + { + uPacketType = pPH->packet_type; + iPacketLength = pPH->total_length; + uDestVehicleId = pPH->vehicle_id_dest; + uStreamId = (pPH->stream_packet_idx) >> PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + } + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) if ( pPH->packet_type == PACKET_TYPE_RUBY_PING_CLOCK ) { u8 uLocalRadioLinkId = 0; @@ -528,6 +584,7 @@ int send_packet_to_radio_interfaces(u8* pPacketData, int nPacketLength, int iSen bHasPingPacket = true; } + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) if ( pPH->packet_type == PACKET_TYPE_TEST_RADIO_LINK ) { int iModelRadioLinkIndex = pData[sizeof(t_packet_header)+2]; @@ -547,26 +604,27 @@ int send_packet_to_radio_interfaces(u8* pPacketData, int nPacketLength, int iSen //if ( pPH->packet_type == PACKET_TYPE_VIDEO_REQ_MULTIPLE_PACKETS2) // iCountRetransmissionsPackets++; - uDestVehicleId = pPH->vehicle_id_dest; - u32 uStreamId = (pPH->stream_packet_idx) >> PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; - if ( pPH->packet_type != PACKET_TYPE_RUBY_PING_CLOCK ) - if ( pPH->packet_type != PACKET_TYPE_RUBY_PING_CLOCK_REPLY ) + if ( uPacketType != PACKET_TYPE_RUBY_PING_CLOCK ) + if ( uPacketType != PACKET_TYPE_RUBY_PING_CLOCK_REPLY ) s_StreamsTxPacketIndex[uStreamId]++; - pPH->stream_packet_idx = (((u32)uStreamId)<packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + pPHC->stream_packet_idx = (((u32)uStreamId)<stream_packet_idx = (((u32)uStreamId)<total_length; + iTotalBytesOnEachStream[uStreamId] += iPacketLength; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) if ( s_bReceivedInvalidRadioPackets ) pPH->vehicle_id_src = 0; - nLength -= pPH->total_length; - pData += pPH->total_length; + nRemainingLength -= iPacketLength; + pData += iPacketLength; } - // Send the received composed packet (or single packet) to each local radio link + // Send the composed packet (or single packet) to each local radio link for( int iLocalRadioLinkId=0; iLocalRadioLinkIdradioInterfacesParams), sizeof(type_radio_interfaces_parameters)); memcpy(&oldRadioLinksParams, &(g_pCurrentModel->radioLinksParams), sizeof(type_radio_links_parameters)); memcpy(&oldRCParams, &(g_pCurrentModel->rc_params), sizeof(rc_parameters_t)); @@ -185,50 +190,83 @@ void _process_local_notification_model_changed(t_packet_header* pPH, u8 uChangeT memcpy(&oldVideoParams, &(g_pCurrentModel->video_params), sizeof(video_parameters_t)); u32 oldEFlags = g_pCurrentModel->enc_flags; - ControllerSettings* pCS = get_ControllerSettings(); - int iOldTxPowerSiK = pCS->iTXPowerSiK; if ( uChangeType == MODEL_CHANGED_RADIO_POWERS ) { log_line("Received local notification that radio powers have changed."); load_ControllerSettings(); - if ( iOldTxPowerSiK == pCS->iTXPowerSiK ) - { - log_line("SiK Tx power is unchanged. Ignoring this notification."); - return; - } - log_line("SiK Tx power changed from %d to %d. Updating SiK radio interfaces params...", iOldTxPowerSiK, pCS->iTXPowerSiK); - if ( g_SiKRadiosState.bConfiguringToolInProgress ) - { - log_softerror_and_alarm("Another SiK configuration is in progress. Ignoring this one."); - return; - } + load_ControllerInterfacesSettings(); + + apply_controller_radio_tx_powers(g_pCurrentModel, pCS->iFixedTxPower, false); - if ( g_SiKRadiosState.bConfiguringSiKThreadWorking ) + int iSikRadioIndexToUpdate = -1; + int iSikOldPower = -1; + int iSikNewPower = -1; + for( int i=0; iisConfigurable ) + continue; + if ( !hardware_radio_index_is_sik_radio(i) ) + continue; + + t_ControllerRadioInterfaceInfo* pCRII = controllerGetRadioCardInfo(pRadioHWInfo->szMAC); + if ( NULL == pCRII ) + continue; + + for( int k=0; kszMAC, oldCIS.listRadioInterfaces[k].szMAC, MAX_MAC_LENGTH) ) + if ( pCRII->iRawPowerLevel != oldCIS.listRadioInterfaces[k].iRawPowerLevel ) + { + iSikOldPower = oldCIS.listRadioInterfaces[k].iRawPowerLevel; + iSikRadioIndexToUpdate = i; + break; + } + } } - if ( g_SiKRadiosState.bMustReinitSiKInterfaces ) + if ( iSikRadioIndexToUpdate != -1 ) { - log_softerror_and_alarm("SiK reinitialization is already flagged. Ignoring this notification."); - return; - } + radio_hw_info_t* pRadioHWInfo = hardware_get_radio_info(iSikRadioIndexToUpdate); + t_ControllerRadioInterfaceInfo* pCRII = controllerGetRadioCardInfo(pRadioHWInfo->szMAC); + iSikNewPower = pCRII->iRawPowerLevel; + if ( (iSikNewPower < 0) || (iSikNewPower > 20) ) + iSikNewPower = 20; + log_line("SiK Tx power changed on radio interface %d from %d to %d. Updating SiK radio interface params...", + iSikRadioIndexToUpdate, iSikOldPower, iSikNewPower); + if ( g_SiKRadiosState.bConfiguringToolInProgress ) + { + log_softerror_and_alarm("Another SiK configuration is in progress. Ignoring this one."); + return; + } - radio_links_close_and_mark_sik_interfaces_to_reopen(); - g_SiKRadiosState.bConfiguringToolInProgress = true; - g_SiKRadiosState.uTimeStartConfiguring = g_TimeNow; - - char szCommand[128]; - sprintf(szCommand, "rm -rf %s%s", FOLDER_RUBY_TEMP, FILE_TEMP_SIK_CONFIG_FINISHED); - hw_execute_bash_command(szCommand, NULL); + if ( g_SiKRadiosState.bConfiguringSiKThreadWorking ) + { + log_softerror_and_alarm("SiK reinitialization thread is in progress. Ignoring this notification."); + return; + } - sprintf(szCommand, "./ruby_sik_config none 0 -power %d &", pCS->iTXPowerSiK); - hw_execute_bash_command(szCommand, NULL); + if ( g_SiKRadiosState.bMustReinitSiKInterfaces ) + { + log_softerror_and_alarm("SiK reinitialization is already flagged. Ignoring this notification."); + return; + } - // Do not need to notify other components. Just return. - return; + radio_links_close_and_mark_sik_interfaces_to_reopen(); + g_SiKRadiosState.bConfiguringToolInProgress = true; + g_SiKRadiosState.uTimeStartConfiguring = g_TimeNow; + + char szCommand[128]; + sprintf(szCommand, "rm -rf %s%s", FOLDER_RUBY_TEMP, FILE_TEMP_SIK_CONFIG_FINISHED); + hw_execute_bash_command(szCommand, NULL); + + sprintf(szCommand, "./ruby_sik_config none 0 -power %d &", iSikNewPower); + hw_execute_bash_command(szCommand, NULL); + + // Do not need to notify other components. Just return. + return; + } } // Reload new model state @@ -664,8 +702,7 @@ void process_local_control_packet(t_packet_header* pPH) break; if ( g_pVideoProcessorRxList[i]->m_uVehicleId == pPH->vehicle_id_src ) { - // To fix? - //g_pVideoProcessorRxList[i]->resetRetransmissionsStats(); + g_pVideoProcessorRxList[i]->discardRetransmissionsInfo(); break; } } diff --git a/code/r_station/process_radio_in_packets.cpp b/code/r_station/process_radio_in_packets.cpp index e936e11e..2d7689ab 100644 --- a/code/r_station/process_radio_in_packets.cpp +++ b/code/r_station/process_radio_in_packets.cpp @@ -83,20 +83,39 @@ void init_radio_rx_structures() s_ParserH264RadioInput.init(); } - int _process_received_ruby_message(int iInterfaceIndex, u8* pPacketBuffer) { t_packet_header* pPH = (t_packet_header*)pPacketBuffer; + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pPacketBuffer; + + u8 uPacketType = 0; + int iTotalLength = 0; + u32 uVehicleIdSrc = 0; + u32 uVehicleIdDest = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + uPacketType = pPHC->packet_type; + iTotalLength = pPHC->total_length; + uVehicleIdSrc = pPHC->vehicle_id_src; + uVehicleIdDest = pPHC->vehicle_id_dest; + } + else + { + uPacketType = pPH->packet_type; + iTotalLength = pPH->total_length; + uVehicleIdSrc = pPH->vehicle_id_src; + uVehicleIdDest = pPH->vehicle_id_dest; + } - if ( pPH->packet_type == PACKET_TYPE_TEST_RADIO_LINK ) + if ( uPacketType == PACKET_TYPE_TEST_RADIO_LINK ) { test_link_process_received_message(iInterfaceIndex, pPacketBuffer); return 0; } - if ( pPH->packet_type == PACKET_TYPE_DEBUG_VEHICLE_RT_INFO ) + if ( uPacketType == PACKET_TYPE_DEBUG_VEHICLE_RT_INFO ) { - if ( pPH->total_length == sizeof(t_packet_header) + sizeof(vehicle_runtime_info) ) + if ( iTotalLength == sizeof(t_packet_header) + sizeof(vehicle_runtime_info) ) { memcpy((u8*)&g_SMVehicleRTInfo, pPacketBuffer + sizeof(t_packet_header), sizeof(vehicle_runtime_info)); if ( g_SMControllerRTInfo.iCurrentIndex > 100 && g_SMControllerRTInfo.iCurrentIndex < 150 ) @@ -118,17 +137,17 @@ int _process_received_ruby_message(int iInterfaceIndex, u8* pPacketBuffer) return 0; } - if ( pPH->packet_type == PACKET_TYPE_RUBY_RADIO_CONFIG_UPDATED ) + if ( uPacketType == PACKET_TYPE_RUBY_RADIO_CONFIG_UPDATED ) { - log_line("Received current radio configuration from vehicle uid %u, packet size: %d bytes.", pPH->vehicle_id_src, pPH->total_length); - if ( pPH->total_length != (sizeof(t_packet_header) + sizeof(type_relay_parameters) + sizeof(type_radio_interfaces_parameters) + sizeof(type_radio_links_parameters)) ) + log_line("Received current radio configuration from vehicle uid %u, packet size: %d bytes.", uVehicleIdSrc, iTotalLength); + if ( iTotalLength != (sizeof(t_packet_header) + sizeof(type_relay_parameters) + sizeof(type_radio_interfaces_parameters) + sizeof(type_radio_links_parameters)) ) { log_softerror_and_alarm("Received current radio configuration: invalid packet size. Ignoring."); return 0; } if ( NULL == g_pCurrentModel ) return 0; - if ( g_pCurrentModel->uVehicleId == pPH->vehicle_id_src ) + if ( g_pCurrentModel->uVehicleId == uVehicleIdSrc ) { type_radio_interfaces_parameters radioInt; type_radio_links_parameters radioLinks; @@ -154,45 +173,45 @@ int _process_received_ruby_message(int iInterfaceIndex, u8* pPacketBuffer) return 0; } - if ( pPH->packet_type == PACKET_TYPE_RUBY_PAIRING_CONFIRMATION ) + if ( uPacketType == PACKET_TYPE_RUBY_PAIRING_CONFIRMATION ) { u32 uResendCount = 0; - if ( pPH->total_length >= sizeof(t_packet_header) + sizeof(u32) ) + if ( iTotalLength >= (int)(sizeof(t_packet_header) + sizeof(u32)) ) memcpy(&uResendCount, pPacketBuffer + sizeof(t_packet_header), sizeof(u32)); - log_line("Received pairing confirmation from vehicle (received vehicle resend counter: %u). VID: %u, CID: %u", uResendCount, pPH->vehicle_id_src, pPH->vehicle_id_dest); + log_line("Received pairing confirmation from vehicle (received vehicle resend counter: %u). VID: %u, CID: %u", uResendCount, uVehicleIdSrc, uVehicleIdDest); - int iRuntimeIndex = getVehicleRuntimeIndex(pPH->vehicle_id_src); + int iRuntimeIndex = getVehicleRuntimeIndex(uVehicleIdSrc); if ( -1 == iRuntimeIndex ) { - log_softerror_and_alarm("Received pairing confirmation from unknown VID %u. Currently known runtime vehicles:", pPH->vehicle_id_src); + log_softerror_and_alarm("Received pairing confirmation from unknown VID %u. Currently known runtime vehicles:", uVehicleIdSrc); logCurrentVehiclesRuntimeInfo(); return 0; } if ( ! g_State.vehiclesRuntimeInfo[iRuntimeIndex].bIsPairingDone ) { - ruby_ipc_channel_send_message(g_fIPCToCentral, pPacketBuffer, pPH->total_length); + ruby_ipc_channel_send_message(g_fIPCToCentral, pPacketBuffer, iTotalLength); if ( NULL != g_pProcessStats ) g_pProcessStats->lastIPCOutgoingTime = g_TimeNow; - send_alarm_to_central(ALARM_ID_CONTROLLER_PAIRING_COMPLETED, pPH->vehicle_id_src, 0); + send_alarm_to_central(ALARM_ID_CONTROLLER_PAIRING_COMPLETED, uVehicleIdSrc, 0); g_State.vehiclesRuntimeInfo[iRuntimeIndex].bIsPairingDone = true; } return 0; } - if ( (pPH->packet_type == PACKET_TYPE_SIK_CONFIG) || (pPH->packet_type == PACKET_TYPE_OTA_UPDATE_STATUS) ) + if ( (uPacketType == PACKET_TYPE_SIK_CONFIG) || (uPacketType == PACKET_TYPE_OTA_UPDATE_STATUS) ) { if ( -1 != g_fIPCToCentral ) - ruby_ipc_channel_send_message(g_fIPCToCentral, (u8*)pPH, pPH->total_length); + ruby_ipc_channel_send_message(g_fIPCToCentral, (u8*)pPH, iTotalLength); else log_softerror_and_alarm("Received SiK config message but there is not channel to central to notify it."); return 0; } - if ( pPH->packet_type == PACKET_TYPE_RUBY_RADIO_REINITIALIZED ) + if ( uPacketType == PACKET_TYPE_RUBY_RADIO_REINITIALIZED ) { log_line("Received message that vehicle radio interfaces where reinitialized."); t_packet_header PH; @@ -205,14 +224,14 @@ int _process_received_ruby_message(int iInterfaceIndex, u8* pPacketBuffer) return 0; } - if ( pPH->packet_type == PACKET_TYPE_RUBY_ALARM ) + if ( uPacketType == PACKET_TYPE_RUBY_ALARM ) { u32 uAlarmIndex = 0; u32 uAlarm = 0; u32 uFlags1 = 0; u32 uFlags2 = 0; char szBuff[256]; - if ( pPH->total_length == (int)(sizeof(t_packet_header) + 3 * sizeof(u32)) ) + if ( iTotalLength == ((int)(sizeof(t_packet_header) + 3 * sizeof(u32))) ) { memcpy(&uAlarm, pPacketBuffer + sizeof(t_packet_header), sizeof(u32)); memcpy(&uFlags1, pPacketBuffer + sizeof(t_packet_header) + sizeof(u32), sizeof(u32)); @@ -221,7 +240,7 @@ int _process_received_ruby_message(int iInterfaceIndex, u8* pPacketBuffer) log_line("Received alarm from vehicle (old format). Alarm: %s, alarm index: %u", szBuff, uAlarmIndex); } // New format, version 7.5 - else if ( pPH->total_length == (int)(sizeof(t_packet_header) + 4 * sizeof(u32)) ) + else if ( iTotalLength == ((int)(sizeof(t_packet_header) + 4 * sizeof(u32))) ) { memcpy(&uAlarmIndex, pPacketBuffer + sizeof(t_packet_header), sizeof(u32)); memcpy(&uAlarm, pPacketBuffer + sizeof(t_packet_header) + sizeof(u32), sizeof(u32)); @@ -256,7 +275,7 @@ int _process_received_ruby_message(int iInterfaceIndex, u8* pPacketBuffer) } else { - log_softerror_and_alarm("Received invalid alarm from vehicle. Received %d bytes, expected %d bytes", pPH->total_length, (int)sizeof(t_packet_header) + 4 * (int)sizeof(u32)); + log_softerror_and_alarm("Received invalid alarm from vehicle. Received %d bytes, expected %d bytes", iTotalLength, (int)sizeof(t_packet_header) + 4 * (int)sizeof(u32)); return 0; } @@ -276,16 +295,16 @@ int _process_received_ruby_message(int iInterfaceIndex, u8* pPacketBuffer) log_line("Received alarm that vehicle recovered the connection from controller."); } - log_line("Send alarm to central"); - ruby_ipc_channel_send_message(g_fIPCToCentral, pPacketBuffer, pPH->total_length); + log_line("Sending the alarm to central..."); + ruby_ipc_channel_send_message(g_fIPCToCentral, pPacketBuffer, iTotalLength); if ( NULL != g_pProcessStats ) g_pProcessStats->lastIPCOutgoingTime = g_TimeNow; log_line("Sent alarm to central"); return 0; } - if ( pPH->packet_type == PACKET_TYPE_RUBY_PING_CLOCK_REPLY ) - if ( pPH->total_length >= sizeof(t_packet_header) + 2*sizeof(u8) + sizeof(u32) ) + if ( uPacketType == PACKET_TYPE_RUBY_PING_CLOCK_REPLY ) + if ( iTotalLength >= (int)(sizeof(t_packet_header) + 2*sizeof(u8) + sizeof(u32)) ) { u8 uPingId = 0; u32 uVehicleLocalTimeMs = 0; @@ -297,20 +316,28 @@ int _process_received_ruby_message(int iInterfaceIndex, u8* pPacketBuffer) memcpy(&uOriginalLocalRadioLinkId, pPacketBuffer + sizeof(t_packet_header)+sizeof(u8)+sizeof(u32), sizeof(u8)); if ( pPH->total_length > sizeof(t_packet_header) + 2*sizeof(u8) + sizeof(u32) ) memcpy(&uReplyVehicleLocalRadioLinkId, pPacketBuffer + sizeof(t_packet_header)+2*sizeof(u8) + sizeof(u32), sizeof(u8)); - int iIndex = getVehicleRuntimeIndex(pPH->vehicle_id_src); if ( iIndex >= 0 ) { if ( uPingId == g_State.vehiclesRuntimeInfo[iIndex].uLastPingIdSentToVehicleOnLocalRadioLinks[uOriginalLocalRadioLinkId] ) { - u32 uRoundtripMilis = get_current_timestamp_ms() - g_State.vehiclesRuntimeInfo[iIndex].uTimeLastPingSentToVehicleOnLocalRadioLinks[uOriginalLocalRadioLinkId]; + g_TimeNow = get_current_timestamp_ms(); + u32 uRoundtripMilis = g_TimeNow - g_State.vehiclesRuntimeInfo[iIndex].uTimeLastPingSentToVehicleOnLocalRadioLinks[uOriginalLocalRadioLinkId]; controller_rt_info_update_ack_rt_time(&g_SMControllerRTInfo, pPH->vehicle_id_src, g_SM_RadioStats.radio_interfaces[iInterfaceIndex].assignedLocalRadioLinkId, uRoundtripMilis); if ( uPingId != g_State.vehiclesRuntimeInfo[iIndex].uLastPingIdReceivedFromVehicleOnLocalRadioLinks[uOriginalLocalRadioLinkId] ) { g_State.vehiclesRuntimeInfo[iIndex].uLastPingIdReceivedFromVehicleOnLocalRadioLinks[uOriginalLocalRadioLinkId] = uPingId; g_State.vehiclesRuntimeInfo[iIndex].uTimeLastPingReplyReceivedFromVehicleOnLocalRadioLinks[uOriginalLocalRadioLinkId] = g_TimeNow; g_State.vehiclesRuntimeInfo[iIndex].uPingRoundtripTimeOnLocalRadioLinks[uOriginalLocalRadioLinkId] = uRoundtripMilis; - adjustLinkClockDeltasForVehicleRuntimeIndex(iIndex, uRoundtripMilis, uVehicleLocalTimeMs); + if ( uRoundtripMilis < g_State.vehiclesRuntimeInfo[iIndex].uMinimumPingTimeMilisec ) + { + g_State.vehiclesRuntimeInfo[iIndex].uMinimumPingTimeMilisec = uRoundtripMilis; + adjustLinkClockDeltasForVehicleRuntimeIndex(iIndex, uRoundtripMilis, uVehicleLocalTimeMs); + } + + //log_line("DEBUG recv ping, roundtrip: %u ms, min %u ms", + // uRoundtripMilis, g_State.vehiclesRuntimeInfo[iIndex].uMinimumPingTimeMilisec); + //log_line("DEBUG vehicle clock %u, computed vehicle clock %u", uVehicleLocalTimeMs, g_TimeNow + g_State.vehiclesRuntimeInfo[iIndex].iVehicleClockDeltaMilisec); } } } @@ -319,17 +346,18 @@ int _process_received_ruby_message(int iInterfaceIndex, u8* pPacketBuffer) return 0; } - if ( pPH->packet_type == PACKET_TYPE_RUBY_MODEL_SETTINGS ) + if ( uPacketType == PACKET_TYPE_RUBY_MODEL_SETTINGS ) { if ( -1 != g_fIPCToCentral ) - ruby_ipc_channel_send_message(g_fIPCToCentral, (u8*)pPH, pPH->total_length); + ruby_ipc_channel_send_message(g_fIPCToCentral, (u8*)pPH, iTotalLength); else - log_softerror_and_alarm("Received message with current compressed model settings (%d bytes) but there is not channel to central to notify it.", pPH->total_length - sizeof(t_packet_header)); + log_softerror_and_alarm("Received message with current compressed model settings (%d bytes) but there is not channel to central to notify it.", iTotalLength - sizeof(t_packet_header)); return 0; } - if ( pPH->packet_type == PACKET_TYPE_RUBY_LOG_FILE_SEGMENT ) + if ( uPacketType == PACKET_TYPE_RUBY_LOG_FILE_SEGMENT ) + if ( iTotalLength >= (int)sizeof(t_packet_header) ) { t_packet_header_file_segment* pPHFS = (t_packet_header_file_segment*)(pPacketBuffer + sizeof(t_packet_header)); log_line("Received a log file segment: file id: %d, segment size: %d, segment index: %d", pPHFS->file_id, (int)pPHFS->segment_size, (int)pPHFS->segment_index); @@ -362,14 +390,16 @@ int _process_received_ruby_message(int iInterfaceIndex, u8* pPacketBuffer) return 0; } - if ( pPH->packet_type == PACKET_TYPE_NEGOCIATE_RADIO_LINKS ) + if ( uPacketType == PACKET_TYPE_NEGOCIATE_RADIO_LINKS ) + if ( iTotalLength > (int)sizeof(t_packet_header)+1 ) { + // uCommand is second byte after header u8 uCommand = pPacketBuffer[sizeof(t_packet_header) + sizeof(u8)]; if ( NEGOCIATE_RADIO_STEP_DATA_RATE == uCommand ) { radio_stats_reset_interfaces_rx_info(&g_SM_RadioStats); } - ruby_ipc_channel_send_message(g_fIPCToCentral, pPacketBuffer, pPH->total_length); + ruby_ipc_channel_send_message(g_fIPCToCentral, pPacketBuffer, iTotalLength); if ( NULL != g_pProcessStats ) g_pProcessStats->lastIPCOutgoingTime = g_TimeNow; return 0; @@ -515,62 +545,27 @@ void _process_received_single_packet_while_searching(int interfaceIndex, u8* pDa } } -void _parse_single_packet_h264_data(u8* pPacketData, bool bIsRelayed) + +void _check_update_first_pairing_done_if_needed(int iInterfaceIndex, u8* pPacketData) { - if ( NULL == pPacketData ) + if ( g_bFirstModelPairingDone || g_bSearching || (NULL == pPacketData) ) return; -// To fix - /* + t_packet_header* pPH = (t_packet_header*)pPacketData; - t_packet_header_video_full_77* pPHVF = (t_packet_header_video_full_77*) (pPacketData+sizeof(t_packet_header)); - int iVideoDataLength = pPHVF->video_data_length; - u8* pData = pPacketData + sizeof(t_packet_header) + sizeof(t_packet_header_video_full_77); + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pPacketData; - bool bStartOfFrameDetected = s_ParserH264RadioInput.parseData(pData, iVideoDataLength, g_TimeNow); - if ( ! bStartOfFrameDetected ) - return; - - if ( g_iDebugShowKeyFramesAfterRelaySwitch > 0 ) - if ( s_ParserH264RadioInput.IsInsideIFrame() ) + u32 uStreamPacketIndex = 0; + u32 uVehicleIdSrc = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) { - log_line("[Debug] Received video keyframe from VID %u after relay switch.", pPH->vehicle_id_src); - g_iDebugShowKeyFramesAfterRelaySwitch--; + uStreamPacketIndex = pPHC->stream_packet_idx; + uVehicleIdSrc = pPHC->vehicle_id_src; } - - u32 uLastFrameDuration = s_ParserH264RadioInput.getTimeDurationOfLastCompleteFrame(); - if ( uLastFrameDuration > 127 ) - uLastFrameDuration = 127; - if ( uLastFrameDuration < 1 ) - uLastFrameDuration = 1; - - u32 uLastFrameSize = s_ParserH264RadioInput.getSizeOfLastCompleteFrame(); - uLastFrameSize /= 1000; // transform to kbytes - - if ( uLastFrameSize > 127 ) - uLastFrameSize = 127; // kbytes - - g_SM_VideoInfoStatsRadioIn.uLastIndex = (g_SM_VideoInfoStatsRadioIn.uLastIndex+1) % MAX_FRAMES_SAMPLES; - g_SM_VideoInfoStatsRadioIn.uFramesDuration[g_SM_VideoInfoStatsRadioIn.uLastIndex] = uLastFrameDuration; - g_SM_VideoInfoStatsRadioIn.uFramesTypesAndSizes[g_SM_VideoInfoStatsRadioIn.uLastIndex] = (g_SM_VideoInfoStatsRadioIn.uFramesTypesAndSizes[g_SM_VideoInfoStatsRadioIn.uLastIndex] & 0x80) | ((u8)uLastFrameSize); - - u32 uNextIndex = (g_SM_VideoInfoStatsRadioIn.uLastIndex+1) % MAX_FRAMES_SAMPLES; - - if ( s_ParserH264RadioInput.IsInsideIFrame() ) - g_SM_VideoInfoStatsRadioIn.uFramesTypesAndSizes[uNextIndex] |= (1<<7); else - g_SM_VideoInfoStatsRadioIn.uFramesTypesAndSizes[uNextIndex] &= 0x7F; - - g_SM_VideoInfoStatsRadioIn.uKeyframeIntervalMs = s_ParserH264RadioInput.getCurrentlyDetectedKeyframeIntervalMs(); - g_SM_VideoInfoStatsRadioIn.uDetectedFPS = s_ParserH264RadioInput.getDetectedFPS(); - g_SM_VideoInfoStatsRadioIn.uDetectedSlices = (u32) s_ParserH264RadioInput.getDetectedSlices(); -*/ -} - - -void _check_update_first_pairing_done_if_needed(int iInterfaceIndex, t_packet_header *pPH) -{ - if ( g_bFirstModelPairingDone || g_bSearching || (NULL == pPH) ) - return; + { + uStreamPacketIndex = pPH->stream_packet_idx; + uVehicleIdSrc = pPH->vehicle_id_src; + } radio_hw_info_t* pRadioHWInfo = hardware_get_radio_info(iInterfaceIndex); u32 uCurrentFrequencyKhz = 0; @@ -578,16 +573,16 @@ void _check_update_first_pairing_done_if_needed(int iInterfaceIndex, t_packet_he { uCurrentFrequencyKhz = pRadioHWInfo->uCurrentFrequencyKhz; log_line("Received first radio packet (packet index %u) (from VID %u) on radio interface %d, freq: %s, and first pairing was not done. Do first pairing now.", - pPH->stream_packet_idx & PACKET_FLAGS_MASK_STREAM_PACKET_IDX, pPH->vehicle_id_src, iInterfaceIndex+1, str_format_frequency(uCurrentFrequencyKhz)); + uStreamPacketIndex & PACKET_FLAGS_MASK_STREAM_PACKET_IDX, uVehicleIdSrc, iInterfaceIndex+1, str_format_frequency(uCurrentFrequencyKhz)); } else - log_line("Received first radio packet (packet index %u) (from VID %u) on radio interface %d and first pairing was not done. Do first pairing now.", pPH->stream_packet_idx & PACKET_FLAGS_MASK_STREAM_PACKET_IDX, pPH->vehicle_id_src, iInterfaceIndex+1); + log_line("Received first radio packet (packet index %u) (from VID %u) on radio interface %d and first pairing was not done. Do first pairing now.", uStreamPacketIndex & PACKET_FLAGS_MASK_STREAM_PACKET_IDX, uVehicleIdSrc, iInterfaceIndex+1); log_line("Current router local model VID: %u, ptr: %X, models current model: VID: %u, ptr: %X", g_pCurrentModel->uVehicleId, g_pCurrentModel, getCurrentModel()->uVehicleId, getCurrentModel()); g_bFirstModelPairingDone = true; - g_pCurrentModel->uVehicleId = pPH->vehicle_id_src; + g_pCurrentModel->uVehicleId = uVehicleIdSrc; g_pCurrentModel->b_mustSyncFromVehicle = true; g_pCurrentModel->is_spectator = false; deleteAllModels(); @@ -599,8 +594,8 @@ void _check_update_first_pairing_done_if_needed(int iInterfaceIndex, t_packet_he ruby_set_is_first_pairing_done(); resetVehicleRuntimeInfo(0); - g_SM_RouterVehiclesRuntimeInfo.uVehiclesIds[0] = pPH->vehicle_id_src; - g_State.vehiclesRuntimeInfo[0].uVehicleId = pPH->vehicle_id_src; + g_SM_RouterVehiclesRuntimeInfo.uVehiclesIds[0] = uVehicleIdSrc; + g_State.vehiclesRuntimeInfo[0].uVehicleId = uVehicleIdSrc; // Notify central t_packet_header PH; @@ -621,23 +616,57 @@ void _check_update_first_pairing_done_if_needed(int iInterfaceIndex, t_packet_he } - // Returns 1 if end of a video block was reached // Returns -1 if the packet is not for this vehicle or was not processed int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDataLength) { t_packet_header* pPH = (t_packet_header*)pData; - + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pData; + + u32 uStreamPacketIndex = 0; + u32 uVehicleIdSrc = 0; + u32 uVehicleIdDest = 0; + u8 uPacketType = 0; + u8 uPacketFlags = 0; + int iPacketLength = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + uStreamPacketIndex = pPHC->stream_packet_idx; + uVehicleIdSrc = pPHC->vehicle_id_src; + uVehicleIdDest = pPHC->vehicle_id_dest; + uPacketType = pPHC->packet_type; + iPacketLength = pPHC->total_length; + uPacketFlags = pPHC->packet_flags; + uPacketFlags &= ~(PACKET_FLAGS_MASK_MODULE); + uPacketFlags |= pPHC->uExtraBits & PACKET_FLAGS_MASK_MODULE; + } + else + { + uStreamPacketIndex = pPH->stream_packet_idx; + uVehicleIdSrc = pPH->vehicle_id_src; + uVehicleIdDest = pPH->vehicle_id_dest; + uPacketType = pPH->packet_type; + iPacketLength = pPH->total_length; + uPacketFlags = pPH->packet_flags; + } + if ( NULL != g_pProcessStats ) + { + // Added in radio_rx thread too + u32 uGap = g_TimeNow - g_pProcessStats->lastRadioRxTime; + if ( uGap > 255 ) + uGap = 255; + if ( uGap > g_SMControllerRTInfo.uRxMaxAirgapSlots2[g_SMControllerRTInfo.iCurrentIndex] ) + g_SMControllerRTInfo.uRxMaxAirgapSlots2[g_SMControllerRTInfo.iCurrentIndex] = uGap; g_pProcessStats->lastRadioRxTime = g_TimeNow; - + } #ifdef PROFILE_RX u32 timeStart = get_current_timestamp_ms(); #endif - _check_update_first_pairing_done_if_needed(iInterfaceIndex, pPH); + _check_update_first_pairing_done_if_needed(iInterfaceIndex, pData); // Searching ? @@ -647,12 +676,14 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa return 0; } - if ( (0 == pPH->vehicle_id_src) || (MAX_U32 == pPH->vehicle_id_src) ) - log_softerror_and_alarm("Received invalid radio packet: Invalid source vehicle id: %u (vehicle id dest: %u, packet type: %s)", - pPH->vehicle_id_src, pPH->vehicle_id_dest, str_get_packet_type(pPH->packet_type)); + if ( (0 == uVehicleIdSrc) || (MAX_U32 == uVehicleIdSrc) ) + { + log_error_and_alarm("Received invalid radio packet: Invalid source vehicle id: %u (vehicle id dest: %u, packet type: %s, %d bytes, %d total bytes, component: %d)", + uVehicleIdSrc, uVehicleIdDest, str_get_packet_type(uPacketType), iDataLength, pPH->total_length, pPH->packet_flags & PACKET_FLAGS_MASK_MODULE); + return -1; + } - u32 uVehicleId = pPH->vehicle_id_src; - u32 uStreamId = (pPH->stream_packet_idx)>>PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + u32 uStreamId = (uStreamPacketIndex)>>PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; if ( uStreamId >= MAX_RADIO_STREAMS ) uStreamId = 0; @@ -661,7 +692,7 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa { if ( 0 == g_State.vehiclesRuntimeInfo[i].uVehicleId ) break; - if ( g_State.vehiclesRuntimeInfo[i].uVehicleId == uVehicleId ) + if ( g_State.vehiclesRuntimeInfo[i].uVehicleId == uVehicleIdSrc ) { bNewVehicleId = false; break; @@ -670,7 +701,7 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa if ( bNewVehicleId ) { - log_line("Start receiving radio packets from new VID: %u", pPH->vehicle_id_src); + log_line("Start receiving radio packets from new VID: %u", uVehicleIdSrc); int iCount = 0; int iFirstFree = -1; for( int i=0; i= MAX_CONCURENT_VEHICLES) || (-1 == iFirstFree) ) - log_softerror_and_alarm("No more room to store the new VID: %u", pPH->vehicle_id_src); + log_softerror_and_alarm("No more room to store the new VID: %u", uVehicleIdSrc); else { resetVehicleRuntimeInfo(iFirstFree); - g_SM_RouterVehiclesRuntimeInfo.uVehiclesIds[iFirstFree] = uVehicleId; - g_State.vehiclesRuntimeInfo[iFirstFree].uVehicleId = uVehicleId; + g_SM_RouterVehiclesRuntimeInfo.uVehiclesIds[iFirstFree] = uVehicleIdSrc; + g_State.vehiclesRuntimeInfo[iFirstFree].uVehicleId = uVehicleIdSrc; } } - int iRuntimeIndex = getVehicleRuntimeIndex(uVehicleId); + int iRuntimeIndex = getVehicleRuntimeIndex(uVehicleIdSrc); if ( -1 != iRuntimeIndex ) { - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_COMMANDS ) - if ( pPH->packet_type == PACKET_TYPE_COMMAND_RESPONSE ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_COMMANDS ) + if ( uPacketType == PACKET_TYPE_COMMAND_RESPONSE ) + { g_State.vehiclesRuntimeInfo[iRuntimeIndex].uLastTimeReceivedAckFromVehicle = g_TimeNow; - - if ( (pPH->packet_type == PACKET_TYPE_RUBY_PAIRING_CONFIRMATION) || - (pPH->packet_type == PACKET_TYPE_RUBY_PING_CLOCK_REPLY) || - (pPH->packet_type == PACKET_TYPE_VIDEO_SWITCH_TO_ADAPTIVE_VIDEO_LEVEL_ACK) ) + g_SM_RadioStats.uLastTimeReceivedAckFromAVehicle = g_TimeNow; + } + if ( (uPacketType == PACKET_TYPE_RUBY_PAIRING_CONFIRMATION) || + (uPacketType == PACKET_TYPE_RUBY_PING_CLOCK_REPLY) || + (uPacketType == PACKET_TYPE_VIDEO_SWITCH_TO_ADAPTIVE_VIDEO_LEVEL_ACK) ) + { g_State.vehiclesRuntimeInfo[iRuntimeIndex].uLastTimeReceivedAckFromVehicle = g_TimeNow; - - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) - if ( pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED ) + g_SM_RadioStats.uLastTimeReceivedAckFromAVehicle = g_TimeNow; + } + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) + if ( uPacketFlags & PACKET_FLAGS_BIT_RETRANSMITED ) + { g_State.vehiclesRuntimeInfo[iRuntimeIndex].uLastTimeReceivedAckFromVehicle = g_TimeNow; + g_SM_RadioStats.uLastTimeReceivedAckFromAVehicle = g_TimeNow; + } } // Detect vehicle restart (stream packets indexes are starting again from zero or low value ) - if ( radio_dup_detection_is_vehicle_restarted(uVehicleId) ) + if ( radio_dup_detection_is_vehicle_restarted(uVehicleIdSrc) ) { log_line("Vehicle restarted (received stream packet index %u for stream %d, on interface index %d; Max received stream packet index was at %u for stream %d", - (pPH->stream_packet_idx & PACKET_FLAGS_MASK_STREAM_PACKET_IDX), uStreamId, iInterfaceIndex+1, radio_dup_detection_get_max_received_packet_index_for_stream(uVehicleId, uStreamId), uStreamId ); + (uStreamPacketIndex & PACKET_FLAGS_MASK_STREAM_PACKET_IDX), uStreamId, iInterfaceIndex+1, radio_dup_detection_get_max_received_packet_index_for_stream(uVehicleIdSrc, uStreamId), uStreamId ); g_pProcessStats->alarmFlags = PROCESS_ALARM_RADIO_STREAM_RESTARTED; g_pProcessStats->alarmTime = g_TimeNow; @@ -730,21 +768,21 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa { if ( NULL == g_pVideoProcessorRxList[i] ) break; - if ( g_pVideoProcessorRxList[i]->m_uVehicleId == uVehicleId ) + if ( g_pVideoProcessorRxList[i]->m_uVehicleId == uVehicleIdSrc ) { g_pVideoProcessorRxList[i]->resetState(); break; } } - radio_dup_detection_reset_vehicle_restarted_flag(uVehicleId); + radio_dup_detection_reset_vehicle_restarted_flag(uVehicleIdSrc); } // For data streams, discard packets that are too older than the newest packet received on that stream for that vehicle - u32 uMaxStreamPacketIndex = radio_dup_detection_get_max_received_packet_index_for_stream(uVehicleId, uStreamId); + u32 uMaxStreamPacketIndex = radio_dup_detection_get_max_received_packet_index_for_stream(uVehicleIdSrc, uStreamId); - if ( (uStreamId < STREAM_ID_VIDEO_1) && (uMaxStreamPacketIndex > 50) ) - if ( (pPH->stream_packet_idx & PACKET_FLAGS_MASK_STREAM_PACKET_IDX) < uMaxStreamPacketIndex-50 ) + if ( (uStreamId < STREAM_ID_VIDEO_1) && (uMaxStreamPacketIndex > 100) ) + if ( (uStreamPacketIndex & PACKET_FLAGS_MASK_STREAM_PACKET_IDX) < uMaxStreamPacketIndex-100 ) { if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_COMMANDS ) { @@ -765,13 +803,13 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa // Received packet from different vehicle ? - if ( (NULL != g_pCurrentModel) && (pPH->vehicle_id_src != g_pCurrentModel->uVehicleId) ) + if ( (NULL != g_pCurrentModel) && (uVehicleIdSrc != g_pCurrentModel->uVehicleId) ) { // Relayed packet? if ( !g_bSearching ) if ( g_pCurrentModel->relay_params.isRelayEnabledOnRadioLinkId >= 0 ) if ( (g_pCurrentModel->relay_params.uRelayedVehicleId != 0) && (g_pCurrentModel->relay_params.uRelayedVehicleId != MAX_U32) ) - if ( pPH->vehicle_id_src == g_pCurrentModel->relay_params.uRelayedVehicleId ) + if ( uVehicleIdSrc == g_pCurrentModel->relay_params.uRelayedVehicleId ) bIsRelayedPacket = true; /* @@ -794,10 +832,10 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa if ( !bIsRelayedPacket ) { // Ruby telemetry is always sent to central, so that wrong vehicle or relayed vehicles can be detected - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_TELEMETRY ) - if ( pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_EXTENDED || - pPH->packet_type == PACKET_TYPE_FC_TELEMETRY || - pPH->packet_type == PACKET_TYPE_FC_TELEMETRY_EXTENDED ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_TELEMETRY ) + if ( (uPacketType == PACKET_TYPE_RUBY_TELEMETRY_EXTENDED) || + (uPacketType == PACKET_TYPE_FC_TELEMETRY) || + (uPacketType == PACKET_TYPE_FC_TELEMETRY_EXTENDED) ) { if ( -1 != g_fIPCToCentral ) ruby_ipc_channel_send_message(g_fIPCToCentral, pData, iDataLength); @@ -807,7 +845,7 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa #ifdef PROFILE_RX u32 dTime1 = get_current_timestamp_ms() - timeStart; if ( dTime1 >= PROFILE_RX_MAX_TIME ) - log_softerror_and_alarm("[Profile-Rx] Processing single radio packet (type: %d len: %d bytes) from different vehicle, from radio interface %d took too long: %d ms.", pPH->packet_type, pPH->total_length, iInterfaceIndex+1, (int)dTime1); + log_softerror_and_alarm("[Profile-Rx] Processing single radio packet (type: %d len: %d bytes) from different vehicle, from radio interface %d took too long: %d ms.", uPacketType, iPacketLength, iInterfaceIndex+1, (int)dTime1); #endif return 0; @@ -824,18 +862,18 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa int cRC = 0; int cPing = 0; int cOther = 0; - if ( pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED ) + if ( uPacketFlags & PACKET_FLAGS_BIT_RETRANSMITED ) cRetr = 1; - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) cVideo = 1; - else if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_TELEMETRY ) + else if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_TELEMETRY ) cTelem = 1; - else if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RC ) + else if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RC ) cRC = 1; - else if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RUBY ) + else if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RUBY ) { - if ( pPH->packet_type == PACKET_TYPE_RUBY_PING_CLOCK_REPLY ) + if ( uPacketType == PACKET_TYPE_RUBY_PING_CLOCK_REPLY ) cPing = 1; else cOther = 1; @@ -846,7 +884,7 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa #ifdef PROFILE_RX u32 dTimeDbg = get_current_timestamp_ms() - timeStart; if ( dTimeDbg >= PROFILE_RX_MAX_TIME ) - log_softerror_and_alarm("[Profile-Rx] Adding debug stats for single radio packet (type: %d len: %d bytes), from radio interface %d took too long: %d ms.", pPH->packet_type, pPH->total_length, iInterfaceIndex+1, (int)dTimeDbg); + log_softerror_and_alarm("[Profile-Rx] Adding debug stats for single radio packet (type: %d len: %d bytes), from radio interface %d took too long: %d ms.", uPacketType, iPacketLength, iInterfaceIndex+1, (int)dTimeDbg); #endif } @@ -855,12 +893,12 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa //if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_COMPONENT_VIDEO ) // log_line("Received packet from vehicle: module: %d, type: %d, length: %d", (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE), pPH->packet_type, pPH->total_length); - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RUBY ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RUBY ) { if ( bIsRelayedPacket ) { - if ( (pPH->packet_type == PACKET_TYPE_RUBY_PING_CLOCK_REPLY) || - (pPH->packet_type == PACKET_TYPE_RUBY_PAIRING_CONFIRMATION) ) + if ( (uPacketType == PACKET_TYPE_RUBY_PING_CLOCK_REPLY) || + (uPacketType == PACKET_TYPE_RUBY_PAIRING_CONFIRMATION) ) _process_received_ruby_message(iInterfaceIndex, pData); return 0; } @@ -869,15 +907,17 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa #ifdef PROFILE_RX u32 dTimeEnd = get_current_timestamp_ms() - timeStart; if ( dTimeEnd >= PROFILE_RX_MAX_TIME ) - log_softerror_and_alarm("[Profile-Rx] Processing ruby message from single radio packet (type: %d len: %d bytes), from radio interface %d took too long: %d ms.", pPH->packet_type, pPH->total_length, iInterfaceIndex+1, (int)dTimeEnd); + log_softerror_and_alarm("[Profile-Rx] Processing ruby message from single radio packet (type: %d len: %d bytes), from radio interface %d took too long: %d ms.", uPacketType, iPacketLength, iInterfaceIndex+1, (int)dTimeEnd); #endif return 0; } - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_COMMANDS ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_COMMANDS ) { - if ( pPH->packet_type != PACKET_TYPE_COMMAND_RESPONSE ) + if ( uPacketType != PACKET_TYPE_COMMAND_RESPONSE ) + return 0; + if ( iPacketLength < (int)sizeof(t_packet_header) + (int)sizeof(t_packet_header_command_response) ) return 0; t_packet_header_command_response* pPHCR = (t_packet_header_command_response*)(pData + sizeof(t_packet_header)); @@ -898,7 +938,7 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa if ( NULL != g_pProcessStats ) g_pProcessStats->lastIPCOutgoingTime = g_TimeNow; - type_global_state_vehicle_runtime_info* pRuntimeInfo = getVehicleRuntimeInfo(pPH->vehicle_id_src); + type_global_state_vehicle_runtime_info* pRuntimeInfo = getVehicleRuntimeInfo(uVehicleIdSrc); if ( NULL != pRuntimeInfo ) if ( pRuntimeInfo->uLastCommandIdSent != MAX_U32 ) if ( pRuntimeInfo->uLastCommandIdRetrySent != MAX_U32 ) @@ -949,13 +989,13 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa #ifdef PROFILE_RX u32 dTimeEnd = get_current_timestamp_ms() - timeStart; if ( dTimeEnd >= PROFILE_RX_MAX_TIME ) - log_softerror_and_alarm("[Profile-Rx] Processing command message from single radio packet (type: %d len: %d bytes), from radio interface %d took too long: %d ms.", pPH->packet_type, pPH->total_length, iInterfaceIndex+1, (int)dTimeEnd); + log_softerror_and_alarm("[Profile-Rx] Processing command message from single radio packet (type: %d len: %d bytes), from radio interface %d took too long: %d ms.", uPacketType, iPacketLength, iInterfaceIndex+1, (int)dTimeEnd); #endif return 0; } - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_TELEMETRY ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_TELEMETRY ) { if ( ! bIsRelayedPacket ) if ( ! g_bSearching ) @@ -963,7 +1003,7 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa if ( -1 != g_fIPCToTelemetry ) { #ifdef LOG_RAW_TELEMETRY - if ( pPH->packet_type == PACKET_TYPE_TELEMETRY_RAW_DOWNLOAD ) + if ( uPacketType == PACKET_TYPE_TELEMETRY_RAW_DOWNLOAD ) { t_packet_header_telemetry_raw* pPHTR = (t_packet_header_telemetry_raw*)(pData + sizeof(t_packet_header)); log_line("[Raw_Telem] Received raw telem packet from vehicle, index %u, %d / %d bytes", @@ -977,32 +1017,32 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa // Ruby telemetry and FC telemetry from relayed vehicle is always sent to central to detect the relayed vehicle if ( bIsRelayedPacket ) - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_TELEMETRY ) - if ( (pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_EXTENDED) || - (pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_SHORT) || - (pPH->packet_type == PACKET_TYPE_FC_TELEMETRY) || - (pPH->packet_type == PACKET_TYPE_FC_TELEMETRY_EXTENDED) || - (pPH->packet_type == PACKET_TYPE_TELEMETRY_MSP)) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_TELEMETRY ) + if ( (uPacketType == PACKET_TYPE_RUBY_TELEMETRY_EXTENDED) || + (uPacketType == PACKET_TYPE_RUBY_TELEMETRY_SHORT) || + (uPacketType == PACKET_TYPE_FC_TELEMETRY) || + (uPacketType == PACKET_TYPE_FC_TELEMETRY_EXTENDED) || + (uPacketType == PACKET_TYPE_TELEMETRY_MSP)) bSendToCentral = true; if ( bIsRelayedPacket ) - if ( relay_controller_must_forward_telemetry_from(g_pCurrentModel, pPH->vehicle_id_src) ) + if ( relay_controller_must_forward_telemetry_from(g_pCurrentModel, uVehicleIdSrc) ) bSendRelayedTelemetry = true; if ( (! bIsRelayedPacket) || bSendRelayedTelemetry ) - if ( (pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_SHORT) || - (pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_EXTENDED) || - (pPH->packet_type == PACKET_TYPE_FC_TELEMETRY) || - (pPH->packet_type == PACKET_TYPE_FC_TELEMETRY_EXTENDED) || - (pPH->packet_type == PACKET_TYPE_FC_RC_CHANNELS) || - (pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_VEHICLE_TX_HISTORY ) || - (pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_VEHICLE_RX_CARDS_STATS ) || - (pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_DEV_VIDEO_BITRATE_HISTORY) || - (pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_VIDEO_INFO_STATS) || - (pPH->packet_type == PACKET_TYPE_TELEMETRY_RAW_DOWNLOAD) || - (pPH->packet_type == PACKET_TYPE_DEBUG_INFO) || - (pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_RADIO_RX_HISTORY) || - (pPH->packet_type == PACKET_TYPE_TELEMETRY_MSP)) + if ( (uPacketType == PACKET_TYPE_RUBY_TELEMETRY_SHORT) || + (uPacketType == PACKET_TYPE_RUBY_TELEMETRY_EXTENDED) || + (uPacketType == PACKET_TYPE_FC_TELEMETRY) || + (uPacketType == PACKET_TYPE_FC_TELEMETRY_EXTENDED) || + (uPacketType == PACKET_TYPE_FC_RC_CHANNELS) || + (uPacketType == PACKET_TYPE_RUBY_TELEMETRY_VEHICLE_TX_HISTORY ) || + (uPacketType == PACKET_TYPE_RUBY_TELEMETRY_VEHICLE_RX_CARDS_STATS ) || + (uPacketType == PACKET_TYPE_RUBY_TELEMETRY_DEV_VIDEO_BITRATE_HISTORY) || + (uPacketType == PACKET_TYPE_RUBY_TELEMETRY_VIDEO_INFO_STATS) || + (uPacketType == PACKET_TYPE_TELEMETRY_RAW_DOWNLOAD) || + (uPacketType == PACKET_TYPE_DEBUG_INFO) || + (uPacketType == PACKET_TYPE_RUBY_TELEMETRY_RADIO_RX_HISTORY) || + (uPacketType == PACKET_TYPE_TELEMETRY_MSP)) bSendToCentral = true; if ( bSendToCentral ) @@ -1015,7 +1055,7 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa #ifdef PROFILE_RX u32 dTimeEnd = get_current_timestamp_ms() - timeStart; if ( dTimeEnd >= PROFILE_RX_MAX_TIME ) - log_softerror_and_alarm("[Profile-Rx] Processing telemetry message from single radio packet (type: %d len: %d bytes), from radio interface %d took too long: %d ms.", pPH->packet_type, pPH->total_length, iInterfaceIndex+1, (int)dTimeEnd); + log_softerror_and_alarm("[Profile-Rx] Processing telemetry message from single radio packet (type: %d len: %d bytes), from radio interface %d took too long: %d ms.", uPacketType, iPacketLength, iInterfaceIndex+1, (int)dTimeEnd); #endif return 0; } @@ -1029,9 +1069,9 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa //if ( pPH->total_length == sizeof(t_packet_header) + sizeof(shared_mem_video_link_stats_and_overwrites) ) // memcpy(g_pSM_VideoLinkStats, pData+sizeof(t_packet_header), sizeof(shared_mem_video_link_stats_and_overwrites) ); - if ( pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_VIDEO_LINK_DEV_GRAPHS ) + if ( uPacketType == PACKET_TYPE_RUBY_TELEMETRY_VIDEO_LINK_DEV_GRAPHS ) if ( NULL != g_pSM_VideoLinkGraphs ) - if ( pPH->total_length == sizeof(t_packet_header) + sizeof(shared_mem_video_link_graphs) ) + if ( iPacketLength == sizeof(t_packet_header) + sizeof(shared_mem_video_link_graphs) ) memcpy(g_pSM_VideoLinkGraphs, pData+sizeof(t_packet_header), sizeof(shared_mem_video_link_graphs) ); if ( NULL != g_pProcessStats ) @@ -1040,13 +1080,13 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa #ifdef PROFILE_RX u32 dTimeEnd = get_current_timestamp_ms() - timeStart; if ( dTimeEnd >= PROFILE_RX_MAX_TIME ) - log_softerror_and_alarm("[Profile-Rx] Processing telemetry message from single radio packet (type: %d len: %d bytes), from radio interface %d took too long: %d ms.", pPH->packet_type, pPH->total_length, iInterfaceIndex+1, (int)dTimeEnd); + log_softerror_and_alarm("[Profile-Rx] Processing telemetry message from single radio packet (type: %d len: %d bytes), from radio interface %d took too long: %d ms.", uPacketType, iPacketLength, iInterfaceIndex+1, (int)dTimeEnd); #endif return 0; } - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RC ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RC ) { if ( bIsRelayedPacket ) return 0; @@ -1059,29 +1099,29 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa #ifdef PROFILE_RX u32 dTimeEnd = get_current_timestamp_ms() - timeStart; if ( dTimeEnd >= PROFILE_RX_MAX_TIME ) - log_softerror_and_alarm("[Profile-Rx] Processing RC message from single radio packet (type: %d len: %d bytes), from radio interface %d took too long: %d ms.", pPH->packet_type, pPH->total_length, iInterfaceIndex+1, (int)dTimeEnd); + log_softerror_and_alarm("[Profile-Rx] Processing RC message from single radio packet (type: %d len: %d bytes), from radio interface %d took too long: %d ms.", uPacketType, iPacketLength, iInterfaceIndex+1, (int)dTimeEnd); #endif return 0; } - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) { int nRet = process_received_video_packet(iInterfaceIndex, pData, iDataLength); #ifdef PROFILE_RX u32 dTimeEnd = get_current_timestamp_ms() - timeStart; if ( dTimeEnd >= PROFILE_RX_MAX_TIME ) - log_softerror_and_alarm("[Profile-Rx] Processing video message from single radio packet (type: %d len: %d/%d bytes), from radio interface %d took too long: %d ms.", pPH->packet_type, pPH->total_length, iDataLength, iInterfaceIndex+1, (int)dTimeEnd); + log_softerror_and_alarm("[Profile-Rx] Processing video message from single radio packet (type: %d len: %d/%d bytes), from radio interface %d took too long: %d ms.", uPacketType, iPacketLength, iDataLength, iInterfaceIndex+1, (int)dTimeEnd); #endif return nRet; } - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_AUDIO ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_AUDIO ) { if ( bIsRelayedPacket || g_bSearching ) return 0; - if ( pPH->packet_type != PACKET_TYPE_AUDIO_SEGMENT ) + if ( uPacketType != PACKET_TYPE_AUDIO_SEGMENT ) { //log_line("Received unknown video packet type."); return 0; @@ -1091,7 +1131,7 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa #ifdef PROFILE_RX u32 dTimeEnd = get_current_timestamp_ms() - timeStart; if ( dTimeEnd >= PROFILE_RX_MAX_TIME ) - log_softerror_and_alarm("[Profile-Rx] Processing audio message from single radio packet (type: %d len: %d/%d bytes), from radio interface %d took too long: %d ms.", pPH->packet_type, pPH->total_length, iDataLength, iInterfaceIndex+1, (int)dTimeEnd); + log_softerror_and_alarm("[Profile-Rx] Processing audio message from single radio packet (type: %d len: %d/%d bytes), from radio interface %d took too long: %d ms.", uPacketType, iPacketLength, iDataLength, iInterfaceIndex+1, (int)dTimeEnd); #endif return 0; @@ -1100,7 +1140,7 @@ int process_received_single_radio_packet(int iInterfaceIndex, u8* pData, int iDa #ifdef PROFILE_RX u32 dTimeEnd = get_current_timestamp_ms() - timeStart; if ( dTimeEnd >= PROFILE_RX_MAX_TIME ) - log_softerror_and_alarm("[Profile-Rx] Processing other type of message from single radio packet (type: %d len: %d/%d bytes), from radio interface %d took too long: %d ms.", pPH->packet_type, pPH->total_length, iDataLength, iInterfaceIndex+1, (int)dTimeEnd); + log_softerror_and_alarm("[Profile-Rx] Processing other type of message from single radio packet (type: %d len: %d/%d bytes), from radio interface %d took too long: %d ms.", uPacketType, iPacketLength, iDataLength, iInterfaceIndex+1, (int)dTimeEnd); #endif return 0; diff --git a/code/r_station/process_video_packets.cpp b/code/r_station/process_video_packets.cpp index f0527aa4..bdbcc3b0 100644 --- a/code/r_station/process_video_packets.cpp +++ b/code/r_station/process_video_packets.cpp @@ -34,11 +34,13 @@ #include "../base/models.h" #include "../base/models_list.h" #include "../base/controller_rt_info.h" +#include "../base/parser_h264.h" #include "../common/relay_utils.h" #include "adaptive_video.h" #include "shared_vars.h" #include "timers.h" +extern ParserH264 s_ParserH264RadioInput; ProcessorRxVideo* _find_create_rx_video_processor(u32 uVehicleId, u32 uVideoStreamIndex) { @@ -73,6 +75,59 @@ ProcessorRxVideo* _find_create_rx_video_processor(u32 uVehicleId, u32 uVideoStre return g_pVideoProcessorRxList[iFirstFreeSlot]; } + +void _parse_single_packet_h264_data(u8* pPacketData, bool bIsRelayed) +{ + if ( NULL == pPacketData ) + return; +/* + t_packet_header* pPH = (t_packet_header*)pPacketData; + t_packet_header_video_full_98* pPHVF = (t_packet_header_video_full_98*) (pPacketData+sizeof(t_packet_header)); + int iVideoDataLength = pPHVF->uCurrentBlockPacketSize; + u8* pData = pPacketData + sizeof(t_packet_header) + sizeof(t_packet_header_video_full_98); + + bool bStartOfFrameDetected = s_ParserH264RadioInput.parseData(pData, iVideoDataLength, g_TimeNow); + if ( ! bStartOfFrameDetected ) + return; + + //log_line("DEBUG last frame size: %d bytes", s_ParserH264RadioInput.getSizeOfLastCompleteFrameInBytes()); + //log_line("DEBUG detected start of %sframe", s_ParserH264RadioInput.IsInsideIFrame()?"I":"P"); + if ( g_iDebugShowKeyFramesAfterRelaySwitch > 0 ) + if ( s_ParserH264RadioInput.IsInsideIFrame() ) + { + log_line("[Debug] Received video keyframe from VID %u after relay switch.", pPH->vehicle_id_src); + g_iDebugShowKeyFramesAfterRelaySwitch--; + } + + u32 uLastFrameDuration = s_ParserH264RadioInput.getTimeDurationOfLastCompleteFrame(); + if ( uLastFrameDuration > 127 ) + uLastFrameDuration = 127; + if ( uLastFrameDuration < 1 ) + uLastFrameDuration = 1; + + u32 uLastFrameSize = s_ParserH264RadioInput.getSizeOfLastCompleteFrameInBytes(); + uLastFrameSize /= 1000; // transform to kbytes + + if ( uLastFrameSize > 127 ) + uLastFrameSize = 127; // kbytes + + g_SM_VideoInfoStatsRadioIn.uLastFrameIndex = (g_SM_VideoInfoStatsRadioIn.uLastFrameIndex+1) % MAX_FRAMES_SAMPLES; + g_SM_VideoInfoStatsRadioIn.uFramesDuration[g_SM_VideoInfoStatsRadioIn.uLastFrameIndex] = uLastFrameDuration; + g_SM_VideoInfoStatsRadioIn.uFramesTypesAndSizes[g_SM_VideoInfoStatsRadioIn.uLastFrameIndex] = (g_SM_VideoInfoStatsRadioIn.uFramesTypesAndSizes[g_SM_VideoInfoStatsRadioIn.uLastFrameIndex] & 0x80) | ((u8)uLastFrameSize); + + u32 uNextIndex = (g_SM_VideoInfoStatsRadioIn.uLastFrameIndex+1) % MAX_FRAMES_SAMPLES; + + if ( s_ParserH264RadioInput.IsInsideIFrame() ) + g_SM_VideoInfoStatsRadioIn.uFramesTypesAndSizes[uNextIndex] |= (1<<7); + else + g_SM_VideoInfoStatsRadioIn.uFramesTypesAndSizes[uNextIndex] &= 0x7F; + + g_SM_VideoInfoStatsRadioIn.uDetectedKeyframeIntervalMs = s_ParserH264RadioInput.getCurrentlyDetectedKeyframeIntervalMs(); + g_SM_VideoInfoStatsRadioIn.uDetectedFPS = s_ParserH264RadioInput.getDetectedFPS(); + g_SM_VideoInfoStatsRadioIn.uDetectedSlices = (u32) s_ParserH264RadioInput.getDetectedSlices(); +*/ +} + // Returns 1 if end of a video block was reached // Returns -1 if the packet is not for this vehicle or was not processed int _process_received_video_data_packet(int iInterfaceIndex, u8* pPacket, int iPacketLength) @@ -109,9 +164,10 @@ int _process_received_video_data_packet(int iInterfaceIndex, u8* pPacket, int iP s_uTmpDebugLastPacket = pPHVF->uCurrentBlockPacketIndex; */ - - //bool bIsRelayedPacket = relay_controller_is_vehicle_id_relayed_vehicle(g_pCurrentModel, uVehicleId); + // log_line("DEBUG check relay %u", uVehicleId); + bool bIsRelayedPacket = relay_controller_is_vehicle_id_relayed_vehicle(g_pCurrentModel, uVehicleId); u32 uVideoStreamIndex = 0; + //log_line("DEBUG find proc %u, %u", uVehicleId, uVideoStreamIndex); ProcessorRxVideo* pProcessorVideo = _find_create_rx_video_processor(uVehicleId, uVideoStreamIndex); if ( NULL == pProcessorVideo ) @@ -119,6 +175,16 @@ int _process_received_video_data_packet(int iInterfaceIndex, u8* pPacket, int iP pProcessorVideo->handleReceivedVideoPacket(iInterfaceIndex, pPacket, iPacketLength); + /* + t_packet_header_video_full_98 * pPHVF = (t_packet_header_video_full_98*) (pPacket+sizeof(t_packet_header)); + if ( ! ( pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED) ) + if ( pPHVF->uCurrentBlockPacketIndex < pPHVF->uCurrentBlockDataPackets ) + if ( (pPHVF->uVideoStreamIndexAndType >> 4) == VIDEO_TYPE_H264 ) + if ( pModel->osd_params.osd_flags[pModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_H264_FRAMES_INFO ) + //if ( get_ControllerSettings()->iShowVideoStreamInfoCompactType == 0 ) + _parse_single_packet_h264_data(pPacket, bIsRelayedPacket); + */ + // Did we received a new video stream? Add info for it. // To fix /* @@ -131,7 +197,7 @@ int _process_received_video_data_packet(int iInterfaceIndex, u8* pPacket, int iP if ( ! ( pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED) ) if ( pPHVF->video_block_packet_index < pPHVF->block_packets ) if ( uVideoStreamType == VIDEO_TYPE_H264 ) - if ( pModel->osd_params.osd_flags[pModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_KEYFRAMES_INFO ) + if ( pModel->osd_params.osd_flags[pModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_H264_FRAMES_INFO ) if ( get_ControllerSettings()->iShowVideoStreamInfoCompactType == 0 ) _parse_single_packet_h264_data(pPacket, bIsRelayedPacket); @@ -179,11 +245,11 @@ int process_received_video_packet(int iInterfaceIndex, u8* pPacket, int iPacketL if ( pPH->packet_type == PACKET_TYPE_VIDEO_DATA_98 ) { - if ( pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED ) - { - //t_packet_header_video_full_98* pPHVF = (t_packet_header_video_full_98*) (pPacket+sizeof(t_packet_header)); - //log_line("DEBUG recv retr video [%u/%u]", pPHVF->uCurrentBlockIndex, pPHVF->uCurrentBlockPacketIndex); - } + //if ( pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED ) + //{ + // t_packet_header_video_full_98* pPHVF = (t_packet_header_video_full_98*) (pPacket+sizeof(t_packet_header)); + // log_line("DEBUG recv retr video [%u/%u]", pPHVF->uCurrentBlockIndex, pPHVF->uCurrentBlockPacketIndex); + //} nRet = _process_received_video_data_packet(iInterfaceIndex, pPacket, iPacketLength); } diff --git a/code/r_station/processor_rx_video.cpp b/code/r_station/processor_rx_video.cpp index 3d6aefbe..2c1681ca 100644 --- a/code/r_station/processor_rx_video.cpp +++ b/code/r_station/processor_rx_video.cpp @@ -221,14 +221,7 @@ bool ProcessorRxVideo::init() m_uRetryRetransmissionAfterTimeoutMiliseconds = g_pControllerSettings->nRetryRetransmissionAfterTimeoutMS; log_line("[ProcessorRxVideo] Using timers: Retransmission retry after timeout of %d ms; Request retransmission after video silence (no video packets) timeout of %d ms", m_uRetryRetransmissionAfterTimeoutMiliseconds, g_pControllerSettings->nRequestRetransmissionsOnVideoSilenceMs); - - memset((u8*)&m_SM_VideoDecodeStatsHistory, 0, sizeof(shared_mem_video_stream_stats_history)); - m_SM_VideoDecodeStatsHistory.uVehicleId = m_uVehicleId; - m_SM_VideoDecodeStatsHistory.uVideoStreamIndex = m_uVideoStreamIndex; - m_SM_VideoDecodeStatsHistory.outputHistoryIntervalMs = g_pControllerSettings->nGraphVideoRefreshInterval; - log_line("[ProcessorRxVideo] Using graphs slice interval of %d miliseconds.", m_SM_VideoDecodeStatsHistory.outputHistoryIntervalMs); - - + resetReceiveState(); resetOutputState(); @@ -265,7 +258,7 @@ void ProcessorRxVideo::resetReceiveState() m_uLastBlockReceivedEncodingExtraFlags2 = MAX_U32; m_uRetryRetransmissionAfterTimeoutMiliseconds = g_pControllerSettings->nRetryRetransmissionAfterTimeoutMS; - m_uTimeIntervalMsForRequestingRetransmissions = 10; + m_uTimeIntervalMsForRequestingRetransmissions = 15; log_line("[ProcessorRxVideo] Using timers: Retransmission retry after timeout of %d ms; Request retransmission after video silence (no video packets) timeout of %d ms", m_uRetryRetransmissionAfterTimeoutMiliseconds, g_pControllerSettings->nRequestRetransmissionsOnVideoSilenceMs); @@ -318,24 +311,6 @@ void ProcessorRxVideo::resetReceiveState() m_SM_VideoDecodeStats.maxPacketsInBuffers = 10; m_SM_VideoDecodeStats.total_DiscardedSegments = 0; - - m_SM_VideoDecodeStatsHistory.totalCurrentlyMissingPackets = 0; - for( int i=0; inGraphVideoRefreshInterval; - log_line("[ProcessorRxVideo] Using graphs slice interval of %d miliseconds.", m_SM_VideoDecodeStatsHistory.outputHistoryIntervalMs); - m_uRetryRetransmissionAfterTimeoutMiliseconds = g_pControllerSettings->nRetryRetransmissionAfterTimeoutMS; log_line("[ProcessorRxVideo]: Using timers: Retransmission retry after timeout of %d ms; Request retransmission after video silence (no video packets) timeout of %d ms", m_uRetryRetransmissionAfterTimeoutMiliseconds, g_pControllerSettings->nRequestRetransmissionsOnVideoSilenceMs); @@ -432,47 +408,25 @@ void ProcessorRxVideo::resumeProcessing() -void ProcessorRxVideo::checkAndDiscardBlocksTooOld() +bool ProcessorRxVideo::checkAndDiscardBlocksTooOld() { - /* - if ( m_iRXBlocksStackTopIndex <= 0 ) - return; - - if ( m_pRXBlocksStack[0]->uTimeLastUpdated + m_iMilisecondsMaxRetransmissionWindow + 10 >= g_TimeNow ) - return; + if ( !m_pVideoRxBuffer->hasIncompleteBlocks() ) + return false; - if ( m_iMilisecondsMaxRetransmissionWindow > 20 ) - if ( m_pRXBlocksStack[m_iRXBlocksStackTopIndex]->uTimeLastUpdated + m_iMilisecondsMaxRetransmissionWindow + 10 < g_TimeNow ) + // Discard blocks that are too old, past retransmission window + int iCountBlocks = m_pVideoRxBuffer->getBlocksCountInBuffer(); + type_rx_video_block_info* pVideoBlockFirst = m_pVideoRxBuffer->getFirstVideoBlockInBuffer(); + type_rx_video_block_info* pVideoBlockLast = m_pVideoRxBuffer->getVideoBlockInBuffer(iCountBlocks-1); + if ( (NULL != pVideoBlockFirst) && (NULL != pVideoBlockLast) ) + if ( (int)pVideoBlockLast->uReceivedTime - (int)pVideoBlockFirst->uReceivedTime > m_iMilisecondsMaxRetransmissionWindow ) { - log_line("[VideoRx] Discard old blocks (%d blocks in the stack).", m_iRXBlocksStackTopIndex); - //logCurrentRxBuffers(false); - - resetReceiveBuffers(m_iRXBlocksStackTopIndex); + m_pVideoRxBuffer->emptyBuffers("No new video past retransmission window"); + //resetReceiveBuffers(m_iRXBlocksStackTopIndex); resetOutputState(); - return; - } - - - // Find first block that is too old (from top to bottom) - - int iStackIndex = m_iRXBlocksStackTopIndex; - while ( iStackIndex >= 0 ) - { - if ( m_pRXBlocksStack[iStackIndex]->uTimeFirstPacketReceived != MAX_U32 ) - if ( m_pRXBlocksStack[iStackIndex]->uTimeFirstPacketReceived + (u32)m_iMilisecondsMaxRetransmissionWindow < g_TimeNow ) - { - break; - } - iStackIndex--; - } - - // Discard blocks, from 0 to (index, inclusive) (to first that is not too old) (they are not past the retransmission window) - // Block at iStackIndex is the first that is too old - if ( iStackIndex >= 0 ) - { - pushIncompleteBlocksOut(iStackIndex+1, true); + m_uTimeLastReceivedNewVideoPacket = 0; + return true; } - */ + return false; } void ProcessorRxVideo::sendPacketToOutput(int rx_buffer_block_index, int block_packet_index) @@ -536,8 +490,6 @@ void ProcessorRxVideo::pushIncompleteBlocksOut(int iStackIndexToDiscardTo, bool // _rx_video_log_line("Discarding full Rx stack [0-%d] (too old, newest data in discarded segment was at %02d:%02d.%03d)", s_RXBlocksStackTopIndex, s_pRXBlocksStack[countToPush-1]->uTimeLastUpdated/1000/60, (s_pRXBlocksStack[countToPush-1]->uTimeLastUpdated/1000)%60, s_pRXBlocksStack[countToPush-1]->uTimeLastUpdated % 1000); //else // _rx_video_log_line("Discarding full Rx stack [0-%d] (to make room for newer blocks, discarded blocks indexes [%u-%u], latest received block index: %u", s_RXBlocksStackTopIndex, s_pRXBlocksStack[0]->video_block_index, s_pRXBlocksStack[s_RXBlocksStackTopIndex]->video_block_index, s_LastReceivedVideoPacketInfo.video_block_index); - - m_SM_VideoDecodeStatsHistory.outputHistoryMaxGoodBlocksPendingPerPeriod[0] = 0; } else { @@ -819,19 +771,14 @@ int ProcessorRxVideo::getVideoType() return iVideoType; } -shared_mem_video_stream_stats_history* ProcessorRxVideo::getVideoDecodeStatsHistory() -{ - return &m_SM_VideoDecodeStatsHistory; -} - -void ProcessorRxVideo::periodicLoop(u32 uTimeNow) +int ProcessorRxVideo::periodicLoop(u32 uTimeNow, bool bForceSyncNow) { type_global_state_vehicle_runtime_info* pRuntimeInfo = getVehicleRuntimeInfo(m_uVehicleId); Model* pModel = findModelWithId(m_uVehicleId, 155); if ( (NULL == pModel) || (NULL == pRuntimeInfo) ) - return; + return -1; - checkAndRequestMissingPackets(); + return checkAndRequestMissingPackets(bForceSyncNow); /* if ( 0 != m_uTimeLastReceivedNewVideoPacket ) @@ -893,6 +840,20 @@ int ProcessorRxVideo::handleReceivedVideoPacket(int interfaceNb, u8* pBuffer, in #ifdef PROFILE_RX //u32 uTimeStart = get_current_timestamp_ms(); //int iStackIndexStart = m_iRXBlocksStackTopIndex; + #endif + + #if defined(RUBY_BUILD_HW_PLATFORM_PI) + t_packet_header* pPH = (t_packet_header*)pBuffer; + t_packet_header_video_full_98* pPHVF = (t_packet_header_video_full_98*) (pBuffer+sizeof(t_packet_header)); + if (((pPHVF->uVideoStreamIndexAndType >> 4) & 0x0F) == VIDEO_TYPE_H265 ) + { + static u32 s_uTimeLastSendVideoUnsuportedAlarmToCentral = 0; + if ( g_TimeNow > s_uTimeLastSendVideoUnsuportedAlarmToCentral + 20000 ) + { + s_uTimeLastSendVideoUnsuportedAlarmToCentral = g_TimeNow; + send_alarm_to_central(ALARM_ID_UNSUPPORTED_VIDEO_TYPE, pPHVF->uVideoStreamIndexAndType, pPH->vehicle_id_src); + } + } #endif if ( NULL != m_pVideoRxBuffer ) @@ -903,9 +864,9 @@ int ProcessorRxVideo::handleReceivedVideoPacket(int interfaceNb, u8* pBuffer, in updateVideoDecodingStats(pBuffer, length); m_uLatestVideoPacketReceiveTime = g_TimeNow; } + t_packet_header* pPH = (t_packet_header*)pBuffer; t_packet_header_video_full_98* pPHVF = (t_packet_header_video_full_98*) (pBuffer+sizeof(t_packet_header)); - if ( pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED ) { controller_runtime_info_vehicle* pRTInfo = controller_rt_info_get_vehicle_info(&g_SMControllerRTInfo, pPH->vehicle_id_src); @@ -957,9 +918,10 @@ int ProcessorRxVideo::handleReceivedVideoPacket(int interfaceNb, u8* pBuffer, in rx_video_output_video_data(m_uVehicleId, (pVideoPacket->pPHVF->uVideoStreamIndexAndType >> 4) & 0x0F , iVideoWidth, iVideoHeight, pVideoSource, uVideoSize, pVideoPacket->pPH->total_length); - if ( 0 == pVideoBlock->iReconstructedECUsed ) - g_SMControllerRTInfo.uOutputedVideoPackets[g_SMControllerRTInfo.iCurrentIndex]++; - else + g_SMControllerRTInfo.uOutputedVideoPackets[g_SMControllerRTInfo.iCurrentIndex]++; + if ( pVideoPacket->pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED ) + g_SMControllerRTInfo.uOutputedVideoPacketsRetransmitted[g_SMControllerRTInfo.iCurrentIndex]++; + if ( pVideoBlock->iReconstructedECUsed > 0 ) { if ( pVideoBlock->iReconstructedECUsed > g_SMControllerRTInfo.uOutputedVideoPacketsMaxECUsed[g_SMControllerRTInfo.iCurrentIndex] ) g_SMControllerRTInfo.uOutputedVideoPacketsMaxECUsed[g_SMControllerRTInfo.iCurrentIndex] = pVideoBlock->iReconstructedECUsed; @@ -997,7 +959,10 @@ int ProcessorRxVideo::handleReceivedVideoPacket(int interfaceNb, u8* pBuffer, in if ( bSkipIncompleteBlocks ) m_pVideoRxBuffer->advanceStartPositionToVideoBlock(m_pVideoRxBuffer->getMaxReceivedVideoBlockIndex()); else - checkAndRequestMissingPackets(); + { + //checkAndRequestMissingPackets(false); + checkAndDiscardBlocksTooOld(); + } } } @@ -1170,49 +1135,33 @@ void ProcessorRxVideo::reconstructBlock(int rx_buffer_block_index) } -void ProcessorRxVideo::checkAndRequestMissingPackets() +int ProcessorRxVideo::checkAndRequestMissingPackets(bool bForceSyncNow) { type_global_state_vehicle_runtime_info* pRuntimeInfo = getVehicleRuntimeInfo(m_uVehicleId); Model* pModel = findModelWithId(m_uVehicleId, 179); if ( (NULL == pModel) || (NULL == pRuntimeInfo) ) - return; + return -1; int iVideoProfileNow = g_SM_VideoDecodeStats.video_streams[m_iIndexVideoDecodeStats].PHVF.uCurrentVideoLinkProfile; m_iMilisecondsMaxRetransmissionWindow = ((pModel->video_link_profiles[iVideoProfileNow].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_MAX_RETRANSMISSION_WINDOW_MASK) >> 8) * 5; - - // First, discard blocks that are too old, past retransmission window - if ( m_pVideoRxBuffer->hasIncompleteBlocks() ) - { - int iCountBlocks = m_pVideoRxBuffer->getBlocksCountInBuffer(); - type_rx_video_block_info* pVideoBlockFirst = m_pVideoRxBuffer->getFirstVideoBlockInBuffer(); - type_rx_video_block_info* pVideoBlockLast = m_pVideoRxBuffer->getVideoBlockInBuffer(iCountBlocks-1); - if ( (NULL != pVideoBlockFirst) && (NULL != pVideoBlockLast) ) - if ( (int)pVideoBlockLast->uReceivedTime - (int)pVideoBlockFirst->uReceivedTime > m_iMilisecondsMaxRetransmissionWindow ) - { - m_pVideoRxBuffer->emptyBuffers("No new video past retransmission window"); - //resetReceiveBuffers(m_iRXBlocksStackTopIndex); - resetOutputState(); - m_uTimeLastReceivedNewVideoPacket = 0; - return; - } - } - else - return; + checkAndDiscardBlocksTooOld(); if ( g_bSearching || g_bUpdateInProgress || pModel->is_spectator || (! pRuntimeInfo->bIsPairingDone) ) - return; - + return -1; + if ( ! m_pVideoRxBuffer->hasIncompleteBlocks() ) + return -1; + if ( pModel->isVideoLinkFixedOneWay() || (!(pModel->video_link_profiles[pModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_RETRANSMISSIONS)) ) - return; + return -1; // Do not request from models 9.7 or older if ( get_sw_version_build(pModel) < 242 ) - return; + return -1; // If we haven't received any video yet, don't try retransmissions if ( (0 == m_uTimeLastReceivedNewVideoPacket) || (-1 == m_iIndexVideoDecodeStats) ) - return; + return -1; // If too much time since we last received a new video packet, then discard the entire rx buffer @@ -1225,7 +1174,7 @@ void ProcessorRxVideo::checkAndRequestMissingPackets() //resetReceiveBuffers(m_iRXBlocksStackTopIndex); resetOutputState(); m_uTimeLastReceivedNewVideoPacket = 0; - return; + return -1; } @@ -1234,17 +1183,17 @@ void ProcessorRxVideo::checkAndRequestMissingPackets() //if ( m_uTimeIntervalMsForRequestingRetransmissions < 20 ) // m_uTimeIntervalMsForRequestingRetransmissions++; - if ( g_TimeNow < m_uLastTimeRequestedRetransmission + m_uTimeIntervalMsForRequestingRetransmissions ) - return; + if ( (!bForceSyncNow) && (g_TimeNow < m_uLastTimeRequestedRetransmission + m_uTimeIntervalMsForRequestingRetransmissions) ) + return -1; // If link is lost, do not request retransmissions - if ( 0 != g_pControllerSettings->iDisableRetransmissionsAfterControllerLinkLostMiliseconds ) + if ( (!bForceSyncNow) && (0 != g_pControllerSettings->iDisableRetransmissionsAfterControllerLinkLostMiliseconds) ) { u32 uDelta = (u32)g_pControllerSettings->iDisableRetransmissionsAfterControllerLinkLostMiliseconds; if ( g_TimeNow > pRuntimeInfo->uLastTimeReceivedAckFromVehicle + uDelta ) - return; + return -1; } @@ -1322,7 +1271,7 @@ void ProcessorRxVideo::checkAndRequestMissingPackets() } if ( iCountPacketsRequested == 0 ) - return; + return 0; u8 uCount = iCountPacketsRequested; memcpy(packet + sizeof(t_packet_header) + sizeof(u32) + sizeof(u8), (u8*)&uCount, sizeof(u8)); @@ -1341,8 +1290,7 @@ void ProcessorRxVideo::checkAndRequestMissingPackets() pRTInfo->uCountReqRetransmissions[g_SMControllerRTInfo.iCurrentIndex]++; packets_queue_add_packet(&s_QueueRadioPacketsHighPrio, packet); - - return; + return iCountPacketsRequested; /* diff --git a/code/r_station/processor_rx_video.h b/code/r_station/processor_rx_video.h index 2acf3fae..46a42945 100644 --- a/code/r_station/processor_rx_video.h +++ b/code/r_station/processor_rx_video.h @@ -75,6 +75,7 @@ class ProcessorRxVideo virtual bool init(); virtual bool uninit(); virtual void resetState(); + virtual void discardRetransmissionsInfo(); void onControllerSettingsChanged(); void pauseProcessing(); @@ -90,10 +91,10 @@ class ProcessorRxVideo int getVideoHeight(); int getVideoFPS(); int getVideoType(); - shared_mem_video_stream_stats_history* getVideoDecodeStatsHistory(); void updateHistoryStats(u32 uTimeNow); - virtual void periodicLoop(u32 uTimeNow); + // Returns how many retransmission packets where requested, if any + virtual int periodicLoop(u32 uTimeNow, bool bForceSyncNow); virtual int handleReceivedVideoPacket(int interfaceNb, u8* pBuffer, int length); static int m_siInstancesCount; @@ -115,8 +116,10 @@ class ProcessorRxVideo void reconstructBlock(int rx_buffer_block_index); - void checkAndRequestMissingPackets(); - void checkAndDiscardBlocksTooOld(); + // Returns how many retransmission packets where requested, if any + int checkAndRequestMissingPackets(bool bForceSyncNow); + // Returns true if buffer was discarded + bool checkAndDiscardBlocksTooOld(); void sendPacketToOutput(int rx_buffer_block_index, int block_packet_index); void pushIncompleteBlocksOut(int iStackIndexToDiscardTo, bool bTooOld); void pushFirstBlockOut(); @@ -148,8 +151,6 @@ class ProcessorRxVideo // Rx state - shared_mem_video_stream_stats_history m_SM_VideoDecodeStatsHistory; - type_last_rx_packet_info m_InfoLastReceivedVideoPacket; u8 m_uLastReceivedVideoLinkProfile; u32 m_uLastHardEncodingsChangeVideoBlockIndex; diff --git a/code/r_station/radio_links.cpp b/code/r_station/radio_links.cpp index 0abee1d2..9df5c4e9 100644 --- a/code/r_station/radio_links.cpp +++ b/code/r_station/radio_links.cpp @@ -43,6 +43,7 @@ #include "../common/radio_stats.h" #include "../radio/radio_rx.h" #include "../radio/radio_tx.h" +#include "../utils/utils_controller.h" #include "packets_utils.h" #include "links_utils.h" @@ -173,7 +174,7 @@ void radio_links_reinit_radio_interfaces() log_line("================================================================="); log_line("Detected hardware radio interfaces:"); - hardware_log_radio_info(); + hardware_log_radio_info(NULL, 0); radio_links_open_rxtx_radio_interfaces(); @@ -542,9 +543,14 @@ void radio_links_open_rxtx_radio_interfaces() if ( NULL != g_pSM_RadioStats ) memcpy((u8*)g_pSM_RadioStats, (u8*)&g_SM_RadioStats, sizeof(shared_mem_radio_stats)); log_line("Finished opening RX/TX radio interfaces."); + + radio_links_set_monitor_mode(); + load_ControllerSettings(); + load_ControllerInterfacesSettings(); + apply_controller_radio_tx_powers(g_pCurrentModel, get_ControllerSettings()->iFixedTxPower, false); + log_line("OPEN RADIO INTERFACES END ==========================================================="); log_line(""); - radio_links_set_monitor_mode(); } diff --git a/code/r_station/radio_links_sik.cpp b/code/r_station/radio_links_sik.cpp index fb8ef673..728d6d86 100644 --- a/code/r_station/radio_links_sik.cpp +++ b/code/r_station/radio_links_sik.cpp @@ -144,9 +144,14 @@ static void * _reinit_sik_thread_func(void *ignored_argument) else { ControllerSettings* pCS = get_ControllerSettings(); + ControllerInterfacesSettings* pCIS = get_ControllerInterfacesSettings(); + t_ControllerRadioInterfaceInfo* pCRII = controllerGetRadioCardInfo(pRadioHWInfo->szMAC); + u32 uFreqKhz = pRadioHWInfo->uHardwareParamsList[8]; u32 uDataRate = DEFAULT_RADIO_DATARATE_SIK_AIR; - u32 uTxPower = pCS->iTXPowerSiK; + u32 uTxPower = DEFAULT_RADIO_SIK_TX_POWER; + if ( NULL != pCRII ) + uTxPower = pCRII->iRawPowerLevel; u32 uLBT = 0; u32 uECC = 0; u32 uMCSTR = 0; diff --git a/code/r_station/ruby_rt_station.cpp b/code/r_station/ruby_rt_station.cpp index 1bfb0817..99069e4d 100644 --- a/code/r_station/ruby_rt_station.cpp +++ b/code/r_station/ruby_rt_station.cpp @@ -55,7 +55,7 @@ #include "../radio/radio_rx.h" #include "../radio/radio_tx.h" #include "../radio/radio_duplicate_det.h" -#include "../base/controller_utils.h" +#include "../utils/utils_controller.h" #include "../base/controller_rt_info.h" #include "../base/vehicle_rt_info.h" #include "../base/core_plugins_settings.h" @@ -104,6 +104,8 @@ int s_iSearchSikLBT = -1; int s_iSearchSikMCSTR = -1; u32 s_uTimeLastTryReadIPCMessages = 0; +static bool s_bBoolRecvVideoDataThisLoop = false; +static u32 s_uLastTimeRecvVideoDataPacket = 0; void _broadcast_radio_interface_init_failed(int iInterfaceIndex) { @@ -558,7 +560,7 @@ bool links_set_cards_frequencies_for_search( u32 uSearchFreq, bool bSiKSearch, i else log_line("No SiK mode update. Just change all interfaces frequencies"); - ControllerSettings* pCS = get_ControllerSettings(); + ControllerInterfacesSettings* pCIS = get_ControllerInterfacesSettings(); Preferences* pP = get_Preferences(); for( int i=0; iszMAC); u32 uFreqKhz = uSearchFreq; u32 uDataRate = iAirDataRate; - u32 uTxPower = pCS->iTXPowerSiK; + u32 uTxPower = DEFAULT_RADIO_SIK_TX_POWER; + if ( NULL != pCRII ) + uTxPower = pCRII->iRawPowerLevel; u32 uECC = iECC; u32 uLBT = iLBT; u32 uMCSTR = iMCSTR; @@ -682,6 +687,7 @@ bool links_set_cards_frequencies_and_params(int iVehicleLinkId) log_line("Links: Setting cards frequencies and params only for vehicle radio link %d", iVehicleLinkId+1); ControllerSettings* pCS = get_ControllerSettings(); + ControllerInterfacesSettings* pCIS = get_ControllerInterfacesSettings(); Preferences* pP = get_Preferences(); for( int i=0; iradioLinksParams.link_frequency_khz[nAssignedVehicleRadioLinkId]; u32 uDataRate = g_pCurrentModel->radioLinksParams.link_datarate_data_bps[nAssignedVehicleRadioLinkId]; - u32 uTxPower = pCS->iTXPowerSiK; + u32 uTxPower = DEFAULT_RADIO_SIK_TX_POWER; + t_ControllerRadioInterfaceInfo* pCRII = controllerGetRadioCardInfo(pRadioHWInfo->szMAC); + if ( NULL != pCRII ) + uTxPower = pCRII->iRawPowerLevel; u32 uECC = (g_pCurrentModel->radioLinksParams.link_radio_flags[nAssignedVehicleRadioLinkId] & RADIO_FLAGS_SIK_ECC)? 1:0; u32 uLBT = (g_pCurrentModel->radioLinksParams.link_radio_flags[nAssignedVehicleRadioLinkId] & RADIO_FLAGS_SIK_LBT)? 1:0; u32 uMCSTR = (g_pCurrentModel->radioLinksParams.link_radio_flags[nAssignedVehicleRadioLinkId] & RADIO_FLAGS_SIK_MCSTR)? 1:0; @@ -918,7 +927,8 @@ bool _check_queue_ping() { if ( (NULL == g_pCurrentModel) || g_bSearching ) return false; - if ( _must_inject_ping_now() <= 0 ) + int iPingMs = _must_inject_ping_now(); + if ( iPingMs <= 0 ) return false; static u8 s_uPingToSendId = 0xFF; @@ -1181,7 +1191,7 @@ void _read_ipc_pipes(u32 uTimeNow) while ( (maxPacketsToRead > 0) && (NULL != ruby_ipc_try_read_message(g_fIPCFromCentral, s_PipeBufferCommands, &s_PipeBufferCommandsPos, s_BufferCommands)) ) { maxPacketsToRead--; - t_packet_header* pPH = (t_packet_header*)s_BufferCommands; + t_packet_header* pPH = (t_packet_header*)s_BufferCommands; if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_LOCAL_CONTROL ) packets_queue_add_packet(&s_QueueControlPackets, s_BufferCommands); else @@ -1298,15 +1308,6 @@ void init_shared_memory_objects() log_line("Opened video decoder stats shared memory for write: success."); memset((u8*)&g_SM_VideoDecodeStats, 0, sizeof(shared_mem_video_stream_stats_rx_processors)); - - g_pSM_VideoDecodeStatsHistory = shared_mem_video_stream_stats_history_rx_processors_open(false); - if ( NULL == g_pSM_VideoDecodeStatsHistory ) - log_softerror_and_alarm("Failed to open video decoder stats history shared memory for write."); - else - log_line("Opened video decoder stats history shared memory for write: success."); - memset((u8*)&g_SM_VideoDecodeStatsHistory, 0, sizeof(shared_mem_video_stream_stats_history_rx_processors)); - - g_pSM_RadioRxQueueInfo = shared_mem_radio_rx_queue_info_open_for_write(); if ( NULL == g_pSM_RadioRxQueueInfo ) log_softerror_and_alarm("Failed to open radio rx queue info shared memory for write."); @@ -1315,20 +1316,20 @@ void init_shared_memory_objects() memset((u8*)&g_SM_RadioRxQueueInfo, 0, sizeof(shared_mem_radio_rx_queue_info)); g_SM_RadioRxQueueInfo.uMeasureIntervalMs = 100; - g_pSM_VideoInfoStatsOutput = shared_mem_video_info_stats_open_for_write(); - if ( NULL == g_pSM_VideoInfoStatsOutput ) - log_softerror_and_alarm("Failed to open shared mem video info stats output for writing: %s", SHARED_MEM_VIDEO_STREAM_INFO_STATS); + g_pSM_VideoFramesStatsOutput = shared_mem_video_frames_stats_open_for_write(); + if ( NULL == g_pSM_VideoFramesStatsOutput ) + log_softerror_and_alarm("Failed to open shared mem video info stats output for writing: %s", SHARED_MEM_VIDEO_FRAMES_STATS); else log_line("Opened shared mem video info stats stats for writing."); - g_pSM_VideoInfoStatsRadioIn = shared_mem_video_info_stats_radio_in_open_for_write(); - if ( NULL == g_pSM_VideoInfoStatsRadioIn ) - log_softerror_and_alarm("Failed to open shared mem video info radio in stats for writing: %s", SHARED_MEM_VIDEO_STREAM_INFO_STATS_RADIO_IN); - else - log_line("Opened shared mem video info radio in stats stats for writing."); + //g_pSM_VideoInfoStatsRadioIn = shared_mem_video_frames_stats_radio_in_open_for_write(); + //if ( NULL == g_pSM_VideoInfoStatsRadioIn ) + // log_softerror_and_alarm("Failed to open shared mem video info radio in stats for writing: %s", SHARED_MEM_VIDEO_FRAMES_STATS_RADIO_IN); + //else + // log_line("Opened shared mem video info radio in stats stats for writing."); - memset(&g_SM_VideoInfoStatsOutput, 0, sizeof(shared_mem_video_info_stats)); - memset(&g_SM_VideoInfoStatsRadioIn, 0, sizeof(shared_mem_video_info_stats)); + memset(&g_SM_VideoFramesStatsOutput, 0, sizeof(shared_mem_video_frames_stats)); + //memset(&g_SM_VideoInfoStatsRadioIn, 0, sizeof(shared_mem_video_frames_stats)); g_pSM_RouterVehiclesRuntimeInfo = shared_mem_router_vehicles_runtime_info_open_for_write(); if ( NULL == g_pSM_RouterVehiclesRuntimeInfo ) @@ -1587,6 +1588,7 @@ void _router_periodic_loop() continue; if ( g_SM_RadioStats.radio_interfaces[i].assignedLocalRadioLinkId >= 0 ) + if ( g_SM_RadioStats.radio_interfaces[i].timeLastRxPacket != 0 ) if ( g_SM_RadioStats.radio_interfaces[i].timeLastRxPacket < g_TimeNow-2000 ) if ( g_TimeNow > 2000 ) { @@ -1595,7 +1597,7 @@ void _router_periodic_loop() } if ( bInterfcesWithNoData ) if ( g_TimeNow > radio_linkgs_get_last_set_monitor_time() + 2000 ) - if ( g_TimeNow - g_TimeStart > 2000 ) + if ( g_TimeNow > g_TimeStart + 2000 ) if ( ! g_bUpdateInProgress ) if ( ! test_link_is_in_progress() ) radio_links_set_monitor_mode(); @@ -1714,14 +1716,7 @@ void _router_periodic_loop() if ( g_TimeNow >= s_uTimeLastVideoStatsUpdate + 50 ) { s_uTimeLastVideoStatsUpdate = g_TimeNow; - for( int i=0; igetVideoDecodeStatsHistory(), sizeof(shared_mem_video_stream_stats_history)); - } memcpy(g_pSM_VideoDecodeStats, &g_SM_VideoDecodeStats, sizeof(shared_mem_video_stream_stats_rx_processors)); - memcpy(g_pSM_VideoDecodeStatsHistory, &g_SM_VideoDecodeStatsHistory, sizeof(shared_mem_video_stream_stats_history_rx_processors)); } if ( g_TimeNow >= g_SM_RadioRxQueueInfo.uLastMeasureTime + g_SM_RadioRxQueueInfo.uMeasureIntervalMs ) @@ -1780,17 +1775,17 @@ void _synchronize_shared_mems() } //--------------------------------------------- - if ( NULL != g_pCurrentModel ) - if ( g_pCurrentModel->osd_params.osd_flags[g_pCurrentModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_KEYFRAMES_INFO) - if ( g_TimeNow >= g_SM_VideoInfoStatsOutput.uTimeLastUpdate + 200 ) + if ( (NULL != g_pCurrentModel) && g_pCurrentModel->bDeveloperMode ) + if ( g_pCurrentModel->osd_params.osd_flags[g_pCurrentModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_H264_FRAMES_INFO) + if ( g_TimeNow >= g_SM_VideoFramesStatsOutput.uLastTimeStatsUpdate + 200 ) { - update_shared_mem_video_info_stats( &g_SM_VideoInfoStatsOutput, g_TimeNow); - update_shared_mem_video_info_stats( &g_SM_VideoInfoStatsRadioIn, g_TimeNow); + update_shared_mem_video_frames_stats( &g_SM_VideoFramesStatsOutput, g_TimeNow); + //update_shared_mem_video_frames_stats( &g_SM_VideoInfoStatsRadioIn, g_TimeNow); - if ( NULL != g_pSM_VideoInfoStatsOutput ) - memcpy((u8*)g_pSM_VideoInfoStatsOutput, (u8*)&g_SM_VideoInfoStatsOutput, sizeof(shared_mem_video_info_stats)); - if ( NULL != g_pSM_VideoInfoStatsRadioIn ) - memcpy((u8*)g_pSM_VideoInfoStatsRadioIn, (u8*)&g_SM_VideoInfoStatsRadioIn, sizeof(shared_mem_video_info_stats)); + if ( NULL != g_pSM_VideoFramesStatsOutput ) + memcpy((u8*)g_pSM_VideoFramesStatsOutput, (u8*)&g_SM_VideoFramesStatsOutput, sizeof(shared_mem_video_frames_stats)); + //if ( NULL != g_pSM_VideoInfoStatsRadioIn ) + // memcpy((u8*)g_pSM_VideoInfoStatsRadioIn, (u8*)&g_SM_VideoInfoStatsRadioIn, sizeof(shared_mem_video_frames_stats)); } static u32 s_uTimeLastRxHistorySync = 0; @@ -1823,10 +1818,11 @@ int _try_read_consume_high_priority_packets(int iCountMax, u32 uTimeoutMicrosec) shared_mem_radio_stats_rx_hist_update(&g_SM_HistoryRxStats, iRadioInterfaceIndex, pPacket, g_TimeNow); g_SMControllerRTInfo.uRxProcessedPackets[g_SMControllerRTInfo.iCurrentIndex]++; } + return iCountConsumedHighPrio; } -int _try_read_consume_reg_priority_packets(int iCountMax, u32 uTimeoutMicrosec) +int _try_read_consume_reg_priority_packets(int iCountMax, u32 uTimeoutMicrosec, bool* pbEndOfVideoFrameDetected, u16* puVideoFrameId) { int iCountConsumedRegPrio = 0; @@ -1835,23 +1831,49 @@ int _try_read_consume_reg_priority_packets(int iCountMax, u32 uTimeoutMicrosec) int iRadioInterfaceIndex = 0; u8* pPacket = NULL; + if ( NULL != pbEndOfVideoFrameDetected ) + *pbEndOfVideoFrameDetected = false; + if ( NULL != puVideoFrameId ) + *puVideoFrameId = 0; + while ( (iCountConsumedRegPrio < iCountMax) && (!g_bQuit) ) { pPacket = radio_rx_wait_get_next_received_reg_prio_packet(uTimeoutMicrosec, &iPacketLength, &iPacketIsShort, &iRadioInterfaceIndex); if ( (NULL == pPacket) || g_bQuit ) break; + t_packet_header* pPH = (t_packet_header*)pPacket; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) + if ( pPH->packet_type == PACKET_TYPE_VIDEO_DATA_98 ) + if ( ! (pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED) ) + { + s_bBoolRecvVideoDataThisLoop = true; + s_uLastTimeRecvVideoDataPacket = g_TimeNow; + t_packet_header_video_full_98* pPHVF = (t_packet_header_video_full_98*)(pPacket + sizeof(t_packet_header)); + + if ( pPHVF->uFrameId > *puVideoFrameId ) + { + *puVideoFrameId = pPHVF->uFrameId; + *pbEndOfVideoFrameDetected = false; + } + else if ( (pPHVF->uFrameId == *puVideoFrameId) && (pPHVF->uVideoStatusFlags2 & VIDEO_STATUS_FLAGS2_END_FRAME) ) + *pbEndOfVideoFrameDetected = true; + } + iCountConsumedRegPrio++; process_received_single_radio_packet(iRadioInterfaceIndex, pPacket, iPacketLength); shared_mem_radio_stats_rx_hist_update(&g_SM_HistoryRxStats, iRadioInterfaceIndex, pPacket, g_TimeNow); g_SMControllerRTInfo.uRxProcessedPackets[g_SMControllerRTInfo.iCurrentIndex]++; } + return iCountConsumedRegPrio; } -void _main_loop_no_sync(); +void _main_loop_searching(); +void _main_loop_simple(bool bNoTxSync); void _main_loop_basic_sync(); +void _main_loop_adv_sync(); void handle_sigint(int sig) { @@ -2119,7 +2141,11 @@ int main(int argc, char *argv[]) // ----------------------------------------------------------- // Main loop here - + + if ( g_bSearching ) + log_line("Running main loop for searching"); + else + log_line("Running main loop for sync type: %d", g_pCurrentModel->rxtx_sync_type); while ( !g_bQuit ) { g_TimeNow = get_current_timestamp_ms(); @@ -2130,11 +2156,13 @@ int main(int argc, char *argv[]) } if ( g_bSearching ) - _main_loop_no_sync(); + _main_loop_searching(); + else if ( g_pCurrentModel->rxtx_sync_type == RXTX_SYNC_TYPE_ADV ) + _main_loop_adv_sync(); else if ( g_pCurrentModel->rxtx_sync_type == RXTX_SYNC_TYPE_BASIC ) _main_loop_basic_sync(); else - _main_loop_no_sync(); + _main_loop_simple(true); if ( g_bQuit ) break; } @@ -2160,14 +2188,13 @@ int main(int argc, char *argv[]) shared_mem_controller_audio_decode_stats_close(g_pSM_AudioDecodeStats); shared_mem_process_stats_close(SHARED_MEM_WATCHDOG_ROUTER_RX, g_pProcessStats); shared_mem_video_stream_stats_rx_processors_close(g_pSM_VideoDecodeStats); - shared_mem_video_stream_stats_history_rx_processors_close(g_pSM_VideoDecodeStatsHistory); shared_mem_radio_rx_queue_info_close(g_pSM_RadioRxQueueInfo); g_pSM_RadioRxQueueInfo = NULL; // To fix shared_mem_video_link_stats_close(g_pSM_VideoLinkStats); shared_mem_video_link_graphs_close(g_pSM_VideoLinkGraphs); shared_mem_radio_stats_close(g_pSM_RadioStats); - shared_mem_video_info_stats_close(g_pSM_VideoInfoStatsOutput); - shared_mem_video_info_stats_radio_in_close(g_pSM_VideoInfoStatsRadioIn); + shared_mem_video_frames_stats_close(g_pSM_VideoFramesStatsOutput); + //shared_mem_video_frames_stats_radio_in_close(g_pSM_VideoInfoStatsRadioIn); shared_mem_router_vehicles_runtime_info_close(g_pSM_RouterVehiclesRuntimeInfo); radio_links_close_rxtx_radio_interfaces(); @@ -2240,61 +2267,96 @@ void video_processors_cleanup() rx_video_output_uninit(); } -void _main_loop_no_sync() -{ - static u32 uMaxLoopTime = DEFAULT_MAX_LOOP_TIME_MILISECONDS; +static u32 uMaxLoopTime = DEFAULT_MAX_LOOP_TIME_MILISECONDS; - g_TimeNow = get_current_timestamp_ms(); - u32 tTime0 = g_TimeNow; +// Returns true if the end of a video frame was detected +bool _main_loop_try_recevive_video_data(u16* puEndOfVideoFrameId) +{ + s_bBoolRecvVideoDataThisLoop = false; u32 uTimeStart = g_TimeNow; - u32 tTime1 = 0; while ( g_TimeNow < uTimeStart + 2 ) { //--------------------------------------------- // Check and process retransmissions received and pings received and other high priority radio messages - _try_read_consume_high_priority_packets(10, 100); + _try_read_consume_high_priority_packets(5, 500); //------------------------------------------ // Process all the other radio-in packets int iMaxCountRegPrio = 50; - int iWaitMicroSec = 0; + int iWaitMicroSec = 200; while ( (iMaxCountRegPrio > 0) && (!g_bQuit) ) { - int iConsumedReg = _try_read_consume_reg_priority_packets(5, iWaitMicroSec); + bool bEndOfVideoFrameDetected = false; + u16 uVideoFrameId = 0; + int iConsumedReg = _try_read_consume_reg_priority_packets(10, iWaitMicroSec, &bEndOfVideoFrameDetected, &uVideoFrameId); _try_read_consume_high_priority_packets(1, 0); - if ( iConsumedReg < 5 ) + + if ( (!g_bSearching) && (!g_bUpdateInProgress) && (NULL != g_pCurrentModel) && (g_pCurrentModel->rxtx_sync_type == RXTX_SYNC_TYPE_ADV) && g_pCurrentModel->hasCamera() && (iConsumedReg > 0) && (! bEndOfVideoFrameDetected) ) + { + g_TimeNow = get_current_timestamp_ms(); + uTimeStart = g_TimeNow; + } + else if ( iConsumedReg < 5 ) break; if ( g_bQuit ) break; + if ( (!g_bSearching) && (NULL != g_pCurrentModel) && (g_pCurrentModel->rxtx_sync_type == RXTX_SYNC_TYPE_ADV) && g_pCurrentModel->hasCamera() && bEndOfVideoFrameDetected ) + { + if ( NULL != puEndOfVideoFrameId ) + *puEndOfVideoFrameId = uVideoFrameId; + return true; + } iMaxCountRegPrio -= iConsumedReg; + iWaitMicroSec = 100; } g_TimeNow = get_current_timestamp_ms(); - tTime1 = g_TimeNow; } + return false; +} - if ( g_bSearching ) +void _main_loop_searching() +{ + g_TimeNow = get_current_timestamp_ms(); + + _main_loop_try_recevive_video_data(NULL); + + _router_periodic_loop(); + _synchronize_shared_mems(); + _read_ipc_pipes(g_TimeNow); + _consume_ipc_messages(); + + s_iCountCPULoopOverflows = 0; + u32 uTimeNow = get_current_timestamp_ms(); + if ( NULL != g_pProcessStats ) { - _synchronize_shared_mems(); - _read_ipc_pipes(tTime1); - _consume_ipc_messages(); + if ( g_pProcessStats->uMaxLoopTimeMs < uTimeNow - g_TimeNow ) + g_pProcessStats->uMaxLoopTimeMs = uTimeNow - g_TimeNow; + g_pProcessStats->uTotalLoopTime += uTimeNow - g_TimeNow; + if ( 0 != g_pProcessStats->uLoopCounter ) + g_pProcessStats->uAverageLoopTimeMs = g_pProcessStats->uTotalLoopTime / g_pProcessStats->uLoopCounter; + } +} - if ( g_TimeNow > tTime0 + uMaxLoopTime ) - log_softerror_and_alarm("Router loop took too long to complete (%d milisec)!!!", g_TimeNow - tTime0); - else - s_iCountCPULoopOverflows = 0; - return; - } + +void _main_loop_simple(bool bNoTxSync) +{ + g_TimeNow = get_current_timestamp_ms(); + u32 tTime0 = g_TimeNow; + + _main_loop_try_recevive_video_data(NULL); + + u32 tTime1 = g_TimeNow; for( int i=0; iperiodicLoop(g_TimeNow); + g_pVideoProcessorRxList[i]->periodicLoop(g_TimeNow, false); } if ( controller_rt_info_will_advance_index(&g_SMControllerRTInfo, g_TimeNow) ) - adaptive_video_periodic_loop(); + adaptive_video_periodic_loop(false); _router_periodic_loop(); _synchronize_shared_mems(); @@ -2333,16 +2395,12 @@ void _main_loop_no_sync() bool bSendNow = false; - if ( !g_pCurrentModel->hasCamera()) - bSendNow = true; - if ( g_bUpdateInProgress ) - bSendNow = true; - if ( g_pCurrentModel->rxtx_sync_type == RXTX_SYNC_TYPE_NONE ) + if ( bNoTxSync || g_bUpdateInProgress || (!g_pCurrentModel->hasCamera()) ) bSendNow = true; if ( g_TimeNow > s_QueueRadioPacketsRegPrio.timeFirstPacket + 55 ) bSendNow = true; - if ( g_pCurrentModel->rxtx_sync_type != RXTX_SYNC_TYPE_NONE ) + if ( (! bNoTxSync) && (! bSendNow) ) { ProcessorRxVideo* pProcessorRxVideo = ProcessorRxVideo::getVideoProcessorForVehicleId(g_pCurrentModel->uVehicleId, 0); if ( NULL != pProcessorRxVideo ) @@ -2387,10 +2445,13 @@ void _main_loop_no_sync() } if ( controller_rt_info_check_advance_index(&g_SMControllerRTInfo, g_TimeNow) ) + { radio_rx_set_packet_counter_output(&(g_SMControllerRTInfo.uRxVideoPackets[g_SMControllerRTInfo.iCurrentIndex][0]), &(g_SMControllerRTInfo.uRxVideoECPackets[g_SMControllerRTInfo.iCurrentIndex][0]), - &(g_SMControllerRTInfo.uRxVideoRetrPackets[g_SMControllerRTInfo.iCurrentIndex][0]), + &(g_SMControllerRTInfo.uRxHighPriorityPackets[g_SMControllerRTInfo.iCurrentIndex][0]), &(g_SMControllerRTInfo.uRxDataPackets[g_SMControllerRTInfo.iCurrentIndex][0]), &(g_SMControllerRTInfo.uRxMissingPackets[g_SMControllerRTInfo.iCurrentIndex][0]), &(g_SMControllerRTInfo.uRxMissingPacketsMaxGap[g_SMControllerRTInfo.iCurrentIndex][0])); + radio_rx_set_air_gap_track_output(&(g_SMControllerRTInfo.uRxMaxAirgapSlots[g_SMControllerRTInfo.iCurrentIndex])); + } if ( NULL != g_pProcessStats ) { @@ -2404,5 +2465,148 @@ void _main_loop_no_sync() void _main_loop_basic_sync() { - _main_loop_no_sync(); -} \ No newline at end of file + _main_loop_simple(false); +} + + +void _main_loop_adv_sync() +{ + g_TimeNow = get_current_timestamp_ms(); + u32 tTime0 = g_TimeNow; + + u16 uEndOfVideoFrameId = 0; + bool bEndOfVideoFrameDetected = _main_loop_try_recevive_video_data(&uEndOfVideoFrameId); + + if ( bEndOfVideoFrameDetected && (!g_pCurrentModel->isVideoLinkFixedOneWay())) + { + t_packet_header_compressed PHC; + radio_packet_compressed_init(&PHC, PACKET_COMPONENT_VIDEO, PACKET_TYPE_VIDEO_ACK); + PHC.vehicle_id_src = g_uControllerId; + PHC.vehicle_id_dest = g_pCurrentModel->uVehicleId; + PHC.uExtraData = uEndOfVideoFrameId; + u8 packet[MAX_PACKET_TOTAL_SIZE]; + memcpy(packet, (u8*)&PHC, sizeof(t_packet_header_compressed)); + send_packet_to_radio_interfaces(packet, PHC.total_length, -1, 501); + } + + u32 tTime1 = g_TimeNow; + + bool bForceSyncNow = false; + if ( s_bBoolRecvVideoDataThisLoop || bEndOfVideoFrameDetected ) + bForceSyncNow = true; + + for( int i=0; iperiodicLoop(g_TimeNow, bForceSyncNow); + //if ( iRequestedCount > 0 ) + // log_line("DEBUG req %d retransmissions, last video recv data %u ms ago", iRequestedCount, g_TimeNow-s_uLastTimeRecvVideoDataPacket); + } + if ( bForceSyncNow || controller_rt_info_will_advance_index(&g_SMControllerRTInfo, g_TimeNow) ) + adaptive_video_periodic_loop(bForceSyncNow); + + _router_periodic_loop(); + _synchronize_shared_mems(); + _check_rx_loop_consistency(); + _check_queue_ping(); + _read_ipc_pipes(tTime1); + _consume_ipc_messages(); + + if ( (NULL != g_pCurrentModel) && g_pCurrentModel->hasCamera() ) + rx_video_output_periodic_loop(); + + g_TimeNow = get_current_timestamp_ms(); + u32 tTime2 = g_TimeNow; + + if ( controller_rt_info_will_advance_index(&g_SMControllerRTInfo, g_TimeNow) ) + { + for( int i=0; iruntimeInterfaceInfoRx.radioHwRxInfo.nAntennaCount; + for( int k=0; kruntimeInterfaceInfoRx.radioHwRxInfo.nAntennaCount; k++ ) + { + g_SMControllerRTInfo.radioInterfacesDbm[g_SMControllerRTInfo.iCurrentIndex][i].iDbmLast[k] = g_SM_RadioStats.radio_interfaces[i].signalInfo.dbmValuesAll.iDbmLast[k]; + g_SMControllerRTInfo.radioInterfacesDbm[g_SMControllerRTInfo.iCurrentIndex][i].iDbmMin[k] = g_SM_RadioStats.radio_interfaces[i].signalInfo.dbmValuesAll.iDbmMin[k]; + g_SMControllerRTInfo.radioInterfacesDbm[g_SMControllerRTInfo.iCurrentIndex][i].iDbmMax[k] = g_SM_RadioStats.radio_interfaces[i].signalInfo.dbmValuesAll.iDbmMax[k]; + g_SMControllerRTInfo.radioInterfacesDbm[g_SMControllerRTInfo.iCurrentIndex][i].iDbmAvg[k] = g_SM_RadioStats.radio_interfaces[i].signalInfo.dbmValuesAll.iDbmAvg[k]; + g_SMControllerRTInfo.radioInterfacesDbm[g_SMControllerRTInfo.iCurrentIndex][i].iDbmChangeSpeedMin[k] = g_SM_RadioStats.radio_interfaces[i].signalInfo.dbmValuesAll.iDbmChangeSpeedMin[k]; + g_SMControllerRTInfo.radioInterfacesDbm[g_SMControllerRTInfo.iCurrentIndex][i].iDbmChangeSpeedMax[k] = g_SM_RadioStats.radio_interfaces[i].signalInfo.dbmValuesAll.iDbmChangeSpeedMax[k]; + } + radio_stats_reset_signal_info_for_card(&g_SM_RadioStats, i); + } + } + + g_TimeNow = get_current_timestamp_ms(); + u32 tTime3 = g_TimeNow; + + bool bSendNow = false; + + if ( g_bUpdateInProgress || (!g_pCurrentModel->hasCamera()) ) + bSendNow = true; + if ( g_TimeNow > s_QueueRadioPacketsRegPrio.timeFirstPacket + 55 ) + bSendNow = true; + + if ( ! bSendNow ) + { + ProcessorRxVideo* pProcessorRxVideo = ProcessorRxVideo::getVideoProcessorForVehicleId(g_pCurrentModel->uVehicleId, 0); + if ( NULL != pProcessorRxVideo ) + if ( NULL != pProcessorRxVideo->m_pVideoRxBuffer ) + if ( pProcessorRxVideo->m_pVideoRxBuffer->isFrameEnded() ) + { + u32 uFrameDuration = 1000 / g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].fps; + if ( pProcessorRxVideo->getLastestVideoPacketReceiveTime() >= g_TimeNow - uFrameDuration ) + { + if ( g_TimeNow < pProcessorRxVideo->m_pVideoRxBuffer->getLastFrameEndTime() + uFrameDuration - 5 ) + bSendNow = true; + } + else if ( g_TimeNow > pProcessorRxVideo->getLastestVideoPacketReceiveTime() + 2 ) + bSendNow = true; + } + } + + if ( bSendNow ) + { + _process_and_send_packets_individually(&s_QueueRadioPacketsHighPrio); + _process_and_send_packets_individually(&s_QueueRadioPacketsRegPrio); + } + + g_TimeNow = get_current_timestamp_ms(); + u32 tTime4 = g_TimeNow; + if ( (g_TimeNow > g_TimeStart + 10000) && (tTime4 > tTime0 + uMaxLoopTime) ) + { + log_softerror_and_alarm("Router loop took too long to complete (%d milisec: %u + %u + %u + %u), repeat count: %u!!!", tTime4 - tTime0, tTime1-tTime0, tTime2-tTime1, tTime3-tTime2, tTime4-tTime3, s_iCountCPULoopOverflows+1); + + s_iCountCPULoopOverflows++; + if ( s_iCountCPULoopOverflows > 5 ) + if ( g_TimeNow > g_TimeLastSetRadioFlagsCommandSent + 5000 ) + send_alarm_to_central(ALARM_ID_CONTROLLER_CPU_LOOP_OVERLOAD,(tTime4-tTime0), 0); + + if ( tTime4 >= tTime0 + 300 ) + if ( g_TimeNow > g_TimeLastSetRadioFlagsCommandSent + 5000 ) + send_alarm_to_central(ALARM_ID_CONTROLLER_CPU_LOOP_OVERLOAD,(tTime4-tTime0)<<16, 0); + } + else + { + s_iCountCPULoopOverflows = 0; + } + + if ( controller_rt_info_check_advance_index(&g_SMControllerRTInfo, g_TimeNow) ) + { + radio_rx_set_packet_counter_output(&(g_SMControllerRTInfo.uRxVideoPackets[g_SMControllerRTInfo.iCurrentIndex][0]), + &(g_SMControllerRTInfo.uRxVideoECPackets[g_SMControllerRTInfo.iCurrentIndex][0]), + &(g_SMControllerRTInfo.uRxHighPriorityPackets[g_SMControllerRTInfo.iCurrentIndex][0]), + &(g_SMControllerRTInfo.uRxDataPackets[g_SMControllerRTInfo.iCurrentIndex][0]), &(g_SMControllerRTInfo.uRxMissingPackets[g_SMControllerRTInfo.iCurrentIndex][0]), &(g_SMControllerRTInfo.uRxMissingPacketsMaxGap[g_SMControllerRTInfo.iCurrentIndex][0])); + radio_rx_set_air_gap_track_output(&(g_SMControllerRTInfo.uRxMaxAirgapSlots[g_SMControllerRTInfo.iCurrentIndex])); + } + + if ( NULL != g_pProcessStats ) + { + if ( g_pProcessStats->uMaxLoopTimeMs < tTime4 - tTime0 ) + g_pProcessStats->uMaxLoopTimeMs = tTime4 - tTime0; + g_pProcessStats->uTotalLoopTime += tTime4 - tTime0; + if ( 0 != g_pProcessStats->uLoopCounter ) + g_pProcessStats->uAverageLoopTimeMs = g_pProcessStats->uTotalLoopTime / g_pProcessStats->uLoopCounter; + } +} diff --git a/code/r_station/ruby_rx_telemetry.cpp b/code/r_station/ruby_rx_telemetry.cpp index cf11ebb8..266c633b 100644 --- a/code/r_station/ruby_rx_telemetry.cpp +++ b/code/r_station/ruby_rx_telemetry.cpp @@ -40,7 +40,7 @@ #include "../base/models_list.h" #include "../base/ctrl_settings.h" #include "../base/ctrl_interfaces.h" -#include "../base/controller_utils.h" +#include "../utils/utils_controller.h" #include "../base/ruby_ipc.h" #include "../common/string_utils.h" diff --git a/code/r_station/ruby_tx_rc.cpp b/code/r_station/ruby_tx_rc.cpp index 49c532a8..b8462b8a 100644 --- a/code/r_station/ruby_tx_rc.cpp +++ b/code/r_station/ruby_tx_rc.cpp @@ -54,7 +54,7 @@ #include "../base/utils.h" #include "../base/ctrl_interfaces.h" #include "../base/ctrl_settings.h" -#include "../base/controller_utils.h" +#include "../utils/utils_controller.h" #include "../base/ruby_ipc.h" #include "../common/string_utils.h" diff --git a/code/r_station/rx_video_output.cpp b/code/r_station/rx_video_output.cpp index e5e6c76c..d5a5410c 100644 --- a/code/r_station/rx_video_output.cpp +++ b/code/r_station/rx_video_output.cpp @@ -162,25 +162,25 @@ void _rx_video_output_launch_video_player() if ( pcs->iNiceRXVideo >= 0 ) { // Auto priority - sprintf(szPlayer, "./%s > /dev/null 2>&1&", s_szOutputVideoPlayerFilename); + sprintf(szPlayer, "./%s > /dev/null 2>&1 &", s_szOutputVideoPlayerFilename); //sprintf(szPlayer, "%s -z -o hdmi /tmp/ruby/fifovidstream > /dev/null 2>&1 &", s_szOutputVideoPlayerFilename); } else { #ifdef HW_CAPABILITY_IONICE if ( pcs->ioNiceRXVideo > 0 ) - sprintf(szPlayer, "ionice -c 1 -n %d nice -n %d ./%s > /dev/null 2>&1 &", pcs->ioNiceRXVideo, pcs->iNiceRXVideo, s_szOutputVideoPlayerFilename); + sprintf(szPlayer, "ionice -c 1 -n %d nice -n %d ./%s 2>&1 1>/dev/null &", pcs->ioNiceRXVideo, pcs->iNiceRXVideo, s_szOutputVideoPlayerFilename); else #endif - sprintf(szPlayer, "nice -n %d ./%s > /dev/null 2>&1 &", pcs->iNiceRXVideo, s_szOutputVideoPlayerFilename); + sprintf(szPlayer, "nice -n %d ./%s 2>&1 1>/dev/null &", pcs->iNiceRXVideo, s_szOutputVideoPlayerFilename); } //pthread_t th; //pthread_create(&th, NULL, &_thread_video_player, NULL ); - hw_execute_bash_command(szPlayer, NULL); - if ( pcs->iNiceRXVideo < 0 ) - hw_set_proc_priority(s_szOutputVideoPlayerFilename, pcs->iNiceRXVideo, pcs->ioNiceRXVideo, 1); + //hw_execute_bash_command(szPlayer, NULL); + system(szPlayer); + log_line("Executed video player command."); char szComm[256]; char szPids[128]; @@ -188,7 +188,9 @@ void _rx_video_output_launch_video_player() sprintf(szComm, "pidof %s", s_szOutputVideoPlayerFilename); szPids[0] = 0; int count = 0; - while ( (strlen(szPids) <= 2) && (count < 1000) ) + u32 uTimeStart = get_current_timestamp_ms(); + + while ( (strlen(szPids) <= 2) && (count < 1000) && (get_current_timestamp_ms() < uTimeStart+2000) ) { hw_execute_bash_command_silent(szComm, szPids); if ( strlen(szPids) > 2 ) @@ -198,8 +200,15 @@ void _rx_video_output_launch_video_player() count++; } s_iPIDVideoPlayer = atoi(szPids); - log_line("[VideoOutput] Started video player [%s], PID: %s (%d)", s_szOutputVideoPlayerFilename, szPids, s_iPIDVideoPlayer); + if ( (strlen(szPids) > 2) && (s_iPIDVideoPlayer > 0) ) + { + if ( pcs->iNiceRXVideo < 0 ) + hw_set_proc_priority(s_szOutputVideoPlayerFilename, pcs->iNiceRXVideo, pcs->ioNiceRXVideo, 1); + log_line("[VideoOutput] Started video player [%s], PID: %s (%d)", s_szOutputVideoPlayerFilename, szPids, s_iPIDVideoPlayer); + } + else + log_softerror_and_alarm("Failed to launch video player"); #endif #ifdef HW_PLATFORM_RADXA_ZERO3 @@ -563,7 +572,7 @@ void rx_video_output_enable_pipe_output() return; } - s_fPipeVideoOutToPlayer = open(FIFO_RUBY_STATION_VIDEO_STREAM, O_CREAT | O_WRONLY); + s_fPipeVideoOutToPlayer = open(FIFO_RUBY_STATION_VIDEO_STREAM, O_CREAT | O_WRONLY | O_NONBLOCK); if ( s_fPipeVideoOutToPlayer < 0 ) { log_error_and_alarm("[VideoOutput] Failed to open video output pipe write endpoint: %s, error code (%d): [%s]", @@ -576,13 +585,12 @@ void rx_video_output_enable_pipe_output() //if ( RUBY_PIPES_EXTRA_FLAGS & O_NONBLOCK ) //if ( 0 != fcntl(s_fPipeVideoOutToPlayer, F_SETFL, O_NONBLOCK) ) // log_softerror_and_alarm("[IPC] Failed to set nonblock flag on PIC channel %s write endpoint.", FIFO_RUBY_STATION_VIDEO_STREAM); - - log_line("[IPC] Video player FIFO write endpoint pipe flags: %s", str_get_pipe_flags(fcntl(s_fPipeVideoOutToPlayer, F_GETFL))); + //log_line("[VideoOutput] Video player FIFO write endpoint pipe new flags: %s", str_get_pipe_flags(fcntl(s_fPipeVideoOutToPlayer, F_GETFL))); log_line("[VideoOutput] Video player FIFO default size: %d bytes", fcntl(s_fPipeVideoOutToPlayer, F_GETPIPE_SZ)); - //fcntl(s_fPipeVideoOutToPlayer, F_SETPIPE_SZ, 9000); - //log_line("[VideoOutput] Video player FIFO new size: %d bytes", fcntl(s_fPipeVideoOutToPlayer, F_GETPIPE_SZ)); + fcntl(s_fPipeVideoOutToPlayer, F_SETPIPE_SZ, 250000); + log_line("[VideoOutput] Video player FIFO new size: %d bytes", fcntl(s_fPipeVideoOutToPlayer, F_GETPIPE_SZ)); s_bDidSentAnyDataToVideoPlayerPipe = false; } @@ -637,38 +645,27 @@ void rx_video_output_disable_local_player_udp_output() s_iLocalVideoPlayerUDPSocket = -1; } -void _processor_rx_video_forward_parse_h264_stream(u8* pBuffer, int length) +void _processor_rx_video_output_parse_h264_stream(u8* pBuffer, int iLength) { - bool bStartOfFrameDetected = s_ParserH264Output.parseData(pBuffer, length, g_TimeNow); - if ( ! bStartOfFrameDetected ) - return; - - u32 uLastFrameDuration = s_ParserH264Output.getTimeDurationOfLastCompleteFrame(); - if ( uLastFrameDuration > 127 ) - uLastFrameDuration = 127; - if ( uLastFrameDuration < 1 ) - uLastFrameDuration = 1; - - u32 uLastFrameSize = s_ParserH264Output.getSizeOfLastCompleteFrame(); - uLastFrameSize /= 1000; // transform to kbytes + while ( iLength > 0 ) + { + int iBytesParsed = s_ParserH264Output.parseDataUntillStartOfNextNAL(pBuffer, iLength, g_TimeNow); + if ( iBytesParsed >= iLength ) + break; - if ( uLastFrameSize > 127 ) - uLastFrameSize = 127; // kbytes + //log_line("DEBUG %d", iStartOfFramesDetected); + //log_line("DEBUG o last frame size: %d bytes", s_ParserH264Output.getSizeOfLastCompleteFrameInBytes()); + //log_line("DEBUG o detected start of %sframe", s_ParserH264Output.IsInsideIFrame()?"I":"P"); - g_SM_VideoInfoStatsOutput.uLastIndex = (g_SM_VideoInfoStatsOutput.uLastIndex+1) % MAX_FRAMES_SAMPLES; - g_SM_VideoInfoStatsOutput.uFramesDuration[g_SM_VideoInfoStatsOutput.uLastIndex] = uLastFrameDuration; - g_SM_VideoInfoStatsOutput.uFramesTypesAndSizes[g_SM_VideoInfoStatsOutput.uLastIndex] = (g_SM_VideoInfoStatsOutput.uFramesTypesAndSizes[g_SM_VideoInfoStatsOutput.uLastIndex] & 0x80) | ((u8)uLastFrameSize); - - u32 uNextIndex = (g_SM_VideoInfoStatsOutput.uLastIndex+1) % MAX_FRAMES_SAMPLES; - - if ( s_ParserH264Output.IsInsideIFrame() ) - g_SM_VideoInfoStatsOutput.uFramesTypesAndSizes[uNextIndex] |= (1<<7); - else - g_SM_VideoInfoStatsOutput.uFramesTypesAndSizes[uNextIndex] &= 0x7F; + update_shared_mem_video_frames_stats_on_new_frame( &g_SM_VideoFramesStatsOutput, + s_ParserH264Output.getSizeOfLastCompleteFrameInBytes(), + s_ParserH264Output.getCurrentFrameType(), + s_ParserH264Output.getDetectedSlices(), + s_ParserH264Output.getDetectedFPS(), g_TimeNow ); - g_SM_VideoInfoStatsOutput.uKeyframeIntervalMs = s_ParserH264Output.getCurrentlyDetectedKeyframeIntervalMs(); - g_SM_VideoInfoStatsOutput.uDetectedFPS = s_ParserH264Output.getDetectedFPS(); - g_SM_VideoInfoStatsOutput.uDetectedSlices = (u32) s_ParserH264Output.getDetectedSlices(); + pBuffer += iBytesParsed + 1; + iLength -= iBytesParsed + 1; + } } void _rx_video_output_to_video_player(u32 uVehicleId, int width, int height, u8* pBuffer, int length) @@ -720,6 +717,8 @@ void _rx_video_output_to_video_player(u32 uVehicleId, int width, int height, u8* // Error outputing video to player + log_softerror_and_alarm("[VideoOutput] Failed to write to player pipe (%d bytes). Ret code: %d, Error code: %d, err string: (%s)", + length, iRes, errno, strerror(errno)); u32 uFlags = 0; if ( iRes >= 0 ) @@ -868,12 +867,12 @@ void rx_video_output_video_data(u32 uVehicleId, u8 uVideoStreamType, int width, // */ //} - if ( NULL != g_pCurrentModel ) + if ( (NULL != g_pCurrentModel) && g_pCurrentModel->bDeveloperMode ) if ( uVideoStreamType == VIDEO_TYPE_H264 ) - if ( g_pCurrentModel->osd_params.osd_flags[g_pCurrentModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_KEYFRAMES_INFO) - if ( get_ControllerSettings()->iShowVideoStreamInfoCompactType == 0 ) + if ( g_pCurrentModel->osd_params.osd_flags[g_pCurrentModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_H264_FRAMES_INFO) + //if ( get_ControllerSettings()->iShowVideoStreamInfoCompactType == 0 ) { - _processor_rx_video_forward_parse_h264_stream(pBuffer, video_data_length); + _processor_rx_video_output_parse_h264_stream(pBuffer, video_data_length); } if ( -1 != s_fPipeVideoOutToPlayer ) diff --git a/code/r_station/shared_vars.cpp b/code/r_station/shared_vars.cpp index 462d87ac..97f60052 100644 --- a/code/r_station/shared_vars.cpp +++ b/code/r_station/shared_vars.cpp @@ -64,10 +64,10 @@ shared_mem_radio_stats_rx_hist* g_pSM_HistoryRxStats = NULL; shared_mem_radio_stats_rx_hist g_SM_HistoryRxStats; shared_mem_audio_decode_stats* g_pSM_AudioDecodeStats = NULL; -shared_mem_video_info_stats g_SM_VideoInfoStatsOutput; -shared_mem_video_info_stats g_SM_VideoInfoStatsRadioIn; -shared_mem_video_info_stats* g_pSM_VideoInfoStatsOutput = NULL; -shared_mem_video_info_stats* g_pSM_VideoInfoStatsRadioIn = NULL; +shared_mem_video_frames_stats g_SM_VideoFramesStatsOutput; +shared_mem_video_frames_stats* g_pSM_VideoFramesStatsOutput = NULL; +//shared_mem_video_frames_stats g_SM_VideoInfoStatsRadioIn; +//shared_mem_video_frames_stats* g_pSM_VideoInfoStatsRadioIn = NULL; shared_mem_router_vehicles_runtime_info g_SM_RouterVehiclesRuntimeInfo; shared_mem_router_vehicles_runtime_info* g_pSM_RouterVehiclesRuntimeInfo = NULL; @@ -75,9 +75,6 @@ shared_mem_router_vehicles_runtime_info* g_pSM_RouterVehiclesRuntimeInfo = NULL; shared_mem_video_stream_stats_rx_processors g_SM_VideoDecodeStats; shared_mem_video_stream_stats_rx_processors* g_pSM_VideoDecodeStats = NULL; -shared_mem_video_stream_stats_history_rx_processors g_SM_VideoDecodeStatsHistory; -shared_mem_video_stream_stats_history_rx_processors* g_pSM_VideoDecodeStatsHistory = NULL; - shared_mem_radio_rx_queue_info* g_pSM_RadioRxQueueInfo = NULL; shared_mem_radio_rx_queue_info g_SM_RadioRxQueueInfo; diff --git a/code/r_station/shared_vars.h b/code/r_station/shared_vars.h index d0c8843d..227f1937 100644 --- a/code/r_station/shared_vars.h +++ b/code/r_station/shared_vars.h @@ -50,10 +50,10 @@ extern shared_mem_radio_stats_rx_hist* g_pSM_HistoryRxStats; extern shared_mem_radio_stats_rx_hist g_SM_HistoryRxStats; extern shared_mem_audio_decode_stats* g_pSM_AudioDecodeStats; -extern shared_mem_video_info_stats g_SM_VideoInfoStatsOutput; -extern shared_mem_video_info_stats g_SM_VideoInfoStatsRadioIn; -extern shared_mem_video_info_stats* g_pSM_VideoInfoStatsOutput; -extern shared_mem_video_info_stats* g_pSM_VideoInfoStatsRadioIn; +extern shared_mem_video_frames_stats g_SM_VideoFramesStatsOutput; +extern shared_mem_video_frames_stats* g_pSM_VideoFramesStatsOutput; +//extern shared_mem_video_frames_stats g_SM_VideoInfoStatsRadioIn; +//extern shared_mem_video_frames_stats* g_pSM_VideoInfoStatsRadioIn; extern shared_mem_router_vehicles_runtime_info g_SM_RouterVehiclesRuntimeInfo; extern shared_mem_router_vehicles_runtime_info* g_pSM_RouterVehiclesRuntimeInfo; @@ -61,9 +61,6 @@ extern shared_mem_router_vehicles_runtime_info* g_pSM_RouterVehiclesRuntimeInfo; extern shared_mem_video_stream_stats_rx_processors g_SM_VideoDecodeStats; extern shared_mem_video_stream_stats_rx_processors* g_pSM_VideoDecodeStats; -extern shared_mem_video_stream_stats_history_rx_processors g_SM_VideoDecodeStatsHistory; -extern shared_mem_video_stream_stats_history_rx_processors* g_pSM_VideoDecodeStatsHistory; - extern shared_mem_radio_rx_queue_info* g_pSM_RadioRxQueueInfo; extern shared_mem_radio_rx_queue_info g_SM_RadioRxQueueInfo; diff --git a/code/r_station/shared_vars_state.cpp b/code/r_station/shared_vars_state.cpp index 62c9e1c7..e56c936e 100644 --- a/code/r_station/shared_vars_state.cpp +++ b/code/r_station/shared_vars_state.cpp @@ -58,7 +58,8 @@ void resetVehicleRuntimeInfo(int iIndex) } g_State.vehiclesRuntimeInfo[iIndex].uLastTimeReceivedAckFromVehicle = 0; - g_State.vehiclesRuntimeInfo[iIndex].iVehicleClockIsBehindThisMilisec = 500000000; + g_State.vehiclesRuntimeInfo[iIndex].iVehicleClockDeltaMilisec = 500000000; + g_State.vehiclesRuntimeInfo[iIndex].uMinimumPingTimeMilisec = MAX_U32; g_State.vehiclesRuntimeInfo[iIndex].uTimeLastCommandIdSent = 0; g_State.vehiclesRuntimeInfo[iIndex].uLastCommandIdSent = MAX_U32; @@ -233,15 +234,13 @@ void addCommandRTTimeToRuntimeInfo(type_global_state_vehicle_runtime_info* pRunt } } -void adjustLinkClockDeltasForVehicleRuntimeIndex(int iRuntimeInfoIndex, u32 uRoundtripTimeMs, u32 uLocalTimeVehicleMs) +void +adjustLinkClockDeltasForVehicleRuntimeIndex(int iRuntimeInfoIndex, u32 uRoundtripTimeMs, u32 uLocalTimeVehicleMs) { if ( (iRuntimeInfoIndex < 0) || (iRuntimeInfoIndex >= MAX_CONCURENT_VEHICLES) ) return; - if ( g_State.vehiclesRuntimeInfo[iRuntimeInfoIndex].iVehicleClockIsBehindThisMilisec == 500000000 ) - g_State.vehiclesRuntimeInfo[iRuntimeInfoIndex].iVehicleClockIsBehindThisMilisec = (int) get_current_timestamp_ms() - (int)uRoundtripTimeMs/2 - (int)uLocalTimeVehicleMs; - else if ( (int)uRoundtripTimeMs < g_State.vehiclesRuntimeInfo[iRuntimeInfoIndex].iVehicleClockIsBehindThisMilisec ) - g_State.vehiclesRuntimeInfo[iRuntimeInfoIndex].iVehicleClockIsBehindThisMilisec = (int) get_current_timestamp_ms() - (int)uRoundtripTimeMs/2 - (int)uLocalTimeVehicleMs; + g_State.vehiclesRuntimeInfo[iRuntimeInfoIndex].iVehicleClockDeltaMilisec = (int)uLocalTimeVehicleMs - ((int) g_TimeNow - (int)uRoundtripTimeMs/3); - radio_set_link_clock_delta(g_State.vehiclesRuntimeInfo[iRuntimeInfoIndex].iVehicleClockIsBehindThisMilisec); + radio_set_link_clock_delta(g_State.vehiclesRuntimeInfo[iRuntimeInfoIndex].iVehicleClockDeltaMilisec); } \ No newline at end of file diff --git a/code/r_station/shared_vars_state.h b/code/r_station/shared_vars_state.h index b37c2478..43b49b05 100644 --- a/code/r_station/shared_vars_state.h +++ b/code/r_station/shared_vars_state.h @@ -21,9 +21,9 @@ typedef struct u32 uTimeLastPingReplyReceivedFromVehicleOnLocalRadioLinks[MAX_RADIO_INTERFACES]; u8 uLastPingIdReceivedFromVehicleOnLocalRadioLinks[MAX_RADIO_INTERFACES]; u32 uPingRoundtripTimeOnLocalRadioLinks[MAX_RADIO_INTERFACES]; - + u32 uMinimumPingTimeMilisec; u32 uLastTimeReceivedAckFromVehicle; - int iVehicleClockIsBehindThisMilisec; + int iVehicleClockDeltaMilisec; // Commands roundtrip info @@ -36,8 +36,6 @@ typedef struct u32 uMaxCommandRoundtripMiliseconds; u32 uMinCommandRoundtripMiliseconds; - u32 uMinPingRoundtripTime; - // Adaptive video info u8 uPendingVideoProfileToSet; u32 uPendingVideoProfileToSetRequestedBy; diff --git a/code/r_station/video_rx_buffers.cpp b/code/r_station/video_rx_buffers.cpp index 23e89f02..030199fe 100644 --- a/code/r_station/video_rx_buffers.cpp +++ b/code/r_station/video_rx_buffers.cpp @@ -103,7 +103,7 @@ bool VideoRxPacketsBuffer::init(Model* pModel) return false; } log_line("[VideoRXBuffer] Initialize video Rx buffer instance number %d.", m_iInstanceIndex+1); - _empty_buffers("init"); + _empty_buffers("init", NULL, NULL); m_bInitialized = true; log_line("[VideoRXBuffer] Initialized video Tx buffer instance number %d.", m_iInstanceIndex+1); return true; @@ -122,7 +122,7 @@ bool VideoRxPacketsBuffer::uninit() void VideoRxPacketsBuffer::emptyBuffers(const char* szReason) { - _empty_buffers(szReason); + _empty_buffers(szReason, NULL, NULL); } bool VideoRxPacketsBuffer::_check_allocate_video_block_in_buffer(int iBufferIndex) @@ -174,17 +174,81 @@ void VideoRxPacketsBuffer::_empty_block_buffer_index(int iBufferIndex) } } -void VideoRxPacketsBuffer::_empty_buffers(const char* szReason) +void VideoRxPacketsBuffer::_empty_buffers(const char* szReason, t_packet_header* pPH, t_packet_header_video_full_98* pPHVF) { m_bEndOfFirstIFrameDetected = false; m_bIsInsideIFrame = false; m_bFrameEnded = true; m_uFrameEndedTime = 0; + char szLog[256]; if ( NULL == szReason ) - log_line("Empty buffers (no reason)"); + strcpy(szLog, "[VRXBuffers] Empty buffers (no reason)"); else - log_line("Empty buffers (%s)", szReason); + sprintf(szLog, "[VRXBuffers] Empty buffers (%s)", szReason); + + if ( (NULL == pPH) || (NULL == pPHVF) ) + log_line("%s (no additional data)", szLog); + else + { + log_line("%s (recv video packet [%u/%u] (retransmitted: %s), frame id: %u, stream id/packet index: %u, radio index: %u)", + szLog, pPHVF->uCurrentBlockIndex, pPHVF->uCurrentBlockPacketIndex, + (pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED)?"yes":"no", + pPHVF->uFrameId, + (pPH->stream_packet_idx & PACKET_FLAGS_MASK_STREAM_INDEX) >> PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX, + pPH->stream_packet_idx & PACKET_FLAGS_MASK_STREAM_PACKET_IDX, pPH->radio_link_packet_index); + + log_line("[VRXBuffers] Max video block packet received: [%u/%u]", m_uMaxVideoBlockIndexReceived, m_uMaxVideoBlockPacketIndexReceived); + log_line("[VRXBuffers] First received block buffer index: %d, packet index: %d", + m_iBufferIndexFirstReceivedBlock, m_iBufferIndexFirstReceivedPacketIndex ); + if ( m_iBufferIndexFirstReceivedBlock != -1 ) + { + if ( -1 != m_iBufferIndexFirstReceivedPacketIndex ) + log_line("[VRXBuffers] buffer[%d][%d] is empty? %s, 0x%X", + m_iBufferIndexFirstReceivedBlock, m_iBufferIndexFirstReceivedPacketIndex, + m_VideoBlocks[m_iBufferIndexFirstReceivedBlock].packets[m_iBufferIndexFirstReceivedPacketIndex].bEmpty?"yes":"no", + m_VideoBlocks[m_iBufferIndexFirstReceivedBlock].packets[m_iBufferIndexFirstReceivedPacketIndex].pPH); + int iBufferIndex = m_iBufferIndexFirstReceivedBlock; + log_line("[VRXBuffers] First recv video block index: %u, received data/ec in this block: %d,%d, time now, recv: %u - %u = %u", + m_VideoBlocks[iBufferIndex].uVideoBlockIndex, + m_VideoBlocks[iBufferIndex].iRecvDataPackets, + m_VideoBlocks[iBufferIndex].iRecvECPackets, + g_TimeNow, m_VideoBlocks[iBufferIndex].uReceivedTime, + g_TimeNow - m_VideoBlocks[iBufferIndex].uReceivedTime); + + if ( NULL != m_VideoBlocks[iBufferIndex].packets[0].pPH ) + log_line("[VRXBuffers] First recv video block: %u = [%u/%u] (retr: %s), frame id: %u, stream id/packet index: %u, radio index: %u", + m_VideoBlocks[iBufferIndex].uVideoBlockIndex, + m_VideoBlocks[iBufferIndex].packets[0].pPHVF->uCurrentBlockIndex, + m_VideoBlocks[iBufferIndex].packets[0].pPHVF->uCurrentBlockPacketIndex, + (m_VideoBlocks[iBufferIndex].packets[0].pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED)?"yes":"no", + m_VideoBlocks[iBufferIndex].packets[0].pPHVF->uFrameId, + (m_VideoBlocks[iBufferIndex].packets[0].pPH->stream_packet_idx & PACKET_FLAGS_MASK_STREAM_INDEX) >> PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX, + m_VideoBlocks[iBufferIndex].packets[0].pPH->stream_packet_idx & PACKET_FLAGS_MASK_STREAM_PACKET_IDX, m_VideoBlocks[iBufferIndex].packets[0].pPH->radio_link_packet_index ); + + + iBufferIndex = m_iBufferIndexFirstReceivedBlock+1; + if ( iBufferIndex >= MAX_RXTX_BLOCKS_BUFFER ) + iBufferIndex = 0; + log_line("[VRXBuffers] Second recv video block index: %u, received data/ec in this block: %d,%d, time now, recv: %u - %u = %u", + m_VideoBlocks[iBufferIndex].uVideoBlockIndex, + m_VideoBlocks[iBufferIndex].iRecvDataPackets, + m_VideoBlocks[iBufferIndex].iRecvECPackets, + g_TimeNow, + m_VideoBlocks[iBufferIndex].uReceivedTime, + g_TimeNow - m_VideoBlocks[iBufferIndex].uReceivedTime); + if ( NULL != m_VideoBlocks[iBufferIndex].packets[0].pPH ) + log_line("[VRXBuffers] Second recv video block: %u = [%u/%u] (retr: %s), frame id: %u, stream id/packet index: %u, radio index: %u", + m_VideoBlocks[iBufferIndex].uVideoBlockIndex, + m_VideoBlocks[iBufferIndex].packets[0].pPHVF->uCurrentBlockIndex, + m_VideoBlocks[iBufferIndex].packets[0].pPHVF->uCurrentBlockPacketIndex, + (m_VideoBlocks[iBufferIndex].packets[0].pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED)?"yes":"no", + m_VideoBlocks[iBufferIndex].packets[0].pPHVF->uFrameId, + (m_VideoBlocks[iBufferIndex].packets[0].pPH->stream_packet_idx & PACKET_FLAGS_MASK_STREAM_INDEX) >> PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX, + m_VideoBlocks[iBufferIndex].packets[0].pPH->stream_packet_idx & PACKET_FLAGS_MASK_STREAM_PACKET_IDX, m_VideoBlocks[iBufferIndex].packets[0].pPH->radio_link_packet_index ); + } + } + for( int i=0; iuCurrentBlockIndex == m_uMaxVideoBlockIndexReceived ) if ( pPHVF->uCurrentBlockPacketIndex > m_uMaxVideoBlockPacketIndexReceived ) { - m_uMaxVideoBlockIndexReceived = pPHVF->uCurrentBlockIndex; m_uMaxVideoBlockPacketIndexReceived = pPHVF->uCurrentBlockPacketIndex; if ( pPHVF->uVideoStatusFlags2 & VIDEO_STATUS_FLAGS2_IS_IFRAME ) @@ -509,39 +574,32 @@ bool VideoRxPacketsBuffer::checkAddVideoPacket(u8* pPacket, int iPacketLength) // pPHVF->uCurrentBlockIndex, pPHVF->uCurrentBlockPacketIndex, // iVideoDataSize, uVideoSize, pPHVFDebugInfo->uVideoCRC, uVideoCRC, (pPHVFDebugInfo->uVideoCRC == uVideoCRC)?"equal":"different"); } - /* - static u32 s_uTmpDebugLastBlock = 0; - static u32 s_uTmpDebugLastPacket =0; - - u16 uTmp = 0; - memcpy(&uTmp, pPacket + sizeof(t_packet_header) + sizeof(t_packet_header_video_full_98), sizeof(u16)); - - int iMissing = 0; - if ( pPHVF->uCurrentBlockIndex == s_uTmpDebugLastBlock ) - if ( pPHVF->uCurrentBlockPacketIndex > s_uTmpDebugLastPacket+1 ) - iMissing = pPHVF->uCurrentBlockPacketIndex - s_uTmpDebugLastPacket - 1; - if ( pPHVF->uCurrentBlockIndex > s_uTmpDebugLastBlock+1 ) - iMissing = 1; - if ( pPHVF->uCurrentBlockIndex == s_uTmpDebugLastBlock+1 ) - if ( (pPHVF->uCurrentBlockPacketIndex != 0) || (s_uTmpDebugLastPacket != (u32)(pPHVF->uCurrentBlockDataPackets + pPHVF->uCurrentBlockECPackets -1) ) ) - iMissing = 1; - - //if ( iMissing ) - // log_line("DEBUG 2recv video [%u/%u] %s%d %d/%d bytes", pPHVF->uCurrentBlockIndex, pPHVF->uCurrentBlockPacketIndex, - // iMissing?"***":" ", iMissing, pPHVF->uCurrentBlockPacketSize, pPH->total_length - sizeof(t_packet_header) - sizeof(t_packet_header_video_full_98)); - - s_uTmpDebugLastBlock = pPHVF->uCurrentBlockIndex; - s_uTmpDebugLastPacket = pPHVF->uCurrentBlockPacketIndex; - */ - - if ( pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED ) + /* + static u32 sdebugBlockIndex = 0; + static u32 sdebugBlockPacketIndex = 0; + static u32 sdebugRadioPacketIndex = 0; + static u32 sdebugStreamPacketIndex = 0; + static u32 sdebugPacektFlags = 0; + if ( (pPHVF->uCurrentBlockIndex < sdebugBlockIndex) || + ((pPHVF->uCurrentBlockIndex == sdebugBlockIndex) && (pPHVF->uCurrentBlockPacketIndex < sdebugBlockPacketIndex)) ) + if ( ! (pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED) ) + if ( ! (sdebugPacektFlags & PACKET_FLAGS_BIT_RETRANSMITED) ) { - //if ( -1 == m_iBufferIndexFirstReceivedBlock ) - // log_line("DEBUG vrx check add retransmitted packet, buffer start index: %d", m_iBufferIndexFirstReceivedBlock); - //else - // log_line("DEBUG vrx check add retransmitted packet, buffer start index: %d (%u)", m_iBufferIndexFirstReceivedBlock, m_VideoBlocks[m_iBufferIndexFirstReceivedBlock].uVideoBlockIndex); + log_line("DEBUG received out of order video packet: [%u/%u], last received: [%u/%u]", + pPHVF->uCurrentBlockIndex, pPHVF->uCurrentBlockPacketIndex, sdebugBlockIndex, sdebugBlockPacketIndex); + log_line("DEBUG recv/last radio packet index: %u %u", pPH->radio_link_packet_index, sdebugRadioPacketIndex); + log_line("DEBUG recv/last stream packet index: %u %u", pPH->stream_packet_idx, sdebugStreamPacketIndex); + log_line("DEBUG recv/last retr type: %d %d", pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED, sdebugPacektFlags & PACKET_FLAGS_BIT_RETRANSMITED); } + + sdebugBlockIndex = pPHVF->uCurrentBlockIndex; + sdebugBlockPacketIndex = pPHVF->uCurrentBlockPacketIndex; + sdebugRadioPacketIndex = pPH->radio_link_packet_index; + sdebugStreamPacketIndex = pPH->stream_packet_idx; + sdebugPacektFlags = pPH->packet_flags; + */ + // Empty buffers? (never received anything?) if ( -1 == m_iBufferIndexFirstReceivedBlock ) @@ -562,8 +620,9 @@ bool VideoRxPacketsBuffer::checkAddVideoPacket(u8* pPacket, int iPacketLength) if ( pPHVF->uCurrentBlockIndex < m_VideoBlocks[m_iBufferIndexFirstReceivedBlock].uVideoBlockIndex ) { // Discard it and detect restart of vehicle - if ( pPHVF->uCurrentBlockIndex + 20 < m_VideoBlocks[m_iBufferIndexFirstReceivedBlock].uVideoBlockIndex ) - _empty_buffers("received video block too old, vehicle was restarted"); + if ( ! (pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED) ) + if ( pPHVF->uCurrentBlockIndex + 100 < m_VideoBlocks[m_iBufferIndexFirstReceivedBlock].uVideoBlockIndex ) + _empty_buffers("received video block too old, vehicle was restarted", pPH, pPHVF); return false; } @@ -573,7 +632,7 @@ bool VideoRxPacketsBuffer::checkAddVideoPacket(u8* pPacket, int iPacketLength) // No more room? Discard all buffers as the time difference is too big since first video block in buffer if ( uDeltaVideoBlocks >= MAX_RXTX_BLOCKS_BUFFER-5 ) { - _empty_buffers("no more room"); + _empty_buffers("no more room", pPH, pPHVF); if ( 0 != pPHVF->uCurrentBlockPacketIndex ) return false; diff --git a/code/r_station/video_rx_buffers.h b/code/r_station/video_rx_buffers.h index ce580f7c..8aeb2b6f 100644 --- a/code/r_station/video_rx_buffers.h +++ b/code/r_station/video_rx_buffers.h @@ -66,7 +66,7 @@ class VideoRxPacketsBuffer bool _check_allocate_video_block_in_buffer(int iBufferIndex); void _empty_block_buffer_packet_index(int iBufferIndex, int iPacketIndex); void _empty_block_buffer_index(int iBufferIndex); - void _empty_buffers(const char* szReason); + void _empty_buffers(const char* szReason, t_packet_header* pPH, t_packet_header_video_full_98* pPHVF); void _check_do_ec_for_video_block(int iBufferIndex); // Returns true if the packet has the highest video block/packet index received (in order) bool _add_video_packet_to_buffer(int iBufferIndex, u8* pPacket, int iPacketLength); diff --git a/code/r_tests/test_port_rx.cpp b/code/r_tests/test_port_rx.cpp index 62ac067f..b7c2616e 100644 --- a/code/r_tests/test_port_rx.cpp +++ b/code/r_tests/test_port_rx.cpp @@ -69,6 +69,7 @@ void process_packet_summary( int iInterfaceIndex, u8* pBuffer, int iBufferLength return; uSummaryLastUpdateTime = get_current_timestamp_ms(); + log_line("---------------------------------"); log_line("Total recv pckts: %u/sec; ", g_uTotalRecvPackets ); for( int i=0; ipacket_flags & PACKET_FLAGS_MASK_MODULE) == 0 ) || ((pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == 7 ) ) + log_softerror_and_alarm("Received invalid packet module: %d", (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE)); + if ( (pPH->total_length != nLength) || (pPH->total_length < sizeof(t_packet_header)) ) + log_softerror_and_alarm("Received invalid packet size: %d, (total buffer: %d)", pPH->total_length, nLength); + u32 uStreamId = pPH->stream_packet_idx >> PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; g_uTotalRecvPackets++; g_uTotalRecvPacketsTypes[pPH->packet_type]++; diff --git a/code/r_utils/ruby_initdhcp.cpp b/code/r_utils/ruby_initdhcp.cpp index fea439e6..bcf0f6f4 100644 --- a/code/r_utils/ruby_initdhcp.cpp +++ b/code/r_utils/ruby_initdhcp.cpp @@ -74,7 +74,7 @@ void configureDHCP() strcpy(szType, "STATION"); #ifdef HW_PLATFORM_RASPBERRY - sprintf(szBuff, "nice pump -i eth0 --no-ntp -h Ruby%s", szType); + sprintf(szBuff, "nice pump -i eth0 --no-ntp -h Ruby%s 2>&1 1>/dev/nulll", szType); hw_execute_bash_command(szBuff, NULL); #endif //ETHCLIENTIP=`ip addr show eth0 | grep -Po 'inet \K[\d.]+'` @@ -85,6 +85,44 @@ void configureDHCP() log_line("No ethernet connection detected!"); } +void _check_set_fixed_ip() +{ + load_ControllerSettings(); + ControllerSettings* pCS = get_ControllerSettings(); + if ( (pCS == NULL) || (pCS->nUseFixedIP == 0) ) + return; + + char* pszETH = hardware_has_eth(); + if ( NULL == pszETH ) + { + log_line("Device does not have an ETH port."); + return; + } + log_line("Setting a fixed IP for eth device: %s", pszETH); + + hw_execute_bash_command("export PATH=/usr/local/bin:${PATH}", NULL); + //hw_execute_bash_command("ip link set dev eth0 up", NULL); + //execute_bash_command("ip link set dev eth0 down", NULL); + + char szBuff[256]; + szBuff[0] = 0; + #ifdef HW_PLATFORM_RASPBERRY + sprintf(szBuff, "ifconfig %s %d.%d.%d.%d up &", pszETH, (pCS->uFixedIP >> 24 ) & 0xFF, (pCS->uFixedIP >> 16 ) & 0xFF, (pCS->uFixedIP >> 8 ) & 0xFF, pCS->uFixedIP & 0xFF ); + #endif + #ifdef HW_PLATFORM_RADXA_ZERO3 + sprintf(szBuff, "ip addr add %d.%d.%d.%d/24 dev %s", (pCS->uFixedIP >> 24 ) & 0xFF, (pCS->uFixedIP >> 16 ) & 0xFF, (pCS->uFixedIP >> 8 ) & 0xFF, pCS->uFixedIP & 0xFF, pszETH ); + #endif + if ( 0 != szBuff[0] ) + hw_execute_bash_command(szBuff, NULL); + log_line("Setting a fixed IP done."); + sprintf(szBuff, "ip r a default via 192.168.1.1 2>/dev/null"); + hw_execute_bash_command(szBuff, NULL); + + sprintf(szBuff, "ip link set %s up", pszETH); + hw_execute_bash_command(szBuff, NULL); + log_line("Added default ETH route done."); +} + int main(int argc, char *argv[]) { log_init("Ruby DHCP Init"); @@ -123,7 +161,7 @@ int main(int argc, char *argv[]) } log_line("Board type: %d -> %s", board_type, str_get_hardware_board_name(board_type)); - bool bHasETH = hardware_has_eth(); + bool bHasETH = ((hardware_has_eth() != NULL)?true:false); // DHCP if ( ( access( "/boot/nodhcp", R_OK ) != -1 ) || (!bHasETH) ) @@ -132,45 +170,25 @@ int main(int argc, char *argv[]) if ( ! bHasETH ) { - log_line("Pi with no ETH port: no ETH port to enable"); + log_line("SBC with no ETH port: no ETH port to enable"); return 0; } log_line("DHCP is disabled with /boot/nodhcp option."); if ( bIsStation ) - { - load_ControllerSettings(); - ControllerSettings* pCS = get_ControllerSettings(); - if ( pCS != NULL && pCS->nUseFixedIP != 0 ) - { - log_line("Setting a fixed IP."); - hw_execute_bash_command("export PATH=/usr/local/bin:${PATH}", NULL); - //hw_execute_bash_command("ip link set dev eth0 up", NULL); - //execute_bash_command("ip link set dev eth0 down", NULL); - - char szBuff[256]; - szBuff[0] = 0; - #ifdef HW_PLATFORM_RASPBERRY - sprintf(szBuff, "ifconfig eth0 %d.%d.%d.%d up &", (pCS->uFixedIP >> 24 ) & 0xFF, (pCS->uFixedIP >> 16 ) & 0xFF, (pCS->uFixedIP >> 8 ) & 0xFF, pCS->uFixedIP & 0xFF ); - #endif - #ifdef HW_PLATFORM_RADXA_ZERO3 - sprintf(szBuff, "ip addr add %d.%d.%d.%d/24 dev eth0", (pCS->uFixedIP >> 24 ) & 0xFF, (pCS->uFixedIP >> 16 ) & 0xFF, (pCS->uFixedIP >> 8 ) & 0xFF, pCS->uFixedIP & 0xFF ); - #endif - if ( 0 != szBuff[0] ) - hw_execute_bash_command(szBuff, NULL); - log_line("Setting a fixed IP done."); - sprintf(szBuff, "ip r a default via 192.168.1.1 2>/dev/null"); - hw_execute_bash_command(szBuff, NULL); - hw_execute_bash_command("ip link set eth0 up", NULL); - log_line("Added default ETH route done."); - } - } + _check_set_fixed_ip(); log_line("Done DHCP/ETH Configuration."); return 0; } - configureDHCP(); + #if defined HW_PLATFORM_RADXA_ZERO3 + _check_set_fixed_ip(); + #endif + #if defined HW_PLATFORM_RASPBERRY + configureDHCP(); + #endif + hw_execute_bash_command_raw("ls /sys/class/net/", szOutput); log_line("Network devices found: [%s]", szOutput); diff --git a/code/r_utils/ruby_update.cpp b/code/r_utils/ruby_update.cpp index 63a8e74a..21f8827f 100644 --- a/code/r_utils/ruby_update.cpp +++ b/code/r_utils/ruby_update.cpp @@ -10,9 +10,9 @@ * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - * Copyright info and developer info must be preserved as is in the user + * Copyright info and developer info must be preserved as is in the user interface, additions could be made to that info. - * Neither the name of the organization nor the + * Neither the name of the organization nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. * Military use is not permited. @@ -99,9 +99,96 @@ void update_openipc_cpu(Model* pModel) } -void do_update_to_99() +void do_update_to_101() { - log_line("Doing update to 9.9"); + log_line("Doing update to 10.1"); + + if ( ! s_isVehicle ) + { + load_ControllerSettings(); + ControllerSettings* pCS = get_ControllerSettings(); + pCS->nGraphRadioRefreshInterval = 50; + pCS->nGraphVideoRefreshInterval = 50; + pCS->iFixedTxPower = 0; + save_ControllerSettings(); + } + + Model* pModel = getCurrentModel(); + if ( NULL == pModel ) + return; + + pModel->resetVideoParamsToDefaults(); + pModel->resetVideoLinkProfiles(-1); + + pModel->processesPriorities.iNiceTelemetry = DEFAULT_PRIORITY_PROCESS_TELEMETRY; + pModel->processesPriorities.iNiceRouter = DEFAULT_PRIORITY_PROCESS_ROUTER; + #if defined (HW_PLATFORM_OPENIPC_CAMERA) + pModel->processesPriorities.iNiceTelemetry = DEFAULT_PRIORITY_PROCESS_TELEMETRY_OIPC; + pModel->processesPriorities.iNiceRouter = DEFAULT_PRIORITY_PROCESS_ROUTER_OPIC; + #endif + + #if defined (HW_PLATFORM_OPENIPC_CAMERA) + + if ( hardware_board_is_sigmastar(pModel->hwCapabilities.uBoardType & BOARD_TYPE_MASK) ) + { + pModel->processesPriorities.iFreqGPU = 0; + hardware_set_oipc_freq_boost(pModel->processesPriorities.iFreqARM, pModel->processesPriorities.iFreqGPU); + } + pModel->video_params.iH264Slices = DEFAULT_VIDEO_H264_SLICES_OIPC; + + if ( hardware_board_is_sigmastar(hardware_getOnlyBoardType()) ) + pModel->video_link_profiles[VIDEO_PROFILE_HIGH_QUALITY].bitrate_fixed_bps = DEFAULT_VIDEO_BITRATE_OPIC_SIGMASTAR; + + for( int i=0; ivideo_link_profiles[i].fps = DEFAULT_VIDEO_FPS_OIPC; + } + + #endif + + for( int i=0; ihwCapabilities.uBoardType) ) + pModel->video_link_profiles[i].uProfileEncodingFlags |= VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_KEYFRAME; + + pModel->video_link_profiles[i].keyframe_ms = DEFAULT_VIDEO_KEYFRAME; + if ( hardware_board_is_goke(hardware_getOnlyBoardType()) ) + pModel->video_link_profiles[i].keyframe_ms = DEFAULT_VIDEO_KEYFRAME_OIPC_GOKE; + if ( hardware_board_is_sigmastar(hardware_getOnlyBoardType()) ) + pModel->video_link_profiles[i].keyframe_ms = DEFAULT_VIDEO_KEYFRAME_OIPC_SIGMASTAR; + + pModel->video_link_profiles[i].h264profile = 2; // high + } + + for( int i=0; ivideo_link_profiles[i].iIPQuantizationDelta = DEFAULT_VIDEO_H264_IPQUANTIZATION_DELTA_HP; + } + pModel->video_link_profiles[VIDEO_PROFILE_HIGH_QUALITY].iIPQuantizationDelta = DEFAULT_VIDEO_H264_IPQUANTIZATION_DELTA_HQ; + pModel->video_link_profiles[VIDEO_PROFILE_USER].iIPQuantizationDelta = DEFAULT_VIDEO_H264_IPQUANTIZATION_DELTA_HQ; + + pModel->video_link_profiles[VIDEO_PROFILE_HIGH_QUALITY].uProfileEncodingFlags &= ~(VIDEO_PROFILE_ENCODING_FLAG_MAX_RETRANSMISSION_WINDOW_MASK); + pModel->video_link_profiles[VIDEO_PROFILE_HIGH_QUALITY].uProfileEncodingFlags |= (DEFAULT_VIDEO_RETRANS_MS5_HQ<<8); + pModel->video_link_profiles[VIDEO_PROFILE_BEST_PERF].uProfileEncodingFlags &= ~(VIDEO_PROFILE_ENCODING_FLAG_MAX_RETRANSMISSION_WINDOW_MASK); + pModel->video_link_profiles[VIDEO_PROFILE_BEST_PERF].uProfileEncodingFlags |= (DEFAULT_VIDEO_RETRANS_MS5_HP<<8); + pModel->video_link_profiles[VIDEO_PROFILE_USER].uProfileEncodingFlags &= ~(VIDEO_PROFILE_ENCODING_FLAG_MAX_RETRANSMISSION_WINDOW_MASK); + pModel->video_link_profiles[VIDEO_PROFILE_USER].uProfileEncodingFlags |= (DEFAULT_VIDEO_RETRANS_MS5_HP<<8); + pModel->video_link_profiles[VIDEO_PROFILE_MQ].uProfileEncodingFlags &= ~(VIDEO_PROFILE_ENCODING_FLAG_MAX_RETRANSMISSION_WINDOW_MASK); + pModel->video_link_profiles[VIDEO_PROFILE_MQ].uProfileEncodingFlags |= (DEFAULT_VIDEO_RETRANS_MS5_MQ<<8); + pModel->video_link_profiles[VIDEO_PROFILE_LQ].uProfileEncodingFlags &= ~(VIDEO_PROFILE_ENCODING_FLAG_MAX_RETRANSMISSION_WINDOW_MASK); + pModel->video_link_profiles[VIDEO_PROFILE_LQ].uProfileEncodingFlags |= (DEFAULT_VIDEO_RETRANS_MS5_LQ<<8); + + pModel->radioInterfacesParams.iAutoVehicleTxPower = 1; + pModel->radioInterfacesParams.iAutoControllerTxPower = 1; + + pModel->rxtx_sync_type = RXTX_SYNC_TYPE_BASIC; + + log_line("Updated model VID %u (%s) to v10.1", pModel->uVehicleId, pModel->getLongName()); +} + +void do_update_to_100() +{ + log_line("Doing update to 10.0"); if ( ! s_isVehicle ) { @@ -147,7 +234,7 @@ void do_update_to_99() } #endif - log_line("Updated model VID %u (%s) to v9.9", pModel->uVehicleId, pModel->getLongName()); + log_line("Updated model VID %u (%s) to v10.0", pModel->uVehicleId, pModel->getLongName()); } void do_update_to_98() @@ -274,14 +361,14 @@ void do_update_to_97() update_openipc_cpu(pModel); #endif - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) { - u32 uUsage = pModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF; + u32 uUsage = pModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF; if ( uUsage > 0 ) if ( uUsage < SERIAL_PORT_USAGE_MSP_OSD ) { - pModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] = pModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFFFFFF00; - pModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] |= SERIAL_PORT_USAGE_TELEMETRY_MAVLINK; + pModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] = pModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFFFFFF00; + pModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] |= SERIAL_PORT_USAGE_TELEMETRY_MAVLINK; } } @@ -861,7 +948,6 @@ void do_update_to_76() } for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) { - pModel->radioInterfacesParams.interface_dummy1[i] = 0; pModel->radioInterfacesParams.interface_dummy2[i] = 0; } @@ -1039,14 +1125,14 @@ void do_update_to_72() // pModel->osd_params.osd_flags3[i] = OSD_FLAG3_SHOW_GRID_DIAGONAL | OSD_FLAG3_SHOW_GRID_SQUARES; - if ( 0 < pModel->hardwareInterfacesInfo.serial_bus_count ) + if ( 0 < pModel->hardwareInterfacesInfo.serial_port_count ) if ( hardware_get_serial_ports_count() > 0 ) { hw_serial_port_info_t* pPortInfo = hardware_get_serial_port_info(0); if ( NULL != pPortInfo ) { - pPortInfo->lPortSpeed = pModel->hardwareInterfacesInfo.serial_bus_speed[0]; - pPortInfo->iPortUsage = (int)(pModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[0] & 0xFF); + pPortInfo->lPortSpeed = pModel->hardwareInterfacesInfo.serial_port_speed[0]; + pPortInfo->iPortUsage = (int)(pModel->hardwareInterfacesInfo.serial_port_supported_and_usage[0] & 0xFF); hardware_serial_save_configuration(); } } @@ -1147,11 +1233,11 @@ void do_update_to_70() validate_camera(pModel); pModel->populateVehicleSerialPorts(); - if ( 0 < pModel->hardwareInterfacesInfo.serial_bus_count ) + if ( 0 < pModel->hardwareInterfacesInfo.serial_port_count ) { - pModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[0] &= 0xFFFFFF00; - pModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[0] |= SERIAL_PORT_USAGE_TELEMETRY_MAVLINK; - pModel->hardwareInterfacesInfo.serial_bus_speed[0] = DEFAULT_FC_TELEMETRY_SERIAL_SPEED; + pModel->hardwareInterfacesInfo.serial_port_supported_and_usage[0] &= 0xFFFFFF00; + pModel->hardwareInterfacesInfo.serial_port_supported_and_usage[0] |= SERIAL_PORT_USAGE_TELEMETRY_MAVLINK; + pModel->hardwareInterfacesInfo.serial_port_speed[0] = DEFAULT_FC_TELEMETRY_SERIAL_SPEED; } } else @@ -1251,7 +1337,6 @@ void do_update_to_69() for( int i=0; iradioInterfacesParams.interface_dummy1[i] = 0; pModel->radioInterfacesParams.interface_dummy2[i] = 0; } @@ -1389,7 +1474,6 @@ void do_update_to_66() } for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) { - pModel->radioInterfacesParams.interface_dummy1[i] = 0; pModel->radioInterfacesParams.interface_dummy2[i] = 0; } if ( pModel->video_link_profiles[VIDEO_PROFILE_BEST_PERF].bitrate_fixed_bps > 5000000 ) @@ -1824,8 +1908,10 @@ int main(int argc, char *argv[]) do_update_to_97(); if ( (iMajor < 9) || (iMajor == 9 && iMinor <= 8) ) do_update_to_98(); - if ( (iMajor < 9) || (iMajor == 9 && iMinor <= 9) ) - do_update_to_99(); + if ( (iMajor < 10) || (iMajor == 10 && iMinor <= 0) ) + do_update_to_100(); + if ( (iMajor < 10) || (iMajor == 10 && iMinor <= 1) ) + do_update_to_101(); saveCurrentModel(); diff --git a/code/r_utils/ruby_update_worker.cpp b/code/r_utils/ruby_update_worker.cpp index d973cfe6..a28bd77c 100644 --- a/code/r_utils/ruby_update_worker.cpp +++ b/code/r_utils/ruby_update_worker.cpp @@ -47,6 +47,11 @@ bool gbQuit = false; +bool g_bIsController = true; +char g_szUpdateZipFileFullPath[MAX_FILE_PATH_SIZE]; +char g_szUpdateZipFileName[MAX_FILE_PATH_SIZE]; +char g_szUpdateUnpackFolder[MAX_FILE_PATH_SIZE]; + u32 g_TimeNow = 0; void handle_sigint(int sig) @@ -224,29 +229,28 @@ void _write_return_code(int iCode) log_softerror_and_alarm("Failed to write update result to file tmp/tmp_update_result.txt"); } -int _copy_binary_files(char* szInputUpdateFolder) +int _replace_runtime_binary_files() { - if ( (NULL == szInputUpdateFolder) || (0 == szInputUpdateFolder[0]) ) + if ( (0 == g_szUpdateUnpackFolder[0]) ) { log_line("Invalid function param for copy binary files."); _write_return_code(-10); return -1; } - char szComm[256]; + char szComm[MAX_FILE_PATH_SIZE]; char szSrcBinariesFolder[MAX_FILE_PATH_SIZE]; - strcpy(szSrcBinariesFolder, szInputUpdateFolder); #ifdef HW_PLATFORM_RASPBERRY - strcat(szSrcBinariesFolder, SUBFOLDER_UPDATES_PI); + snprintf(szSrcBinariesFolder, sizeof(szSrcBinariesFolder)/sizeof(szSrcBinariesFolder[0]), "%s%s", g_szUpdateUnpackFolder, SUBFOLDER_UPDATES_PI); #endif #ifdef HW_PLATFORM_RADXA_ZERO3 - strcat(szSrcBinariesFolder, SUBFOLDER_UPDATES_RADXA); + snprintf(szSrcBinariesFolder, sizeof(szSrcBinariesFolder)/sizeof(szSrcBinariesFolder[0]), "%s%s", g_szUpdateUnpackFolder, SUBFOLDER_UPDATES_RADXA); #endif #ifdef HW_PLATFORM_OPENIPC_CAMERA - strcat(szSrcBinariesFolder, SUBFOLDER_UPDATES_OIPC); + snprintf(szSrcBinariesFolder, sizeof(szSrcBinariesFolder)/sizeof(szSrcBinariesFolder[0]), "%s%s", g_szUpdateUnpackFolder, SUBFOLDER_UPDATES_OIPC); #endif - log_line("Check for binary files in source unzipped folder [%s] ...", szSrcBinariesFolder); + log_line("Check for binary files in unzipped folder [%s] ...", szSrcBinariesFolder); // Check if ruby binaries are present in folder char szFile[MAX_FILE_PATH_SIZE]; @@ -256,7 +260,7 @@ int _copy_binary_files(char* szInputUpdateFolder) { char szOutput[4096]; szOutput[0] = 0; - sprintf(szComm, "ls %s", szInputUpdateFolder); + snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "ls %s", g_szUpdateUnpackFolder); hw_execute_bash_command(szComm, szOutput); log_line("Content of tmp update folder:"); log_line("[%s]", szOutput); @@ -269,6 +273,8 @@ int _copy_binary_files(char* szInputUpdateFolder) snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %sruby_* %s", szSrcBinariesFolder, FOLDER_BINARIES); hw_execute_bash_command(szComm, NULL); + snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %sstop* %s 2>/dev/null", szSrcBinariesFolder, FOLDER_BINARIES); + hw_execute_bash_command(szComm, NULL); hardware_sleep_ms(50); hw_execute_bash_command("chmod 777 ruby*", NULL); @@ -284,23 +290,20 @@ int _copy_binary_files(char* szInputUpdateFolder) hw_execute_bash_command("cp -rf ruby_capture_veye307 /usr/local/bin/307/veye_raspivid", NULL); #endif - snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %sstop* %s 2>/dev/null", szSrcBinariesFolder, FOLDER_BINARIES); - hw_execute_bash_command(szComm, NULL); - return 0; } -int _copy_update_binary_files(char* szInputUpdateFolder) +int _copy_update_binary_files() { - if ( (NULL == szInputUpdateFolder) || (0 == szInputUpdateFolder[0]) ) + if ( 0 == g_szUpdateUnpackFolder[0] ) { log_line("Invalid function param for copy update binary files."); _write_return_code(-10); return -1; } - char szComm[256]; + char szComm[MAX_FILE_PATH_SIZE]; snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "rm -rf %sbin/", FOLDER_UPDATES); hw_execute_bash_command(szComm, NULL); @@ -308,14 +311,7 @@ int _copy_update_binary_files(char* szInputUpdateFolder) sprintf(szComm, "mkdir -p %sbin/", FOLDER_UPDATES); hw_execute_bash_command(szComm, NULL); - snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %sbin/* %sbin 2>/dev/null", szInputUpdateFolder, FOLDER_UPDATES); - hw_execute_bash_command(szComm, NULL); - - snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "chmod 777 %sbin/pi/* 2>/dev/null", FOLDER_UPDATES); - hw_execute_bash_command(szComm, NULL); - snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "chmod 777 %sbin/radxaz3/* 2>/dev/null", FOLDER_UPDATES); - hw_execute_bash_command(szComm, NULL); - snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "chmod 777 %sbin/ssc338q/* 2>/dev/null", FOLDER_UPDATES); + snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %sbin/* %sbin 2>/dev/null", g_szUpdateUnpackFolder, FOLDER_UPDATES); hw_execute_bash_command(szComm, NULL); snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "chmod 777 %s%s*", FOLDER_UPDATES, SUBFOLDER_UPDATES_PI); @@ -325,15 +321,18 @@ int _copy_update_binary_files(char* szInputUpdateFolder) snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "chmod 777 %s%s*", FOLDER_UPDATES, SUBFOLDER_UPDATES_OIPC); hw_execute_bash_command(szComm, NULL); + snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "chmod 777 %s%s*", FOLDER_UPDATES, SUBFOLDER_UPDATES_DRIVERS); + hw_execute_bash_command(szComm, NULL); + hardware_sleep_ms(50); return 0; } -int _copy_res_files(char* szInputUpdateFolder) +int _copy_res_files() { - if ( (NULL == szInputUpdateFolder) || (0 == szInputUpdateFolder[0]) ) + if ( 0 == g_szUpdateUnpackFolder[0] ) { log_line("Invalid function param for copy res files."); _write_return_code(-10); @@ -342,82 +341,36 @@ int _copy_res_files(char* szInputUpdateFolder) char szComm[256]; - snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %s%s %s%s 2>/dev/null", szInputUpdateFolder, FILE_INFO_SHORT_LAST_UPDATE, FOLDER_CONFIG, FILE_INFO_LAST_UPDATE); + snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %s%s %s%s 2>/dev/null", g_szUpdateUnpackFolder, FILE_INFO_SHORT_LAST_UPDATE, FOLDER_CONFIG, FILE_INFO_LAST_UPDATE); hw_execute_bash_command(szComm, NULL); - snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %sres/* %sres/ 2>/dev/null", szInputUpdateFolder, FOLDER_BINARIES); + snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %sres/* %sres/ 2>/dev/null", g_szUpdateUnpackFolder, FOLDER_BINARIES); hw_execute_bash_command(szComm, NULL); return 0; } -int _copy_update_drivers(char* szInputUpdateFolder) -{ - if ( (NULL == szInputUpdateFolder) || (0 == szInputUpdateFolder[0]) ) - { - log_line("Invalid function param for copy update drivers files."); - _write_return_code(-10); - return -1; - } - - char szDriver[MAX_FILE_PATH_SIZE]; - strcpy(szDriver, szInputUpdateFolder); - #ifdef HW_PLATFORM_RASPBERRY - strcat(szDriver, SUBFOLDER_UPDATES_PI); - strcat(szDriver, "drivers/8812eu_pi.ko"); - #endif - #ifdef HW_PLATFORM_RADXA_ZERO3 - strcat(szDriver, SUBFOLDER_UPDATES_RADXA); - strcat(szDriver, "drivers/8812eu_radxa.ko"); - #endif - #ifdef HW_PLATFORM_OPENIPC_CAMERA - strcat(szDriver, SUBFOLDER_UPDATES_OIPC); - strcat(szDriver, "drivers/8812eu.ko"); - #endif - - if ( access(szDriver, R_OK) != -1 ) - { - log_line("Found driver: (%s)", szDriver); - #ifdef HW_PLATFORM_RADXA_ZERO3 - char szComm[256]; - hw_execute_bash_command("sudo modprobe cfg80211", NULL); - snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %s /home/", szDriver); - hw_execute_bash_command(szComm, NULL); - snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %s /lib/modules/$(uname -r)/kernel/drivers/net/wireless/", szDriver); - hw_execute_bash_command(szComm, NULL); - hw_execute_bash_command("insmod /lib/modules/$(uname -r)/kernel/drivers/net/wireless/8812eu_radxa.ko rtw_tx_pwr_by_rate=0 rtw_tx_pwr_lmt_enable=0 2>&1 1>/dev/null", NULL); - #endif - } - else - log_line("No driver file found (%d)", szDriver); - - return 0; -} - -int _copy_plugin_files(char* szInputUpdateFolder) +int _copy_plugin_files() { - if ( (NULL == szInputUpdateFolder) || (0 == szInputUpdateFolder[0]) ) + if ( 0 == g_szUpdateUnpackFolder[0] ) { log_line("Invalid function param for copy plugin files."); _write_return_code(-10); return -1; } - char szComm[256]; - + char szComm[MAX_FILE_PATH_SIZE]; char szSrcPluginsFolder[MAX_FILE_PATH_SIZE]; - strcpy(szSrcPluginsFolder, szInputUpdateFolder); + #ifdef HW_PLATFORM_RASPBERRY - strcat(szSrcPluginsFolder, "plugins/"); + snprintf(szSrcPluginsFolder, sizeof(szSrcPluginsFolder)/sizeof(szSrcPluginsFolder[0]), "%s%splugins/", g_szUpdateUnpackFolder, SUBFOLDER_UPDATES_PI); #endif #ifdef HW_PLATFORM_RADXA_ZERO3 - strcat(szSrcPluginsFolder, SUBFOLDER_UPDATES_RADXA); - strcat(szSrcPluginsFolder, "plugins/"); + snprintf(szSrcPluginsFolder, sizeof(szSrcPluginsFolder)/sizeof(szSrcPluginsFolder[0]), "%s%splugins/", g_szUpdateUnpackFolder, SUBFOLDER_UPDATES_RADXA); #endif #ifdef HW_PLATFORM_OPENIPC_CAMERA - strcat(szSrcPluginsFolder, SUBFOLDER_UPDATES_OIPC); - strcat(szSrcPluginsFolder, "plugins/"); + snprintf(szSrcPluginsFolder, sizeof(szSrcPluginsFolder)/sizeof(szSrcPluginsFolder[0]), "%s%splugins/", g_szUpdateUnpackFolder, SUBFOLDER_UPDATES_OIPC); #endif log_line("Copying plugins files from source folder: (%s)", szSrcPluginsFolder); @@ -425,108 +378,120 @@ int _copy_plugin_files(char* szInputUpdateFolder) snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %s* %splugins/ 2>/dev/null", szSrcPluginsFolder, FOLDER_BINARIES); hw_execute_bash_command(szComm, NULL); - snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %sosd/* %splugins/osd 2>/dev/null", szSrcPluginsFolder, FOLDER_BINARIES); - hw_execute_bash_command(szComm, NULL); - hw_execute_bash_command("chmod 777 plugins/*", NULL); hw_execute_bash_command("chmod 777 plugins/osd/*", NULL); + hw_execute_bash_command("chmod 777 plugins/core/*", NULL); return 0; } -int _copy_config_files(char* szInputUpdateFolder) +int _copy_config_files() { - if ( (NULL == szInputUpdateFolder) || (0 == szInputUpdateFolder[0]) ) + if ( 0 == g_szUpdateUnpackFolder[0] ) { log_line("Invalid function param for copy config files."); _write_return_code(-10); return -1; } - + #ifdef HW_PLATFORM_RASPBERRY char szSourceFile[MAX_FILE_PATH_SIZE]; - - strcpy(szSourceFile, szInputUpdateFolder); - strcat(szSourceFile, "ruby_profile"); + snprintf(szSourceFile, sizeof(szSourceFile)/sizeof(szSourceFile[0]), "%s%sruby_profile", g_szUpdateUnpackFolder, SUBFOLDER_UPDATES_PI); if ( access( szSourceFile, R_OK ) != -1 ) { - #ifdef HW_PLATFORM_RASPBERRY - char szComm[256]; + char szComm[MAX_FILE_PATH_SIZE]; snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %s /root/.profile 2>/dev/null", szSourceFile); hw_execute_bash_command(szComm, NULL); hw_execute_bash_command("chmod 777 /root/.profile", NULL); - #endif } - strcpy(szSourceFile, szInputUpdateFolder); - strcat(szSourceFile, "ruby_config.txt"); + snprintf(szSourceFile, sizeof(szSourceFile)/sizeof(szSourceFile[0]), "%s%sruby_config.txt", g_szUpdateUnpackFolder, SUBFOLDER_UPDATES_PI); if ( access( szSourceFile, R_OK ) != -1 ) { - #ifdef HW_PLATFORM_RASPBERRY hardware_mount_boot(); hardware_sleep_ms(200); - char szComm[256]; + char szComm[MAX_FILE_PATH_SIZE]; snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %s /boot/config.txt 2>/dev/null", szSourceFile); hw_execute_bash_command(szComm, NULL); hw_execute_bash_command("chmod 777 /boot/config.txt", NULL); - #endif } + #endif return 0; } -int main(int argc, char *argv[]) -{ - signal(SIGINT, handle_sigint); - signal(SIGTERM, handle_sigint); - signal(SIGQUIT, handle_sigint); - if ( strcmp(argv[argc-1], "-ver") == 0 ) +int _copy_update_drivers() +{ + if ( 0 == g_szUpdateUnpackFolder[0] ) { - printf("%d.%d (b%d)", SYSTEM_SW_VERSION_MAJOR, SYSTEM_SW_VERSION_MINOR/10, SYSTEM_SW_BUILD_NUMBER); - return 0; + log_line("Invalid function param for copy update drivers files."); + _write_return_code(-10); + return -1; } + + char szDrivers[MAX_FILE_PATH_SIZE]; + + snprintf(szDrivers, sizeof(szDrivers)/sizeof(szDrivers[0]), "%s%s*", g_szUpdateUnpackFolder, SUBFOLDER_UPDATES_DRIVERS); - log_init("RubyUpdateWorker"); - hardware_sleep_ms(500); + char szComm[MAX_FILE_PATH_SIZE]; + snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "mkdir -p %s", FOLDER_DRIVERS); + hw_execute_bash_command(szComm, NULL); + snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "cp -rf %s %s 2>/dev/null", szDrivers, FOLDER_DRIVERS); + hw_execute_bash_command(szComm, NULL); + snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "chmod 777 %s*", FOLDER_DRIVERS); + hw_execute_bash_command(szComm, NULL); - char szComm[256]; - char szFile[MAX_FILE_PATH_SIZE]; - char szFoundUpdateFile[MAX_FILE_PATH_SIZE]; - char szZipFileName[MAX_FILE_PATH_SIZE]; - char szZipFullFilePath[MAX_FILE_PATH_SIZE]; + char szOutput[2048]; + szOutput[0] = 0; + snprintf(szComm, sizeof(szComm)/sizeof(szComm[0]), "find %s.ko 2>/dev/null", szDrivers); + hw_execute_bash_command(szComm, szOutput); + + if ( (0 < strlen(szOutput)) && (NULL != strstr(szOutput, ".ko")) ) + hardware_install_drivers(); + return 0; +} - szZipFileName[0] = 0; - szZipFullFilePath[0] = 0; - szFoundUpdateFile[0] = 0; - bool bIsController = (bool) hardware_is_station(); +bool _find_update_zip_file() +{ + char szComm[MAX_FILE_PATH_SIZE]; + char szOutput[1024]; - log_line("Executing update for %s...", bIsController?"station":"vehicle"); + g_szUpdateZipFileFullPath[0] = 0; + g_szUpdateZipFileName[0] = 0; - if ( bIsController ) + if ( g_bIsController ) sprintf(szComm, "find %sruby_update*.zip 2>/dev/null", FOLDER_USB_MOUNT); else sprintf(szComm, "find ruby_update*.zip 2>/dev/null"); - hw_execute_bash_command(szComm, szFoundUpdateFile); + hw_execute_bash_command(szComm, szOutput); - if ( (0 == strlen(szFoundUpdateFile)) || (NULL == strstr(szFoundUpdateFile, "ruby_update")) ) - { - if ( bIsController ) - log_line("There is no update update archive on the USB stick."); - else - log_line("There is no update update archive on the Ruby main folder."); + if ( (0 == strlen(szOutput)) || (NULL == strstr(szOutput, "ruby_update")) ) + return false; - _write_return_code(-1); - return -1; + int iLen = strlen(szOutput); + for( int i=0; i= s_TimeLastFPS+1000 ) { s_TimeLastFPS = s_Time; - if ( NULL != fdLog ) - { - fprintf(fdLog, "------------------------\nvsync: %d FPS, %d reads, %d tags found\n", s_iFPS, s_iFPSReads, s_iFPSSearchTagsFound); - fflush(fdLog); - } s_iFPS = 0; s_iFPSReads = 0; s_iFPSSearchTagsFound = 0; @@ -101,8 +95,13 @@ static int video_decode() int iPipeRead = -1; iPipeRead = open(szFileName, O_RDONLY); - if ( iPipeRead < 0 ) - return -1; + if( -1 == iPipeRead ) + { + log_error_and_alarm("Failed to open input file: (%s)", szFileName); + return EXIT_FAILURE; + } + + log_line("Opened file: [%s], fd=%d", szFileName, iPipeRead); // create video_decode if(ilclient_create_component(client, &video_decode, "video_decode", ILCLIENT_DISABLE_ALL_PORTS | ILCLIENT_ENABLE_INPUT_BUFFERS) != 0) @@ -129,8 +128,7 @@ static int video_decode() format.eCompressionFormat = OMX_VIDEO_CodingAVC; format.xFramerate = iFPS << 16; - if ( NULL != fdLog ) - fprintf(fdLog, "FPS: %d\n", iFPS); + log_line("FPS: %d", iFPS); if(status == 0 && OMX_SetParameter(ILC_GET_HANDLE(video_decode), OMX_IndexParamVideoPortFormat, &format) == OMX_ErrorNone && @@ -184,9 +182,7 @@ static int video_decode() } // end of: while (buf->nAllocLen - uBufferReadSize > 0 ) - if ( NULL != fdLog ) - fprintf(fdLog, "buff %d/%d bytes\n", buf->nAllocLen, uBufferReadSize); - + if ( iExit ) break; @@ -242,9 +238,6 @@ static int video_decode() } - if ( NULL != fdLog ) - fclose(fdLog); - if ( -1 != iPipeRead ) close(iPipeRead); @@ -265,30 +258,29 @@ static int video_decode() int main (int argc, char **argv) { - if ( strcmp(argv[argc-1], "-ver") == 0 ) { - printf("%d.%d (b%d)", 6,9,20); + printf("%d.%d (b%d)", 10,1,252); return 0; } if ( argc<3 ) return 0; + log_init("RubyVideoPlayer"); + iFPS = atoi(argv[argc-1]); if ( iFPS < 10 || iFPS > 120 ) iFPS = 30; strcpy(szFileName, argv[argc-2]); - bcm_host_init(); + bcm_host_init(); - //fdLog = fopen("tmp.log", "wb"); - fdLog = NULL; - display = vc_dispmanx_display_open( 0 ); - vc_dispmanx_vsync_callback(display, onVSync, NULL); - return video_decode(); + display = vc_dispmanx_display_open( 0 ); + vc_dispmanx_vsync_callback(display, onVSync, NULL); + return video_decode(); } diff --git a/code/r_utils/video.c.ruby_pipe b/code/r_utils/video.c.ruby10_pipe similarity index 77% rename from code/r_utils/video.c.ruby_pipe rename to code/r_utils/video.c.ruby10_pipe index 6f62600e..c29a3daf 100644 --- a/code/r_utils/video.c.ruby_pipe +++ b/code/r_utils/video.c.ruby10_pipe @@ -26,7 +26,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ // Video deocode demo using OpenMAX IL though the ilcient helper library - +// Build: /opt/vc/src/hello_pi/hello_video #include #include #include @@ -34,22 +34,12 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include +#include #include "bcm_host.h" #include "ilclient.h" - -void _log(const char* szText ) -{ - if ( NULL == szText ) - return; - - FILE* fd = fopen("/tmp/ruby_videoplayer.log", "ab"); - if ( NULL != fd ) - { - fprintf(fd, "%s\n", szText); - fclose(fd); - } -} +#include "base.h" static int video_decode() { @@ -83,39 +73,49 @@ static int video_decode() readfd = open(szFIFOName, O_RDONLY | O_NONBLOCK); if( -1 == readfd ) { - perror("failed readfd: open()"); + log_error_and_alarm("Failed to open input stream: (%s)", szFIFOName); return EXIT_FAILURE; } - char szLog[256]; - sprintf(szLog, "Opened fifo: [%s], fd=%d", szFIFOName, readfd); - _log(szLog); - + log_line("Opened fifo: [%s], fd=%d", szFIFOName, readfd); // create video_decode if(ilclient_create_component(client, &video_decode, "video_decode", ILCLIENT_DISABLE_ALL_PORTS | ILCLIENT_ENABLE_INPUT_BUFFERS) != 0) + { status = -14; + log_softerror_and_alarm("Failed to create video decoder component."); + } list[0] = video_decode; // create video_render if(status == 0 && ilclient_create_component(client, &video_render, "video_render", ILCLIENT_DISABLE_ALL_PORTS) != 0) + { status = -14; + log_softerror_and_alarm("Failed to create video renderer component."); + } list[1] = video_render; - set_tunnel(tunnel, video_decode, 131, video_render, 90); - - - if(status == 0) + if ( status == 0 ) + { + set_tunnel(tunnel, video_decode, 131, video_render, 90); ilclient_change_component_state(video_decode, OMX_StateIdle); + } + if ( status != 0 ) + { + log_softerror_and_alarm("Failed to initialize compontens. Aborting."); + goto exit; + } memset(&format, 0, sizeof(OMX_VIDEO_PARAM_PORTFORMATTYPE)); format.nSize = sizeof(OMX_VIDEO_PARAM_PORTFORMATTYPE); format.nVersion.nVersion = OMX_VERSION; format.nPortIndex = 130; format.eCompressionFormat = OMX_VIDEO_CodingAVC; + log_line("Initialized components."); + if(status == 0 && OMX_SetParameter(ILC_GET_HANDLE(video_decode), OMX_IndexParamVideoPortFormat, &format) == OMX_ErrorNone && ilclient_enable_port_buffers(video_decode, 130, NULL, NULL, NULL) == 0) @@ -126,33 +126,32 @@ static int video_decode() ilclient_change_component_state(video_decode, OMX_StateExecuting); + fd_set selectReadSet; + struct timeval selectTimeInterval; while((buf = ilclient_get_input_buffer(video_decode, 130, 1)) != NULL) { // feed data and wait until we get port settings changed unsigned char *dest = buf->pBuffer; data_len = 0; + while (data_len == 0) { + FD_ZERO(&selectReadSet); + FD_SET(readfd, &selectReadSet); + selectTimeInterval.tv_sec = 0; + selectTimeInterval.tv_usec = 10000; // 10 milisec timeout - int read_count = read(readfd, dest, buf->nAllocLen-data_len); - //if ( read_count > 0 ) - //{ - // sprintf(szLog, "read %d of %d", read_count, buf->nAllocLen-data_len); - // _log(szLog); - //} - //if ( read_count < 0 ) - //{ - // iExit = 1; - // break; - //} - if ( read_count <= 0 ) + int iSelect = select(readfd+1, &selectReadSet, NULL, NULL, &selectTimeInterval); + + if ( (iSelect > 0) && (FD_ISSET(readfd, &selectReadSet)) ) { - struct timespec to_sleep = { 0, (long int)(2*1000*1000) }; - nanosleep(&to_sleep, NULL); + //int iCountReady = 0; + //ioctl(readfd, FIONREAD, &iCountReady); + int read_count = read(readfd, dest, buf->nAllocLen-data_len); + if ( read_count > 0 ) + data_len += read_count; } - else - data_len += read_count; } if ( iExit ) break; @@ -206,14 +205,16 @@ static int video_decode() ilclient_flush_tunnels(tunnel, 0); } - - if ( readfd != -1 ) - close(readfd); ilclient_disable_tunnel(tunnel); ilclient_disable_port_buffers(video_decode, 130, NULL, NULL, NULL); ilclient_teardown_tunnels(tunnel); +exit: + + if ( readfd != -1 ) + close(readfd); + ilclient_state_transition(list, OMX_StateIdle); ilclient_state_transition(list, OMX_StateLoaded); @@ -227,34 +228,36 @@ static int video_decode() int main (int argc, char **argv) { + if ( strcmp(argv[argc-1], "-ver") == 0 ) + { + printf("%d.%d (b%d)", 10,1,253); + return 0; + } + bcm_host_init(); - char szLog[128]; + log_init("RubyVideoStreamer"); + pthread_t this_thread = pthread_self(); struct sched_param params; int policy = 0; int ret = 0; ret = pthread_getschedparam(this_thread, &policy, ¶ms); if ( ret != 0 ) - sprintf(szLog, "Failed to get schedule param"); + log_softerror_and_alarm("Failed to get schedule param"); else - sprintf(szLog, "Current thread policy/priority: %d/%d", policy, params.sched_priority); - _log(szLog); + log_line("Current thread policy/priority: %d/%d", policy, params.sched_priority); params.sched_priority = 50; ret = pthread_setschedparam(this_thread, SCHED_FIFO, ¶ms); if ( ret != 0 ) - { - sprintf(szLog, "Failed to set thread schedule class, error: %d, %s", errno, strerror(errno)); - _log(szLog); - } + log_softerror_and_alarm("Failed to set thread schedule class, error: %d, %s", errno, strerror(errno)); ret = pthread_getschedparam(this_thread, &policy, ¶ms); if ( ret != 0 ) - sprintf(szLog, "Failed to get schedule param"); + log_softerror_and_alarm("Failed to get schedule param"); else - sprintf(szLog, "Current new thread policy/priority: %d/%d", policy, params.sched_priority); - _log(szLog); + log_line("Current new thread policy/priority: %d/%d", policy, params.sched_priority); return video_decode(); } diff --git a/code/r_vehicle/adaptive_video.cpp b/code/r_vehicle/adaptive_video.cpp index 98b35cd9..d0925f7f 100644 --- a/code/r_vehicle/adaptive_video.cpp +++ b/code/r_vehicle/adaptive_video.cpp @@ -53,6 +53,7 @@ int s_iPendingAdaptiveRadioDataRate = 0; u32 s_uTimeSetPendingAdaptiveRadioDataRate = 0; u32 s_uLastAdaptiveAppliedVideoBitrate = 0; +int s_iLastIPQuantizationSet = -1000; void adaptive_video_init() { @@ -95,6 +96,16 @@ void adaptive_video_set_last_profile_requested_by_controller(int iVideoProfile) if ( g_pCurrentModel->isActiveCameraOpenIPC() ) video_source_majestic_set_videobitrate_value(uBitrateBPS); } + + // Update IP quantization delta + if ( g_pCurrentModel->hasCamera() ) + if ( g_pCurrentModel->isActiveCameraOpenIPC() ) + if ( s_iLastIPQuantizationSet != g_pCurrentModel->video_link_profiles[iVideoProfile].iIPQuantizationDelta ) + { + s_iLastIPQuantizationSet = g_pCurrentModel->video_link_profiles[iVideoProfile].iIPQuantizationDelta; + video_source_majestic_set_qpdelta_value(s_iLastIPQuantizationSet); + } + // Update adaptive video rate for tx radio: if ( s_uLastVideoProfileRequestedByController == g_pCurrentModel->video_params.user_selected_video_link_profile ) @@ -173,6 +184,7 @@ bool _adaptive_video_send_kf_to_capture_program(u16 uNewKeyframeMs) void adaptive_video_on_capture_restarted() { s_uLastAdaptiveAppliedVideoBitrate = 0; + s_iLastIPQuantizationSet = -1000; } void adaptive_video_on_new_camera_read(bool bEndOfFrame, bool bIsInsideIFrame) @@ -203,14 +215,7 @@ void adaptive_video_periodic_loop() if ( g_TimeNow < s_uTimeLastTimeAdaptivePeriodicLoop + 10 ) return; if ( g_bNegociatingRadioLinks ) - { - if ( g_TimeNow > g_uTimeStartNegociatingRadioLinks + 60*1000 ) - { - g_uTimeStartNegociatingRadioLinks = 0; - g_bNegociatingRadioLinks = false; - } return; - } s_uTimeLastTimeAdaptivePeriodicLoop = g_TimeNow; diff --git a/code/r_vehicle/hw_config_check.cpp b/code/r_vehicle/hw_config_check.cpp index 753f99ae..7468302f 100644 --- a/code/r_vehicle/hw_config_check.cpp +++ b/code/r_vehicle/hw_config_check.cpp @@ -137,7 +137,7 @@ bool _check_update_hardware_one_interface_after_and_before(Model* pModel) pModel->radioInterfacesParams.interface_current_frequency_khz[0] = pModel->radioLinksParams.link_frequency_khz[0]; pModel->radioInterfacesParams.interface_current_radio_flags[0] = pModel->radioLinksParams.link_radio_flags[0]; - pModel->radioInterfacesParams.interface_dummy1[0] = 0; + pModel->radioInterfacesParams.interface_raw_power[0] = DEFAULT_RADIO_TX_POWER; pModel->radioInterfacesParams.interface_dummy2[0] = 0; log_line("[HW Radio Check] Radio hardware check: Updated radio links based on current hardware radio interfaces. Completed."); @@ -207,7 +207,7 @@ bool _check_update_hardware_one_interface_after_multiple_before(Model* pModel) pModel->radioInterfacesParams.interface_link_id[0] = 0; pModel->radioInterfacesParams.interface_current_frequency_khz[0] = pModel->radioLinksParams.link_frequency_khz[0]; pModel->radioInterfacesParams.interface_current_radio_flags[0] = pModel->radioLinksParams.link_radio_flags[0]; - pModel->radioInterfacesParams.interface_dummy1[0] = 0; + pModel->radioInterfacesParams.interface_raw_power[0] = DEFAULT_RADIO_TX_POWER; pModel->radioInterfacesParams.interface_dummy2[0] = 0; pModel->radioInterfacesParams.interface_radiotype_and_driver[0] = (pRadioInfo->iRadioType & 0xFF) | ((pRadioInfo->iRadioDriver << 8) & 0xFF00); @@ -247,7 +247,6 @@ bool _check_update_hardware_one_interface_after_multiple_before(Model* pModel) pModel->radioInterfacesParams.interface_link_id[0] = 0; pModel->radioInterfacesParams.interface_current_frequency_khz[0] = pModel->radioLinksParams.link_frequency_khz[0]; pModel->radioInterfacesParams.interface_current_radio_flags[0] = pModel->radioLinksParams.link_radio_flags[0]; - pModel->radioInterfacesParams.interface_dummy1[0] = 0; pModel->radioInterfacesParams.interface_dummy2[0] = 0; pModel->radioInterfacesParams.interface_radiotype_and_driver[0] = (pRadioInfo->iRadioType & 0xFF) | ((pRadioInfo->iRadioDriver << 8) & 0xFF00); @@ -497,9 +496,9 @@ bool check_update_hardware_nics_vehicle(Model* pModel) pModel->radioInterfacesParams.interface_link_id[i] = pModel->radioInterfacesParams.interface_link_id[k]; pModel->radioInterfacesParams.interface_link_id[k] = tmp; - tmp = pModel->radioInterfacesParams.interface_power[i]; - pModel->radioInterfacesParams.interface_power[i] = pModel->radioInterfacesParams.interface_power[k]; - pModel->radioInterfacesParams.interface_power[k] = tmp; + tmp = pModel->radioInterfacesParams.interface_raw_power[i]; + pModel->radioInterfacesParams.interface_raw_power[i] = pModel->radioInterfacesParams.interface_raw_power[k]; + pModel->radioInterfacesParams.interface_raw_power[k] = tmp; u = pModel->radioInterfacesParams.interface_radiotype_and_driver[i]; pModel->radioInterfacesParams.interface_radiotype_and_driver[i] = pModel->radioInterfacesParams.interface_radiotype_and_driver[k]; @@ -529,9 +528,9 @@ bool check_update_hardware_nics_vehicle(Model* pModel) pModel->radioInterfacesParams.interface_current_radio_flags[i] = pModel->radioInterfacesParams.interface_current_radio_flags[k]; pModel->radioInterfacesParams.interface_current_radio_flags[k] = u; - tmp = pModel->radioInterfacesParams.interface_dummy1[i]; - pModel->radioInterfacesParams.interface_dummy1[i] = pModel->radioInterfacesParams.interface_dummy1[k]; - pModel->radioInterfacesParams.interface_dummy1[k] = tmp; + tmp = pModel->radioInterfacesParams.interface_raw_power[i]; + pModel->radioInterfacesParams.interface_raw_power[i] = pModel->radioInterfacesParams.interface_raw_power[k]; + pModel->radioInterfacesParams.interface_raw_power[k] = tmp; tmp = pModel->radioInterfacesParams.interface_dummy2[i]; pModel->radioInterfacesParams.interface_dummy2[i] = pModel->radioInterfacesParams.interface_dummy2[k]; @@ -580,7 +579,7 @@ bool check_update_hardware_nics_vehicle(Model* pModel) pModel->radioInterfacesParams.interface_card_model[i] = pRadioInfo->iCardModel; pModel->radioInterfacesParams.interface_current_frequency_khz[i] = 0; pModel->radioInterfacesParams.interface_current_radio_flags[i] = 0; - pModel->radioInterfacesParams.interface_dummy1[i] = 0; + pModel->radioInterfacesParams.interface_raw_power[i] = DEFAULT_RADIO_TX_POWER; pModel->radioInterfacesParams.interface_dummy2[i] = 0; pModel->radioInterfacesParams.interface_radiotype_and_driver[i] = (pRadioInfo->iRadioType & 0xFF) | ((pRadioInfo->iRadioDriver << 8) & 0xFF00); diff --git a/code/r_vehicle/packets_utils.cpp b/code/r_vehicle/packets_utils.cpp index b2ed0493..4fccb4a6 100644 --- a/code/r_vehicle/packets_utils.cpp +++ b/code/r_vehicle/packets_utils.cpp @@ -440,25 +440,12 @@ bool _send_packet_to_wifi_radio_interface(int iLocalRadioLinkId, int iRadioInter } */ -/* To remove "DEBUG" - t_packet_header* pPH = (t_packet_header*)pPacketData; - if ( pPH->packet_type == PACKET_TYPE_VIDEO_DATA_98 ) - { - static FILE* sfp2 = NULL; - if (NULL == sfp2 ) - sfp2 = fopen("out4.h264", "wb"); - u16 uTmp = 0; - memcpy(&uTmp, pPacketData + sizeof(t_packet_header) + sizeof(t_packet_header_video_full_98), sizeof(u16)); - t_packet_header_video_full_98* pCurrentVideoPacketHeader = (t_packet_header_video_full_98*)(pPacketData + sizeof(t_packet_header)); - if ( pCurrentVideoPacketHeader->uCurrentBlockPacketIndex < 9 ) - if ( pCurrentVideoPacketHeader->uCurrentBlockIndex > 20 ) - if ( pCurrentVideoPacketHeader->uCurrentBlockIndex % 200 ) - fwrite( pPacketData + sizeof(t_packet_header) + sizeof(t_packet_header_video_full_98)+sizeof(u16), 1, pPH->total_length - sizeof(t_packet_header) - sizeof(t_packet_header_video_full_98) - sizeof(u16), sfp2 ); - } -*/ int totalLength = radio_build_new_raw_packet(iLocalRadioLinkId, s_RadioRawPacket, pPacketData, nPacketLength, RADIO_PORT_ROUTER_DOWNLINK, be); u32 microT1 = get_current_timestamp_micros(); + u32 uPacketType = 0; + u32 uStreamId = 0; + int iSinglePacketLength = 0; if ( radio_write_raw_packet(iRadioInterfaceIndex, s_RadioRawPacket, totalLength) ) { @@ -482,13 +469,24 @@ bool _send_packet_to_wifi_radio_interface(int iLocalRadioLinkId, int iRadioInter while ( nLength > 0 ) { t_packet_header* pPH = (t_packet_header*)pData; - u32 uStreamId = (pPH->stream_packet_idx) >> PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; - + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pData; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + uStreamId = (pPHC->stream_packet_idx) >> PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + uPacketType = pPHC->packet_type; + iSinglePacketLength = pPHC->total_length; + } + else + { + uStreamId = (pPH->stream_packet_idx) >> PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + uPacketType = pPH->packet_type; + iSinglePacketLength = pPH->total_length; + } iCountChainedPackets[uStreamId]++; - iTotalBytesOnEachStream[uStreamId] += pPH->total_length; + iTotalBytesOnEachStream[uStreamId] += iSinglePacketLength; - nLength -= pPH->total_length; - pData += pPH->total_length; + nLength -= iSinglePacketLength; + pData += iSinglePacketLength; } for( int i=0; ipacket_type), nPacketLength, totalLength); - + log_softerror_and_alarm("Failed to write to radio interface %d (type %s, size: %d bytes, raw: %d bytes)", + iRadioInterfaceIndex+1, + str_get_packet_type(uPacketType), nPacketLength, totalLength); return false; } diff --git a/code/r_vehicle/periodic_loop.cpp b/code/r_vehicle/periodic_loop.cpp index 0dbb751e..a84a8aea 100644 --- a/code/r_vehicle/periodic_loop.cpp +++ b/code/r_vehicle/periodic_loop.cpp @@ -52,7 +52,6 @@ #include "test_link_params.h" #include "packets_utils.h" #include "processor_relay.h" -#include "utils_vehicle.h" #include "launchers_vehicle.h" #include "video_source_csi.h" @@ -99,7 +98,7 @@ static void * _reinit_sik_thread_func(void *ignored_argument) { uFreqKhz = g_pCurrentModel->radioLinksParams.link_frequency_khz[iRadioLink]; uDataRate = g_pCurrentModel->radioLinksParams.link_datarate_data_bps[iRadioLink]; - uTxPower = g_pCurrentModel->radioInterfacesParams.txPowerSiK; + uTxPower = g_pCurrentModel->radioInterfacesParams.interface_raw_power[g_SiKRadiosState.iMustReconfigureSiKInterfaceIndex]; uECC = (g_pCurrentModel->radioLinksParams.link_radio_flags[iRadioLink] & RADIO_FLAGS_SIK_ECC)? 1:0; uLBT = (g_pCurrentModel->radioLinksParams.link_radio_flags[iRadioLink] & RADIO_FLAGS_SIK_LBT)? 1:0; uMCSTR = (g_pCurrentModel->radioLinksParams.link_radio_flags[iRadioLink] & RADIO_FLAGS_SIK_MCSTR)? 1:0; @@ -906,6 +905,14 @@ int periodicLoop() _periodic_update_radio_stats(); + + if ( g_bNegociatingRadioLinks ) + if ( (g_TimeNow > g_uTimeStartNegociatingRadioLinks + 60*1000) || (g_TimeNow > g_uTimeLastNegociateRadioLinksCommand + 4000) ) + { + g_uTimeStartNegociatingRadioLinks = 0; + g_bNegociatingRadioLinks = false; + } + //_periodic_loop_check_ping(); int iMaxRxQuality = 0; diff --git a/code/r_vehicle/process_local_packets.cpp b/code/r_vehicle/process_local_packets.cpp index fc93c24f..6617e27b 100644 --- a/code/r_vehicle/process_local_packets.cpp +++ b/code/r_vehicle/process_local_packets.cpp @@ -44,7 +44,6 @@ #include "../common/string_utils.h" #include "process_local_packets.h" #include "processor_tx_video.h" -#include "utils_vehicle.h" #include "../radio/radiopackets2.h" #include "../radio/radiolink.h" @@ -57,7 +56,7 @@ #include "shared_vars.h" #include "timers.h" #include "ruby_rt_vehicle.h" -#include "utils_vehicle.h" +#include "../utils/utils_vehicle.h" #include "launchers_vehicle.h" #include "radio_links.h" #include "processor_tx_video.h" @@ -368,11 +367,9 @@ void _process_local_notification_model_changed(t_packet_header* pPH, int changeT if ( changeType == MODEL_CHANGED_RADIO_POWERS ) { - log_line("Tx powers before updating local model: RTL8812AU: %d, RTL8812EU: %d, Atheros: %d, SiK: %d", - g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU, - g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU, - g_pCurrentModel->radioInterfacesParams.txPowerAtheros, - g_pCurrentModel->radioInterfacesParams.txPowerSiK); + log_line("Tx powers before updating local model:"); + for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) + log_line("Radio interface %d current tx power raw: %d", i+1, g_pCurrentModel->radioInterfacesParams.interface_raw_power[i]); } // Reload model first @@ -801,9 +798,23 @@ void _process_local_notification_model_changed(t_packet_header* pPH, int changeT if ( changeType == MODEL_CHANGED_USER_SELECTED_VIDEO_PROFILE ) { log_line("Received local notification that the user selected video profile has changed."); -// To fix -// g_SM_VideoLinkStats.overwrites.userVideoLinkProfile = g_pCurrentModel->video_params.user_selected_video_link_profile; -//To fix video_stats_overwrites_reset_to_highest_level(); + + int iIPQuantizationDelta = g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].iIPQuantizationDelta; + int iIPQuantizationDeltaNew = iExtraParam - 100; + char szProfile[64]; + strcpy(szProfile, str_get_video_profile_name(adaptive_video_get_current_active_video_profile())); + log_line("Received local notification that video IP quantization delta was changed by user (from %d to %d) (current video profile: %s, user selected video profile: %s", + iIPQuantizationDelta, + iIPQuantizationDeltaNew, + szProfile, + str_get_video_profile_name(g_pCurrentModel->video_params.user_selected_video_link_profile)); + + if ( adaptive_video_get_current_active_video_profile() == g_pCurrentModel->video_params.user_selected_video_link_profile ) + { + if ( g_pCurrentModel->hasCamera() ) + if ( g_pCurrentModel->isActiveCameraOpenIPC() ) + video_source_majestic_set_qpdelta_value(iIPQuantizationDeltaNew); + } } if ( changeType == MODEL_CHANGED_RADIO_LINK_CAPABILITIES ) @@ -825,15 +836,22 @@ void _process_local_notification_model_changed(t_packet_header* pPH, int changeT if ( changeType == MODEL_CHANGED_RADIO_POWERS ) { log_line("Received local notification that radio powers have changed."); - log_line("Tx powers after updating local model: RTL8812AU: %d, RTL8812EU: %d, Atheros: %d, SiK: %d", - g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU, - g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU, - g_pCurrentModel->radioInterfacesParams.txPowerAtheros, - g_pCurrentModel->radioInterfacesParams.txPowerSiK); + log_line("Tx powers after updating local model:"); + int iSikRadioIndexToUpdate = -1; + for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) + { + log_line("Radio interface %d current tx power raw: %d (old %d)", i+1, g_pCurrentModel->radioInterfacesParams.interface_raw_power[i], oldRadioInterfacesParams.interface_raw_power[i]); + if ( hardware_radio_index_is_sik_radio(i) ) + if ( g_pCurrentModel->radioInterfacesParams.interface_raw_power[i] != oldRadioInterfacesParams.interface_raw_power[i] ) + iSikRadioIndexToUpdate = i; + } + + apply_vehicle_tx_power_levels(g_pCurrentModel); - if ( g_pCurrentModel->radioInterfacesParams.txPowerSiK != oldRadioInterfacesParams.txPowerSiK ) + if ( -1 != iSikRadioIndexToUpdate ) { - log_line("SiK radio interfaces tx power was changed from %d to %d. Updating SiK radio interfaces...", oldRadioInterfacesParams.txPowerSiK, g_pCurrentModel->radioInterfacesParams.txPowerSiK ); + log_line("SiK radio interface %d tx power was changed from %d to %d. Updating SiK radio interfaces...", + iSikRadioIndexToUpdate+1, oldRadioInterfacesParams.interface_raw_power[iSikRadioIndexToUpdate], g_pCurrentModel->radioInterfacesParams.interface_raw_power[iSikRadioIndexToUpdate] ); if ( g_SiKRadiosState.bConfiguringToolInProgress ) { @@ -863,7 +881,7 @@ void _process_local_notification_model_changed(t_packet_header* pPH, int changeT sprintf(szCommand, "rm -rf %s%s", FOLDER_RUBY_TEMP, FILE_TEMP_SIK_CONFIG_FINISHED); hw_execute_bash_command(szCommand, NULL); - sprintf(szCommand, "./ruby_sik_config none 0 -power %d &", g_pCurrentModel->radioInterfacesParams.txPowerSiK); + sprintf(szCommand, "./ruby_sik_config none 0 -power %d &", g_pCurrentModel->radioInterfacesParams.interface_raw_power[iSikRadioIndexToUpdate]); hw_execute_bash_command(szCommand, NULL); return; } @@ -895,7 +913,8 @@ void _process_local_notification_model_changed(t_packet_header* pPH, int changeT radio_hw_info_t* pRadioHWInfo = hardware_get_radio_info(i); if ( NULL == pRadioHWInfo ) continue; - + if ( ! hardware_radio_driver_is_atheros_card(pRadioHWInfo->iRadioDriver) ) + continue; int nRateTx = g_pCurrentModel->radioLinksParams.link_datarate_video_bps[iRadioLink]; update_atheros_card_datarate(g_pCurrentModel, i, nRateTx, g_pProcessStats); g_TimeNow = get_current_timestamp_ms(); @@ -908,6 +927,9 @@ void _process_local_notification_model_changed(t_packet_header* pPH, int changeT log_line("Received local notification that adaptive video link capabilities changed."); bMustSignalOtherComponents = false; bMustReinitVideo = false; + + adaptive_video_on_capture_restarted(); + adaptive_video_set_last_profile_requested_by_controller(g_pCurrentModel->video_params.user_selected_video_link_profile); //bool bUseAdaptiveVideo = ((g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags) & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_LINK)?true:false; //if ( (! bOldUseAdaptiveVideo) && bUseAdaptiveVideo ) @@ -960,6 +982,27 @@ void _process_local_notification_model_changed(t_packet_header* pPH, int changeT return; } + if ( changeType == MODEL_CHANGED_VIDEO_IPQUANTIZATION_DELTA ) + { + int iIPQuantizationDelta = g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].iIPQuantizationDelta; + int iIPQuantizationDeltaNew = iExtraParam - 100; + char szProfile[64]; + strcpy(szProfile, str_get_video_profile_name(adaptive_video_get_current_active_video_profile())); + log_line("Received local notification that video IP quantization delta was changed by user (from %d to %d) (current video profile: %s, user selected video profile: %s", + iIPQuantizationDelta, + iIPQuantizationDeltaNew, + szProfile, + str_get_video_profile_name(g_pCurrentModel->video_params.user_selected_video_link_profile)); + + if ( adaptive_video_get_current_active_video_profile() == g_pCurrentModel->video_params.user_selected_video_link_profile ) + { + if ( g_pCurrentModel->hasCamera() ) + if ( g_pCurrentModel->isActiveCameraOpenIPC() ) + video_source_majestic_set_qpdelta_value(iIPQuantizationDeltaNew); + } + return; + } + if ( changeType == MODEL_CHANGED_SIK_FREQUENCY ) { log_line("Received local notification that a SiK radio frequency was changed. Updating SiK interfaces..."); diff --git a/code/r_vehicle/process_radio_in_packets.cpp b/code/r_vehicle/process_radio_in_packets.cpp index 6434943d..d3129e81 100644 --- a/code/r_vehicle/process_radio_in_packets.cpp +++ b/code/r_vehicle/process_radio_in_packets.cpp @@ -80,6 +80,9 @@ void _try_decode_controller_links_stats_from_packet(u8* pPacketData, int packetL { t_packet_header* pPH = (t_packet_header*)pPacketData; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + return; + bool bHasControllerData = false; u8* pData = NULL; //int dataLength = 0; @@ -265,7 +268,11 @@ int _handle_received_packet_error(int iInterfaceIndex, u8* pData, int nDataLengt if ( iRadioError == RADIO_PROCESSING_ERROR_CODE_INVALID_CRC_RECEIVED ) { t_packet_header* pPH = (t_packet_header*)pData; - pPH->vehicle_id_src = 0; + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pData; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + pPHC->vehicle_id_src = 0; + else + pPH->vehicle_id_src = 0; int nPacketLength = packet_process_and_check(iInterfaceIndex, pData, nDataLength, pCRCOk); if ( nPacketLength > 0 ) @@ -305,6 +312,29 @@ int _handle_received_packet_error(int iInterfaceIndex, u8* pData, int nDataLengt void process_received_single_radio_packet(int iRadioInterface, u8* pData, int dataLength ) { t_packet_header* pPH = (t_packet_header*)pData; + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pData; + + u32 uVehicleIdSrc = 0; + u32 uVehicleIdDest = 0; + u8 uPacketType = 0; + u8 uPacketFlags = 0; + + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + uVehicleIdSrc = pPHC->vehicle_id_src; + uVehicleIdDest = pPHC->vehicle_id_dest; + uPacketType = pPHC->packet_type; + uPacketFlags = pPHC->packet_flags; + uPacketFlags &= ~(PACKET_FLAGS_MASK_MODULE); + uPacketFlags |= pPHC->uExtraBits & PACKET_FLAGS_MASK_MODULE; + } + else + { + uVehicleIdSrc = pPH->vehicle_id_src; + uVehicleIdDest = pPH->vehicle_id_dest; + uPacketType = pPH->packet_type; + uPacketFlags = pPH->packet_flags; + } if ( NULL != g_pProcessStats ) g_pProcessStats->lastRadioRxTime = g_TimeNow; @@ -347,11 +377,11 @@ void process_received_single_radio_packet(int iRadioInterface, u8* pData, int da { log_line("[Relay-RadioIn] Started for first time to receive data on the relay link (radio link %d, expected relayed VID: %u), from VID: %u, packet type: %s, current relay mode: %s", iRadioLinkId+1, g_pCurrentModel->relay_params.uRelayedVehicleId, - pPH->vehicle_id_src, str_get_packet_type(pPH->packet_type), str_format_relay_mode(g_pCurrentModel->relay_params.uCurrentRelayMode)); + uVehicleIdSrc, str_get_packet_type(uPacketType), str_format_relay_mode(g_pCurrentModel->relay_params.uCurrentRelayMode)); s_bFirstTimeReceivedDataOnRelayLink = false; } - if ( pPH->vehicle_id_src != g_pCurrentModel->relay_params.uRelayedVehicleId ) + if ( uVehicleIdSrc != g_pCurrentModel->relay_params.uRelayedVehicleId ) return; // Process packets received on relay links separately @@ -362,7 +392,7 @@ void process_received_single_radio_packet(int iRadioInterface, u8* pData, int da // Detect if it's a relayed packet from controller to relayed vehicle if ( (NULL != g_pCurrentModel) && (g_pCurrentModel->relay_params.isRelayEnabledOnRadioLinkId >= 0) ) - if ( pPH->vehicle_id_dest == g_pCurrentModel->relay_params.uRelayedVehicleId ) + if ( uVehicleIdDest == g_pCurrentModel->relay_params.uRelayedVehicleId ) { _mark_link_from_controller_present(); @@ -371,20 +401,22 @@ void process_received_single_radio_packet(int iRadioInterface, u8* pData, int da } #ifdef FEATURE_VEHICLE_COMPUTES_ADAPTIVE_VIDEO - if ( (((pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RUBY ) && (pPH->packet_type == PACKET_TYPE_RUBY_PING_CLOCK)) || - (((pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) && (pPH->packet_type == PACKET_TYPE_VIDEO_REQ_MULTIPLE_PACKETS)) || - (((pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) && (pPH->packet_type == PACKET_TYPE_VIDEO_REQ_MULTIPLE_PACKETS2)) ) + if ( (((uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RUBY ) && (uPacketType == PACKET_TYPE_RUBY_PING_CLOCK)) || + (((uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) && (uPacketType == PACKET_TYPE_VIDEO_REQ_MULTIPLE_PACKETS)) || + (((uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) && (uPacketType == PACKET_TYPE_VIDEO_REQ_MULTIPLE_PACKETS2)) ) _try_decode_controller_links_stats_from_packet(pData, dataLength); #endif - if ( (0 == pPH->vehicle_id_src) || (MAX_U32 == pPH->vehicle_id_src) ) - log_softerror_and_alarm("Received invalid radio packet: Invalid source vehicle id: %u (vehicle id dest: %u, packet type: %s)", - pPH->vehicle_id_src, pPH->vehicle_id_dest, str_get_packet_type(pPH->packet_type)); - - if ( pPH->vehicle_id_src == g_uControllerId ) + if ( (0 == uVehicleIdSrc) || (MAX_U32 == uVehicleIdSrc) ) + { + log_error_and_alarm("Received invalid radio packet: Invalid source vehicle id: %u (vehicle id dest: %u, packet type: %s, %d bytes, %d total bytes, component: %d)", + uVehicleIdSrc, uVehicleIdDest, str_get_packet_type(uPacketType), dataLength, pPH->total_length, pPH->packet_flags & PACKET_FLAGS_MASK_MODULE); + return; + } + if ( uVehicleIdSrc == g_uControllerId ) _mark_link_from_controller_present(); - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RC ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RC ) { if ( ! s_bRCLinkDetected ) { @@ -395,16 +427,17 @@ void process_received_single_radio_packet(int iRadioInterface, u8* pData, int da s_bRCLinkDetected = true; } - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RUBY ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RUBY ) { - if ( pPH->vehicle_id_dest == g_pCurrentModel->uVehicleId ) + if ( uVehicleIdDest == g_pCurrentModel->uVehicleId ) process_received_ruby_message(iRadioInterface, pData); return; } - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_COMMANDS ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_COMMANDS ) { - if ( pPH->packet_type == PACKET_TYPE_COMMAND ) + if ( uPacketType == PACKET_TYPE_COMMAND ) + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) { int iParamsLength = pPH->total_length - sizeof(t_packet_header) - sizeof(t_packet_header_command); t_packet_header_command* pPHC = (t_packet_header_command*)(pData + sizeof(t_packet_header)); @@ -437,23 +470,23 @@ void process_received_single_radio_packet(int iRadioInterface, u8* pData, int da return; } - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_TELEMETRY ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_TELEMETRY ) { //log_line("Received an uplink telemetry packet: packet type: %d, module: %d, length: %d", pPH->packet_type, pPH->packet_flags & PACKET_FLAGS_MASK_MODULE, pPH->total_length); ruby_ipc_channel_send_message(s_fIPCRouterToTelemetry, pData, dataLength); return; } - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RC ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_RC ) { if ( g_pCurrentModel->rc_params.rc_enabled ) ruby_ipc_channel_send_message(s_fIPCRouterToRC, pData, dataLength); return; } - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) { - if ( pPH->packet_type == PACKET_TYPE_VIDEO_SWITCH_VIDEO_KEYFRAME_TO_VALUE ) + if ( uPacketType == PACKET_TYPE_VIDEO_SWITCH_VIDEO_KEYFRAME_TO_VALUE ) { if ( pPH->total_length < sizeof(t_packet_header) + sizeof(u32) ) return; @@ -484,7 +517,7 @@ void process_received_single_radio_packet(int iRadioInterface, u8* pData, int da PH.packet_flags = PACKET_COMPONENT_VIDEO; PH.packet_type = PACKET_TYPE_VIDEO_SWITCH_VIDEO_KEYFRAME_TO_VALUE_ACK; PH.vehicle_id_src = g_pCurrentModel->uVehicleId; - PH.vehicle_id_dest = pPH->vehicle_id_src; + PH.vehicle_id_dest = uVehicleIdSrc; PH.total_length = sizeof(t_packet_header) + sizeof(u32); u8 packet[MAX_PACKET_TOTAL_SIZE]; memcpy(packet, (u8*)&PH, sizeof(t_packet_header)); diff --git a/code/r_vehicle/process_received_ruby_messages.cpp b/code/r_vehicle/process_received_ruby_messages.cpp index 4ab62bcb..f1aa94d6 100644 --- a/code/r_vehicle/process_received_ruby_messages.cpp +++ b/code/r_vehicle/process_received_ruby_messages.cpp @@ -305,6 +305,7 @@ int process_received_ruby_message(int iInterfaceIndex, u8* pPacketBuffer) memcpy(&uParam, pPacketBuffer + sizeof(t_packet_header) + 2*sizeof(u8), sizeof(u32)); memcpy(&iParam, &uParam, sizeof(int)); log_line("Received negociate radio link, command %d, param: %d", uCommand, iParam); + g_uTimeLastNegociateRadioLinksCommand = g_TimeNow; if ( (uCommand == NEGOCIATE_RADIO_STEP_END) || (uCommand == NEGOCIATE_RADIO_STEP_CANCEL) ) { diff --git a/code/r_vehicle/process_upload.cpp b/code/r_vehicle/process_upload.cpp index c3513322..02566b0f 100644 --- a/code/r_vehicle/process_upload.cpp +++ b/code/r_vehicle/process_upload.cpp @@ -279,26 +279,6 @@ static void * _thread_process_upload(void *argument) hw_execute_ruby_process_wait(NULL, "ruby_update_vehicle", "-ver", szOutput, 1); log_line("ruby_update_vehicle: [%s]", szOutput); - // Begin Check and update drivers - - #ifdef HW_PLATFORM_OPENIPC_CAMERA - char szDriver[MAX_FILE_PATH_SIZE]; - strcpy(szDriver, FOLDER_BINARIES); - strcat(szDriver, "drivers/8812eu.ko"); - - if ( access(szDriver, R_OK) != -1 ) - { - sprintf(szComm, "mv -f %s /lib/modules/$(uname -r)/extra/", szDriver); - hw_execute_bash_command(szComm, NULL); - hw_execute_bash_command("modprobe cfg80211", NULL); - hw_execute_bash_command("insmod /lib/modules/$(uname -r)/extra/8812eu.ko rtw_tx_pwr_by_rate=0 rtw_tx_pwr_lmt_enable=0", NULL); - } - else - log_line("No new driver in file [%s]", szDriver); - - #endif - // End check and update drivers - #ifdef HW_PLATFORM_RASPBERRY if ( access( "ruby_capture_raspi", R_OK ) != -1 ) hw_execute_bash_command("cp -rf ruby_capture_raspi /opt/vc/bin/raspivid", NULL); @@ -395,6 +375,44 @@ static void * _thread_process_upload(void *argument) _sw_update_close_remove_temp_files(); _process_upload_send_status_to_controller(OTA_UPDATE_STATUS_COMPLETED, 50); + + + // Begin Check and update drivers + + #ifdef HW_PLATFORM_OPENIPC_CAMERA + char szDriver[MAX_FILE_PATH_SIZE]; + strcpy(szDriver, FOLDER_BINARIES); + strcat(szDriver, "drivers/8812eu-oipc.ko"); + + if ( access(szDriver, R_OK) != -1 ) + { + sprintf(szComm, "mv -f %s /lib/modules/$(uname -r)/extra/", szDriver); + hw_execute_bash_command(szComm, NULL); + hw_execute_bash_command("modprobe cfg80211", NULL); + hw_execute_bash_command("rmmod 8812eu 2>&1 1>/dev/null", NULL); + hw_execute_bash_command("insmod /lib/modules/$(uname -r)/extra/8812eu-oipc.ko rtw_tx_pwr_by_rate=0 rtw_tx_pwr_lmt_enable=0", NULL); + } + else + log_line("No new RTL8812EU driver in file [%s]", szDriver); + + strcpy(szDriver, FOLDER_BINARIES); + strcat(szDriver, "drivers/88XXau-oipc.ko"); + + if ( access(szDriver, R_OK) != -1 ) + { + sprintf(szComm, "mv -f %s /lib/modules/$(uname -r)/extra/", szDriver); + hw_execute_bash_command(szComm, NULL); + hw_execute_bash_command("modprobe cfg80211", NULL); + hw_execute_bash_command("rmmod 88XXau 2>&1 1>/dev/null", NULL); + hw_execute_bash_command("insmod /lib/modules/$(uname -r)/extra/88XXau-oipc.ko rtw_tx_pwr_idx_override=1", NULL); + } + else + log_line("No new RTL8812AU driver in file [%s]", szDriver); + #endif + + hardware_install_drivers(); + // End check and update drivers + signalReboot(); return NULL; } @@ -434,7 +452,7 @@ void process_sw_upload_new(u32 command_param, u8* pBuffer, int length) return; } - if ( (params->total_size <= 0) || (params->block_length <= 0) || (params->total_size > 50000000) || (params->block_length < 50) ) + if ( (params->total_size <= 0) || (params->block_length <= 0) || (params->total_size > 50000000) ) { log_softerror_and_alarm("Received SW Upload packet of invalid size: %d bytes, total length: %d bytes.", params->block_length, params->total_size); _sw_update_close_remove_temp_files(); diff --git a/code/r_vehicle/processor_relay.cpp b/code/r_vehicle/processor_relay.cpp index 0933917f..4e29bf9e 100644 --- a/code/r_vehicle/processor_relay.cpp +++ b/code/r_vehicle/processor_relay.cpp @@ -38,12 +38,12 @@ #include "../common/relay_utils.h" #include "../radio/radiolink.h" #include "../radio/radio_rx.h" +#include "../utils/utils_vehicle.h" #include "processor_relay.h" #include "ruby_rt_vehicle.h" #include "radio_links.h" #include "shared_vars.h" #include "timers.h" -#include "utils_vehicle.h" bool s_bHasEverReceivedDataFromRelayedVehicle = false; bool s_uLastReceivedRelayedVehicleID = MAX_U32; @@ -78,9 +78,13 @@ void relay_init_and_set_rx_info_stats(type_uplink_rx_info_stats* pUplinkStats) void relay_process_received_single_radio_packet_from_controller_to_relayed_vehicle(int iRadioInterfaceIndex, u8* pBufferData, int iBufferLength) { t_packet_header* pPH = (t_packet_header*)pBufferData; - //log_line("[Relay] Relay from CID %u to VID %u, type: %s", - // pPH->vehicle_id_src, pPH->vehicle_id_dest, str_get_packet_type(pPH->packet_type)); + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pBufferData; + + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + if ( pPHC->packet_type == PACKET_TYPE_RUBY_PING_CLOCK ) + s_uLastLocalRadioLinkUsedForPingToRelayedVehicle = (u8) g_pCurrentModel->radioInterfacesParams.interface_link_id[iRadioInterfaceIndex]; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) if ( pPH->packet_type == PACKET_TYPE_RUBY_PING_CLOCK ) s_uLastLocalRadioLinkUsedForPingToRelayedVehicle = (u8) g_pCurrentModel->radioInterfacesParams.interface_link_id[iRadioInterfaceIndex]; @@ -100,17 +104,37 @@ void relay_process_received_radio_packet_from_relayed_vehicle(int iRadioLink, in return; t_packet_header* pPH = (t_packet_header*)pBufferData; - - if ( (pPH->vehicle_id_src == 0) || (pPH->vehicle_id_src == MAX_U32) || + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pBufferData; + u32 uVehicleIdSrc = 0; + int iTotalLength = 0; + u8 uPacketType = 0; + u8 uPacketFlags = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + uVehicleIdSrc = pPHC->vehicle_id_src; + iTotalLength = pPHC->total_length; + uPacketType = pPHC->packet_type; + uPacketFlags = pPHC->packet_flags; + uPacketFlags &= ~(PACKET_FLAGS_MASK_MODULE); + uPacketFlags |= pPHC->uExtraBits & PACKET_FLAGS_MASK_MODULE; + } + else + { + uVehicleIdSrc = pPH->vehicle_id_src; + iTotalLength = pPH->total_length; + uPacketType = pPH->packet_type; + uPacketFlags = pPH->packet_flags; + } + if ( (uVehicleIdSrc == 0) || (uVehicleIdSrc == MAX_U32) || (g_pCurrentModel->relay_params.uRelayedVehicleId == 0 ) || (g_pCurrentModel->relay_params.uRelayedVehicleId == MAX_U32) || - (pPH->vehicle_id_src != g_pCurrentModel->relay_params.uRelayedVehicleId) ) + (uVehicleIdSrc != g_pCurrentModel->relay_params.uRelayedVehicleId) ) { static bool s_bFirstTimeReceivedDataFromWrongRelayedVID = true; if ( s_bFirstTimeReceivedDataFromWrongRelayedVID ) { log_line("[Relay] Started to receive data for first time from wrong relayed VID (%u). Expected relayed VID: %u", - pPH->vehicle_id_src, g_pCurrentModel->relay_params.uRelayedVehicleId); + uVehicleIdSrc, g_pCurrentModel->relay_params.uRelayedVehicleId); s_bFirstTimeReceivedDataFromWrongRelayedVID = false; } return; @@ -119,18 +143,18 @@ void relay_process_received_radio_packet_from_relayed_vehicle(int iRadioLink, in if ( ! s_bHasEverReceivedDataFromRelayedVehicle ) { log_line("[Relay] Started to receive valid data from relayed VID: %u, current relay flags: %s, current relay mode: %s", - pPH->vehicle_id_src, str_format_relay_flags(g_pCurrentModel->relay_params.uRelayCapabilitiesFlags), str_format_relay_mode(g_pCurrentModel->relay_params.uCurrentRelayMode)); + uVehicleIdSrc, str_format_relay_flags(g_pCurrentModel->relay_params.uRelayCapabilitiesFlags), str_format_relay_mode(g_pCurrentModel->relay_params.uCurrentRelayMode)); s_bHasEverReceivedDataFromRelayedVehicle = true; - s_uLastReceivedRelayedVehicleID = pPH->vehicle_id_src; + s_uLastReceivedRelayedVehicleID = uVehicleIdSrc; } // Do not relay video packets if relay mode is not one where remote video through this vehicle is needed - if ( ((pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO) || - ((pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_AUDIO) ) - if ( (pPH->packet_type == PACKET_TYPE_VIDEO_DATA_98) || - (pPH->packet_type == PACKET_TYPE_AUDIO_SEGMENT) ) - if ( ! relay_vehicle_must_forward_video_from_relayed_vehicle(g_pCurrentModel, pPH->vehicle_id_src) ) + if ( ((uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO) || + ((uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_AUDIO) ) + if ( (uPacketType == PACKET_TYPE_VIDEO_DATA_98) || + (uPacketType == PACKET_TYPE_AUDIO_SEGMENT) ) + if ( ! relay_vehicle_must_forward_video_from_relayed_vehicle(g_pCurrentModel, uVehicleIdSrc) ) return; type_uplink_rx_info_stats* pRxInfoStats = NULL; @@ -138,30 +162,47 @@ void relay_process_received_radio_packet_from_relayed_vehicle(int iRadioLink, in pRxInfoStats = (type_uplink_rx_info_stats*)(((u32*)s_pRelayRxInfoStats) + iRadioInterfaceIndex * sizeof(type_uplink_rx_info_stats)); u8* pData = pBufferData; - int nLength = iBufferLength; + int nRemainingLength = iBufferLength; int iCountReceivedPackets = 0; bool bIsFullComposedPacketOkToForward = true; bool bPacketContainsDataToForward = false; - while ( nLength > 0 ) + while ( nRemainingLength > 0 ) { - t_packet_header* pPH = (t_packet_header*)pData; + pPH = (t_packet_header*)pData; + pPHC = (t_packet_header_compressed*)pData; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + uVehicleIdSrc = pPHC->vehicle_id_src; + iTotalLength = pPHC->total_length; + uPacketType = pPHC->packet_type; + uPacketFlags = pPHC->packet_flags; + uPacketFlags &= ~(PACKET_FLAGS_MASK_MODULE); + uPacketFlags |= pPHC->uExtraBits & PACKET_FLAGS_MASK_MODULE; + } + else + { + uVehicleIdSrc = pPH->vehicle_id_src; + iTotalLength = pPH->total_length; + uPacketType = pPH->packet_type; + uPacketFlags = pPH->packet_flags; + } int bCRCOk = 0; - int iPacketLength = packet_process_and_check(iRadioInterfaceIndex, pData, nLength, &bCRCOk); + int iPacketLength = packet_process_and_check(iRadioInterfaceIndex, pData, nRemainingLength, &bCRCOk); if ( iPacketLength <= 0 ) return; - if ( pPH->vehicle_id_src != g_pCurrentModel->relay_params.uRelayedVehicleId ) + if ( uVehicleIdSrc != g_pCurrentModel->relay_params.uRelayedVehicleId ) { - pData += pPH->total_length; - nLength -= pPH->total_length; + pData += iTotalLength; + nRemainingLength -= iTotalLength; if ( (NULL != pRxInfoStats) && (g_TimeNow > pRxInfoStats->timeLastLogWrongRxPacket + 2000) ) { pRxInfoStats->timeLastLogWrongRxPacket = g_TimeNow; - log_softerror_and_alarm("[Relaying] Received radio packet on the relay link from a different vehicle than the relayed vehicle (received VID: %u, current main VID: %u, relayed VID: %u)", pPH->vehicle_id_src, g_pCurrentModel->uVehicleId, g_pCurrentModel->relay_params.uRelayedVehicleId ); + log_softerror_and_alarm("[Relaying] Received radio packet on the relay link from a different vehicle than the relayed vehicle (received VID: %u, current main VID: %u, relayed VID: %u)", uVehicleIdSrc, g_pCurrentModel->uVehicleId, g_pCurrentModel->relay_params.uRelayedVehicleId ); } bIsFullComposedPacketOkToForward = false; @@ -170,47 +211,48 @@ void relay_process_received_radio_packet_from_relayed_vehicle(int iRadioLink, in iCountReceivedPackets++; - if ( (pPH->packet_type == PACKET_TYPE_RUBY_PAIRING_REQUEST) || - (pPH->packet_type == PACKET_TYPE_RUBY_PAIRING_CONFIRMATION) ) + if ( (uPacketType == PACKET_TYPE_RUBY_PAIRING_REQUEST) || + (uPacketType == PACKET_TYPE_RUBY_PAIRING_CONFIRMATION) ) { bPacketContainsDataToForward = true; log_line("Will relay from relayed vehicle to controller the pairing confirmation message."); } - if ( (pPH->packet_type == PACKET_TYPE_VIDEO_SWITCH_VIDEO_KEYFRAME_TO_VALUE_ACK) || - (pPH->packet_type == PACKET_TYPE_VIDEO_SWITCH_TO_ADAPTIVE_VIDEO_LEVEL_ACK) ) + if ( (uPacketType == PACKET_TYPE_VIDEO_SWITCH_VIDEO_KEYFRAME_TO_VALUE_ACK) || + (uPacketType == PACKET_TYPE_VIDEO_SWITCH_TO_ADAPTIVE_VIDEO_LEVEL_ACK) || + (uPacketType == PACKET_TYPE_NEGOCIATE_RADIO_LINKS) ) bPacketContainsDataToForward = true; if ( g_pCurrentModel->relay_params.uRelayCapabilitiesFlags & RELAY_CAPABILITY_TRANSPORT_VIDEO ) - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) if ( relay_current_vehicle_must_send_relayed_video_feeds() ) bPacketContainsDataToForward = true; if ( g_pCurrentModel->relay_params.uRelayCapabilitiesFlags & RELAY_CAPABILITY_TRANSPORT_TELEMETRY ) - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_TELEMETRY ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_TELEMETRY ) bPacketContainsDataToForward = true; // Ruby telemetry and FC telemetry is always forwarded on the relay link - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_TELEMETRY ) - if ( (pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_EXTENDED) || - (pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_SHORT) || - (pPH->packet_type == PACKET_TYPE_FC_TELEMETRY) || - (pPH->packet_type == PACKET_TYPE_FC_TELEMETRY_EXTENDED) ) + if ( (uPacketFlags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_TELEMETRY ) + if ( (uPacketType == PACKET_TYPE_RUBY_TELEMETRY_EXTENDED) || + (uPacketType == PACKET_TYPE_RUBY_TELEMETRY_SHORT) || + (uPacketType == PACKET_TYPE_FC_TELEMETRY) || + (uPacketType == PACKET_TYPE_FC_TELEMETRY_EXTENDED) ) { - if ( (pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_EXTENDED) || - (pPH->packet_type == PACKET_TYPE_RUBY_TELEMETRY_SHORT) ) - _process_received_ruby_telemetry_from_relayed_vehicle((u8*)&pPH, pPH->total_length); + if ( (uPacketType == PACKET_TYPE_RUBY_TELEMETRY_EXTENDED) || + (uPacketType == PACKET_TYPE_RUBY_TELEMETRY_SHORT) ) + _process_received_ruby_telemetry_from_relayed_vehicle(pData, iTotalLength); bPacketContainsDataToForward = true; } - if ( (pPH->packet_type == PACKET_TYPE_RUBY_PING_CLOCK) || - (pPH->packet_type == PACKET_TYPE_RUBY_PING_CLOCK_REPLY) ) + if ( (uPacketType == PACKET_TYPE_RUBY_PING_CLOCK) || + (uPacketType == PACKET_TYPE_RUBY_PING_CLOCK_REPLY) ) { bPacketContainsDataToForward = true; - if ( pPH->packet_type == PACKET_TYPE_RUBY_PING_CLOCK_REPLY ) + if ( uPacketType == PACKET_TYPE_RUBY_PING_CLOCK_REPLY ) memcpy(pData+sizeof(t_packet_header)+2*sizeof(u8)+sizeof(u32), &s_uLastLocalRadioLinkUsedForPingToRelayedVehicle, sizeof(u8)); } - pData += pPH->total_length; - nLength -= pPH->total_length; + pData += iTotalLength; + nRemainingLength -= iTotalLength; } if ( (! bIsFullComposedPacketOkToForward) || (! bPacketContainsDataToForward) ) @@ -354,24 +396,40 @@ void relay_send_packet_to_controller(u8* pBufferData, int iBufferLength) } u8* pData = pBufferData; - int nLength = iBufferLength; + int iRemainingLength = iBufferLength; u32 uCountChainedPackets = 0; + int iPacketLength = 0; u32 uStreamId = 0; u32 uSourceVehicleId = 0; bool bContainsPairConfirmation = false; - while ( nLength > 0 ) + while ( iRemainingLength > 0 ) { t_packet_header* pPH = (t_packet_header*)pData; - if ( pPH->packet_type == PACKET_TYPE_RUBY_PAIRING_CONFIRMATION ) + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pData; + u8 uPacketType = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + iPacketLength = pPHC->total_length; + uPacketType = pPHC->packet_type; + uSourceVehicleId = pPHC->vehicle_id_src; + uStreamId = (pPHC->stream_packet_idx)>>PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + } + else + { + iPacketLength = pPH->total_length; + uPacketType = pPH->packet_type; + uSourceVehicleId = pPH->vehicle_id_src; + uStreamId = (pPH->stream_packet_idx)>>PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + } + if ( uPacketType == PACKET_TYPE_RUBY_PAIRING_CONFIRMATION ) bContainsPairConfirmation = true; - uSourceVehicleId = pPH->vehicle_id_src; - uStreamId = (pPH->stream_packet_idx)>>PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; - if ( uStreamId < 0 || uStreamId >= MAX_RADIO_STREAMS ) + + if ( (uStreamId < 0) || (uStreamId >= MAX_RADIO_STREAMS) ) uStreamId = 0; - nLength -= pPH->total_length; - pData += pPH->total_length; + iRemainingLength -= iPacketLength; + pData += iPacketLength; uCountChainedPackets++; } @@ -460,10 +518,22 @@ void relay_send_single_packet_to_relayed_vehicle(u8* pBufferData, int iBufferLen return; } t_packet_header* pPH = (t_packet_header*)pBufferData; + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pBufferData; + + u32 uRelayedVehicleId = 0; + u32 uStreamId = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + uRelayedVehicleId = pPHC->vehicle_id_dest; + uStreamId = (pPHC->stream_packet_idx)>>PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + } + else + { + uRelayedVehicleId = pPH->vehicle_id_dest; + uStreamId = (pPH->stream_packet_idx)>>PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + } - u32 uRelayedVehicleId = pPH->vehicle_id_dest; - u32 uStreamId = (pPH->stream_packet_idx)>>PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; - if ( uStreamId < 0 || uStreamId >= MAX_RADIO_STREAMS ) + if ( (uStreamId < 0) || (uStreamId >= MAX_RADIO_STREAMS) ) uStreamId = 0; if ( uRelayedVehicleId != g_pCurrentModel->relay_params.uRelayedVehicleId ) diff --git a/code/r_vehicle/processor_tx_video.cpp b/code/r_vehicle/processor_tx_video.cpp index 1fa34266..a3d99d86 100644 --- a/code/r_vehicle/processor_tx_video.cpp +++ b/code/r_vehicle/processor_tx_video.cpp @@ -44,7 +44,7 @@ #include "processor_tx_video.h" #include "processor_relay.h" #include "packets_utils.h" -#include "utils_vehicle.h" +#include "../utils/utils_vehicle.h" #include "adaptive_video.h" #include "video_source_csi.h" #include "video_source_majestic.h" @@ -691,24 +691,24 @@ void _send_packet(int bufferIndex, int packetIndex, bool isRetransmitted, bool i if ( uLastFrameDuration < 1 ) uLastFrameDuration = 1; - u32 uLastFrameSize = s_ParserH264RadioOutput.getSizeOfLastCompleteFrame(); + u32 uLastFrameSize = s_ParserH264RadioOutput.getSizeOfLastCompleteFrameInBytes(); uLastFrameSize /= 1000; // transform to kbytes if ( uLastFrameSize > 127 ) uLastFrameSize = 127; // kbytes - g_VideoInfoStatsRadioOut.uLastIndex = (g_VideoInfoStatsRadioOut.uLastIndex+1) % MAX_FRAMES_SAMPLES; - g_VideoInfoStatsRadioOut.uFramesDuration[g_VideoInfoStatsRadioOut.uLastIndex] = uLastFrameDuration; - g_VideoInfoStatsRadioOut.uFramesTypesAndSizes[g_VideoInfoStatsRadioOut.uLastIndex] = (g_VideoInfoStatsRadioOut.uFramesTypesAndSizes[g_VideoInfoStatsRadioOut.uLastIndex] & 0x80) | ((u8)uLastFrameSize); + g_VideoInfoStatsRadioOut.uLastFrameIndex = (g_VideoInfoStatsRadioOut.uLastFrameIndex+1) % MAX_FRAMES_SAMPLES; + g_VideoInfoStatsRadioOut.uFramesDuration[g_VideoInfoStatsRadioOut.uLastFrameIndex] = uLastFrameDuration; + g_VideoInfoStatsRadioOut.uFramesTypesAndSizes[g_VideoInfoStatsRadioOut.uLastFrameIndex] = (g_VideoInfoStatsRadioOut.uFramesTypesAndSizes[g_VideoInfoStatsRadioOut.uLastFrameIndex] & 0x80) | ((u8)uLastFrameSize); - u32 uNextIndex = (g_VideoInfoStatsRadioOut.uLastIndex+1) % MAX_FRAMES_SAMPLES; + u32 uNextIndex = (g_VideoInfoStatsRadioOut.uLastFrameIndex+1) % MAX_FRAMES_SAMPLES; if ( s_ParserH264RadioOutput.IsInsideIFrame() ) g_VideoInfoStatsRadioOut.uFramesTypesAndSizes[uNextIndex] |= (1<<7); else g_VideoInfoStatsRadioOut.uFramesTypesAndSizes[uNextIndex] &= 0x7F; - g_VideoInfoStatsRadioOut.uKeyframeIntervalMs = s_ParserH264RadioOutput.getCurrentlyDetectedKeyframeIntervalMs(); + g_VideoInfoStatsRadioOut.uDetectedKeyframeIntervalMs = s_ParserH264RadioOutput.getCurrentlyDetectedKeyframeIntervalMs(); g_VideoInfoStatsRadioOut.uDetectedFPS = s_ParserH264RadioOutput.getDetectedFPS(); g_VideoInfoStatsRadioOut.uDetectedSlices = (u32) s_ParserH264RadioOutput.getDetectedSlices(); @@ -1382,7 +1382,7 @@ bool process_data_tx_video_command(int iRadioInterface, u8* pPacketBuffer) memcpy( &uVideoStreamIndex, pPacketBuffer + sizeof(t_packet_header) + sizeof(u32) + sizeof(u8), sizeof(u8)); t_packet_header PH; - radio_packet_init(&PH, PACKET_COMPONENT_VIDEO, PACKET_TYPE_VIDEO_SWITCH_TO_ADAPTIVE_VIDEO_LEVEL_ACK, STREAM_ID_DATA); + radio_packet_init(&PH, PACKET_COMPONENT_VIDEO, PACKET_TYPE_VIDEO_SWITCH_TO_ADAPTIVE_VIDEO_LEVEL_ACK, STREAM_ID_VIDEO_1); PH.vehicle_id_src = g_pCurrentModel->uVehicleId; PH.vehicle_id_dest = pPH->vehicle_id_src; PH.total_length = sizeof(t_packet_header) + sizeof(u32) + sizeof(u8); @@ -1504,24 +1504,24 @@ void _parse_camera_source_h264_data(u8* pData, int iDataSize) if ( uLastFrameDuration < 1 ) uLastFrameDuration = 1; - u32 uLastFrameSize = s_ParserH264CameraOutput.getSizeOfLastCompleteFrame(); + u32 uLastFrameSize = s_ParserH264CameraOutput.getSizeOfLastCompleteFrameInBytes(); uLastFrameSize /= 1000; // transform to kbytes if ( uLastFrameSize > 127 ) uLastFrameSize = 127; // kbytes - g_VideoInfoStatsCameraOutput.uLastIndex = (g_VideoInfoStatsCameraOutput.uLastIndex+1) % MAX_FRAMES_SAMPLES; - g_VideoInfoStatsCameraOutput.uFramesDuration[g_VideoInfoStatsCameraOutput.uLastIndex] = uLastFrameDuration; - g_VideoInfoStatsCameraOutput.uFramesTypesAndSizes[g_VideoInfoStatsCameraOutput.uLastIndex] = (g_VideoInfoStatsCameraOutput.uFramesTypesAndSizes[g_VideoInfoStatsCameraOutput.uLastIndex] & 0x80) | ((u8)uLastFrameSize); + g_VideoInfoStatsCameraOutput.uLastFrameIndex = (g_VideoInfoStatsCameraOutput.uLastFrameIndex+1) % MAX_FRAMES_SAMPLES; + g_VideoInfoStatsCameraOutput.uFramesDuration[g_VideoInfoStatsCameraOutput.uLastFrameIndex] = uLastFrameDuration; + g_VideoInfoStatsCameraOutput.uFramesTypesAndSizes[g_VideoInfoStatsCameraOutput.uLastFrameIndex] = (g_VideoInfoStatsCameraOutput.uFramesTypesAndSizes[g_VideoInfoStatsCameraOutput.uLastFrameIndex] & 0x80) | ((u8)uLastFrameSize); - u32 uNextIndex = (g_VideoInfoStatsCameraOutput.uLastIndex+1) % MAX_FRAMES_SAMPLES; + u32 uNextIndex = (g_VideoInfoStatsCameraOutput.uLastFrameIndex+1) % MAX_FRAMES_SAMPLES; if ( s_ParserH264CameraOutput.IsInsideIFrame() ) g_VideoInfoStatsCameraOutput.uFramesTypesAndSizes[uNextIndex] |= (1<<7); else g_VideoInfoStatsCameraOutput.uFramesTypesAndSizes[uNextIndex] &= 0x7F; - g_VideoInfoStatsCameraOutput.uKeyframeIntervalMs = s_ParserH264CameraOutput.getCurrentlyDetectedKeyframeIntervalMs(); + g_VideoInfoStatsCameraOutput.uDetectedKeyframeIntervalMs = s_ParserH264CameraOutput.getCurrentlyDetectedKeyframeIntervalMs(); if ( s_ParserH264CameraOutput.IsInsideIFrame() ) return; @@ -1554,7 +1554,7 @@ void _parse_camera_source_h264_data(u8* pData, int iDataSize) return; // Set highest bit to mark keyframe changed - g_VideoInfoStatsCameraOutput.uFramesDuration[g_VideoInfoStatsCameraOutput.uLastIndex] |= 0x80; + g_VideoInfoStatsCameraOutput.uFramesDuration[g_VideoInfoStatsCameraOutput.uLastFrameIndex] |= 0x80; g_SM_VideoLinkStats.overwrites.uCurrentActiveKeyframeMs = g_SM_VideoLinkStats.overwrites.uCurrentPendingKeyframeMs; diff --git a/code/r_vehicle/ruby_rt_vehicle.cpp b/code/r_vehicle/ruby_rt_vehicle.cpp index f2fd678e..8142226f 100644 --- a/code/r_vehicle/ruby_rt_vehicle.cpp +++ b/code/r_vehicle/ruby_rt_vehicle.cpp @@ -77,7 +77,7 @@ #include "process_received_ruby_messages.h" #include "process_radio_in_packets.h" #include "launchers_vehicle.h" -#include "utils_vehicle.h" +#include "../utils/utils_vehicle.h" #include "periodic_loop.h" #include "../radio/radiopackets2.h" @@ -185,7 +185,7 @@ bool links_set_cards_frequencies_and_params(int iLinkId) { u32 uFreqKhz = uRadioLinkFrequency; u32 uDataRate = g_pCurrentModel->radioLinksParams.link_datarate_data_bps[nRadioLinkId]; - u32 uTxPower = g_pCurrentModel->radioInterfacesParams.txPowerSiK; + u32 uTxPower = g_pCurrentModel->radioInterfacesParams.interface_raw_power[i]; u32 uECC = (g_pCurrentModel->radioLinksParams.link_radio_flags[nRadioLinkId] & RADIO_FLAGS_SIK_ECC)? 1:0; u32 uLBT = (g_pCurrentModel->radioLinksParams.link_radio_flags[nRadioLinkId] & RADIO_FLAGS_SIK_LBT)? 1:0; u32 uMCSTR = (g_pCurrentModel->radioLinksParams.link_radio_flags[nRadioLinkId] & RADIO_FLAGS_SIK_MCSTR)? 1:0; @@ -550,7 +550,7 @@ void reinit_radio_interfaces() log_line("================================================================="); log_line("Detected hardware radio interfaces:"); - hardware_log_radio_info(); + hardware_log_radio_info(NULL, 0); log_line("Setting all the cards frequencies again..."); @@ -834,6 +834,10 @@ void process_and_send_packets() pPHRTE->uplink_rssi_dbm[i] = g_UplinkInfoRxStats[i].lastReceivedDBM + 200; pPHRTE->uplink_link_quality[i] = g_SM_RadioStats.radio_interfaces[i].rxQuality; + if ( g_TimeLastReceivedRadioPacketFromController < g_TimeNow-2000 ) + pPHRTE->uplink_link_quality[i] = 0; + else if ( (g_TimeLastReceivedRadioPacketFromController < g_TimeNow-1500) && (pPHRTE->uplink_link_quality[i] > 20) ) + pPHRTE->uplink_link_quality[i] = 20; } pPHRTE->txTimePerSec = g_RadioTxTimers.uComputedTotalTxTimeMilisecPerSecondAverage; @@ -862,39 +866,43 @@ void process_and_send_packets() void _synchronize_shared_mems() { - if ( g_pCurrentModel->osd_params.osd_flags[g_pCurrentModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_KEYFRAMES_INFO) + /* + if ( g_pCurrentModel->osd_params.osd_flags[g_pCurrentModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_H264_FRAMES_INFO) if ( g_TimeNow >= g_VideoInfoStatsCameraOutput.uTimeLastUpdate + 200 ) { - update_shared_mem_video_info_stats( &g_VideoInfoStatsCameraOutput, g_TimeNow); + update_shared_mem_video_frames_stats( &g_VideoInfoStatsCameraOutput, g_TimeNow); if ( NULL != g_pSM_VideoInfoStatsCameraOutput ) - memcpy((u8*)g_pSM_VideoInfoStatsCameraOutput, (u8*)&g_VideoInfoStatsCameraOutput, sizeof(shared_mem_video_info_stats)); + memcpy((u8*)g_pSM_VideoInfoStatsCameraOutput, (u8*)&g_VideoInfoStatsCameraOutput, sizeof(shared_mem_video_frames_stats)); else { - g_pSM_VideoInfoStatsCameraOutput = shared_mem_video_info_stats_open_for_write(); + g_pSM_VideoInfoStatsCameraOutput = shared_mem_video_frames_stats_open_for_write(); if ( NULL == g_pSM_VideoInfoStatsCameraOutput ) log_error_and_alarm("Failed to open shared mem video info camera stats for write!"); else log_line("Opened shared mem video info stats camera for write."); } } + */ - if ( g_pCurrentModel->osd_params.osd_flags[g_pCurrentModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_KEYFRAMES_INFO) + /* + if ( g_pCurrentModel->osd_params.osd_flags[g_pCurrentModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_H264_FRAMES_INFO) if ( g_TimeNow >= g_VideoInfoStatsRadioOut.uTimeLastUpdate + 200 ) { - update_shared_mem_video_info_stats( &g_VideoInfoStatsRadioOut, g_TimeNow); + update_shared_mem_video_frames_stats( &g_VideoInfoStatsRadioOut, g_TimeNow); if ( NULL != g_pSM_VideoInfoStatsRadioOut ) - memcpy((u8*)g_pSM_VideoInfoStatsRadioOut, (u8*)&g_VideoInfoStatsRadioOut, sizeof(shared_mem_video_info_stats)); + memcpy((u8*)g_pSM_VideoInfoStatsRadioOut, (u8*)&g_VideoInfoStatsRadioOut, sizeof(shared_mem_video_frames_stats)); else { - g_pSM_VideoInfoStatsRadioOut = shared_mem_video_info_stats_radio_out_open_for_write(); + g_pSM_VideoInfoStatsRadioOut = shared_mem_video_frames_stats_radio_out_open_for_write(); if ( NULL == g_pSM_VideoInfoStatsRadioOut ) log_error_and_alarm("Failed to open shared mem video info stats radio out for write!"); else log_line("Opened shared mem video info stats radio out for write."); } } + */ static u32 s_uTimeLastRxHistorySync = 0; @@ -1190,10 +1198,6 @@ void handle_sigint(int sig) radio_rx_mark_quit(); } -// To remove -bool bDebugNoVideoOutput = false; - - void _main_loop(); int main(int argc, char *argv[]) @@ -1465,20 +1469,22 @@ int main(int argc, char *argv[]) log_line("Start sequence: Done creating video processor."); - g_pSM_VideoInfoStatsCameraOutput = shared_mem_video_info_stats_open_for_write(); + /* + g_pSM_VideoInfoStatsCameraOutput = shared_mem_video_frames_stats_open_for_write(); if ( NULL == g_pSM_VideoInfoStatsCameraOutput ) log_error_and_alarm("Start sequence: Failed to open shared mem video camera info stats for write!"); else log_line("Start sequence: Opened shared mem video camera info stats for write."); - g_pSM_VideoInfoStatsRadioOut = shared_mem_video_info_stats_radio_out_open_for_write(); + g_pSM_VideoInfoStatsRadioOut = shared_mem_video_frames_stats_radio_out_open_for_write(); if ( NULL == g_pSM_VideoInfoStatsRadioOut ) log_error_and_alarm("Start sequence: Failed to open shared mem video info stats radio out for write!"); else log_line("Start sequence: Opened shared mem video info stats radio out for write."); - memset(&g_VideoInfoStatsCameraOutput, 0, sizeof(shared_mem_video_info_stats)); - memset(&g_VideoInfoStatsRadioOut, 0, sizeof(shared_mem_video_info_stats)); + memset(&g_VideoInfoStatsCameraOutput, 0, sizeof(shared_mem_video_frames_stats)); + memset(&g_VideoInfoStatsRadioOut, 0, sizeof(shared_mem_video_frames_stats)); + */ g_pProcessorTxAudio = new ProcessorTxAudio(); @@ -1540,9 +1546,6 @@ int main(int argc, char *argv[]) send_alarm_to_controller(ALARM_ID_FIRMWARE_OLD, i, 0, 5); } - if( access( "novideo", R_OK ) != -1 ) - bDebugNoVideoOutput = true; - g_iDefaultRouterThreadPriority = hw_increase_current_thread_priority("Main thread", g_pCurrentModel->processesPriorities.iThreadPriorityRouter); @@ -1581,8 +1584,8 @@ int main(int argc, char *argv[]) delete g_pProcessorTxVideo; delete g_pVideoTxBuffers; shared_mem_radio_stats_rx_hist_close(g_pSM_HistoryRxStats); - shared_mem_video_info_stats_close(g_pSM_VideoInfoStatsCameraOutput); - shared_mem_video_info_stats_radio_out_close(g_pSM_VideoInfoStatsRadioOut); + //shared_mem_video_frames_stats_close(g_pSM_VideoInfoStatsCameraOutput); + //shared_mem_video_frames_stats_radio_out_close(g_pSM_VideoInfoStatsRadioOut); shared_mem_process_stats_close(SHARED_MEM_WATCHDOG_ROUTER_TX, g_pProcessStats); log_line("Stopped.Exit now. (PID %d)", getpid()); log_line("---------------------\n"); @@ -1726,8 +1729,7 @@ void _main_loop() { int iBuffSize = video_source_csi_get_buffer_size(); bEndOfFrame = (iReadSize < iBuffSize)?true:false; - if ( ! bDebugNoVideoOutput ) - g_pVideoTxBuffers->fillVideoPackets(pVideoData, iReadSize, bEndOfFrame, bIsInsideIFrame); + g_pVideoTxBuffers->fillVideoPackets(pVideoData, iReadSize, bEndOfFrame, bIsInsideIFrame); if ( iReadSize < iBuffSize ) iMaxRepeatCount = 0; } @@ -1744,10 +1746,7 @@ void _main_loop() bool bEnd = video_source_majestic_last_read_is_end_nal(); bIsInsideIFrame = video_source_majestic_is_inside_iframe(); bEndOfFrame = (bSingle || bEnd); - if ( ! bDebugNoVideoOutput ) - { - g_pVideoTxBuffers->fillVideoPackets(pVideoData, iReadSize, bEndOfFrame, bIsInsideIFrame); - } + g_pVideoTxBuffers->fillVideoPackets(pVideoData, iReadSize, bEndOfFrame, bIsInsideIFrame); } else iMaxRepeatCount = 0; diff --git a/code/r_vehicle/ruby_rx_commands.cpp b/code/r_vehicle/ruby_rx_commands.cpp index 4fbf0761..3fcff18e 100644 --- a/code/r_vehicle/ruby_rx_commands.cpp +++ b/code/r_vehicle/ruby_rx_commands.cpp @@ -57,7 +57,7 @@ #include "video_source_csi.h" #include "shared_vars.h" #include "timers.h" -#include "utils_vehicle.h" +#include "../utils/utils_vehicle.h" #include "process_upload.h" #include @@ -1119,6 +1119,21 @@ bool process_command(u8* pBuffer, int length) strcat(szBuffer, szOutput); strcat(szBuffer, "#"); + szOutput[0] = 0; + #ifdef HW_PLATFORM_RASPBERRY + hw_execute_bash_command("cat /proc/cpuinfo | grep 'Revision' | awk '{print $3}'", szOutput); + strcat(szBuffer, "CPU Id: "); + strcat(szBuffer, szOutput); + strcat(szBuffer, "#"); + #endif + + strcat(szBuffer, "Detected board type: "); + strcat(szBuffer, str_get_hardware_board_name(hardware_getOnlyBoardType())); + strcat(szBuffer, "#"); + strcat(szBuffer, "Stored board type: "); + strcat(szBuffer, str_get_hardware_board_name(g_pCurrentModel->hwCapabilities.uBoardType)); + strcat(szBuffer, "#"); + hw_execute_bash_command_raw("free -m | grep Mem", szOutput); char szTemp[1024]; long lt, lu, lf; @@ -1761,6 +1776,16 @@ bool process_command(u8* pBuffer, int length) return true; } + if ( uCommandType == COMMAND_ID_SET_AUTO_TX_POWERS ) + { + g_pCurrentModel->radioInterfacesParams.iAutoControllerTxPower = (int)((pPHC->command_param >> 8) & 0xFF); + saveCurrentModel(); + signalReloadModel(MODEL_CHANGED_GENERIC,0); + sendCommandReply(COMMAND_RESPONSE_FLAGS_OK, 0, 0); + apply_vehicle_tx_power_levels(g_pCurrentModel); + return true; + } + if ( uCommandType == COMMAND_ID_SET_CAMERA_PARAMETERS ) { sendCommandReply(COMMAND_RESPONSE_FLAGS_OK, 0, 0); @@ -2102,7 +2127,16 @@ bool process_command(u8* pBuffer, int length) sendCommandReply(COMMAND_RESPONSE_FLAGS_FAILED, 0, 0); return true; } - sendCommandReply(COMMAND_RESPONSE_FLAGS_OK, 0, 0); + if ( ((pPHC->command_param >> 8) & 0xFF) == 0xFF ) + { + radio_hw_info_t* pRadioHWInfo = hardware_get_radio_info(cardIndex); + if ( NULL != pRadioHWInfo ) + cardType = pRadioHWInfo->iCardModel; + sendCommandReply(COMMAND_RESPONSE_FLAGS_OK, cardType, 0); + } + else + sendCommandReply(COMMAND_RESPONSE_FLAGS_OK, 0, 0); + g_pCurrentModel->radioInterfacesParams.interface_card_model[cardIndex] = cardType; if ( 0 == cardType ) { @@ -2406,8 +2440,9 @@ bool process_command(u8* pBuffer, int length) signalReloadModel(0, 0); return true; } - - log_line("Received new video params. User selected video link profile change from %s to %s", str_get_video_profile_name(oldParams.user_selected_video_link_profile), str_get_video_profile_name(g_pCurrentModel->video_params.user_selected_video_link_profile)); + char szModeOld[32]; + strcpy(szModeOld, str_get_video_profile_name(oldParams.user_selected_video_link_profile)); + log_line("Received new video params. User selected video link profile change from %s to %s", szModeOld, str_get_video_profile_name(g_pCurrentModel->video_params.user_selected_video_link_profile)); log_line("Video flags for video profile %s: %s, %s, %s", str_get_video_profile_name(g_pCurrentModel->video_params.user_selected_video_link_profile), @@ -2440,7 +2475,6 @@ bool process_command(u8* pBuffer, int length) g_pCurrentModel->video_link_profiles[VIDEO_PROFILE_LQ].keyframe_ms = g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].keyframe_ms; } - int iProfileToCheck = g_pCurrentModel->video_params.user_selected_video_link_profile; // Copy the bidirectional video and adaptive video flags to MQ and LQ profiles too @@ -2491,7 +2525,6 @@ bool process_command(u8* pBuffer, int length) g_pCurrentModel->video_link_profiles[oldParams.user_selected_video_link_profile].h264profile != g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264profile || g_pCurrentModel->video_link_profiles[oldParams.user_selected_video_link_profile].h264level != g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264level || g_pCurrentModel->video_link_profiles[oldParams.user_selected_video_link_profile].h264refresh != g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264refresh || - g_pCurrentModel->video_link_profiles[oldParams.user_selected_video_link_profile].insertPPS != g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].insertPPS || g_pCurrentModel->video_link_profiles[oldParams.user_selected_video_link_profile].h264quantization != g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].h264quantization ) bVideoResolutionChanged = true; @@ -2533,6 +2566,7 @@ bool process_command(u8* pBuffer, int length) signalTXVideoEncodingChanged(); signalUserSelectedVideoProfileChanged(); } + log_line("Finished processing COMMAND_ID_SET_VIDEO_PARAMS"); return true; } @@ -2565,6 +2599,7 @@ bool process_command(u8* pBuffer, int length) (g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_LINK)?"AdaptiveVideo=On":"AdaptiveVideo=Off", (g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ADAPTIVE_VIDEO_LINK_USE_CONTROLLER_INFO_TOO)?"AdaptiveUseControllerInfo=On":"AdaptiveUseControllerInfo=Off" ); + log_line("Received video data rate for current video profile %s: %d, (current: %d)", str_get_video_profile_name(g_pCurrentModel->video_params.user_selected_video_link_profile), g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].radio_datarate_video_bps, @@ -2676,6 +2711,21 @@ bool process_command(u8* pBuffer, int length) return true; } + if ( videoLinkProfileIsOnlyIPQuantizationDeltaChanged(&oldVideoProfiles[iProfileToCheck], &g_pCurrentModel->video_link_profiles[iProfileToCheck]) ) + { + log_line("[RX Commands]: Changed only IP quantization delta."); + if ( g_pCurrentModel->isActiveCameraOpenIPC() && hardware_board_is_sigmastar(g_pCurrentModel->hwCapabilities.uBoardType) ) + { + log_line("[RX Commands]: Signal IP quantization delta change on the fly for sigmastar."); + signalReloadModel(MODEL_CHANGED_VIDEO_IPQUANTIZATION_DELTA, 100 + g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].iIPQuantizationDelta); + } + else + { + signalReloadModel(MODEL_CHANGED_GENERIC, 0); + } + return true; + } + bool bChangedOneWayVideo = false; if ( (oldVideoProfiles[oldVideoParams.user_selected_video_link_profile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ONE_WAY_FIXED_VIDEO ) != (g_pCurrentModel->video_link_profiles[g_pCurrentModel->video_params.user_selected_video_link_profile].uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ONE_WAY_FIXED_VIDEO) ) @@ -2783,15 +2833,16 @@ bool process_command(u8* pBuffer, int length) { log_line("Received new serial ports info"); type_vehicle_hardware_interfaces_info* pNewInfo = (type_vehicle_hardware_interfaces_info*)(pBuffer + sizeof(t_packet_header)+sizeof(t_packet_header_command)); - g_pCurrentModel->hardwareInterfacesInfo.serial_bus_count = pNewInfo->serial_bus_count; - for( int i=0; iserial_bus_count; i++ ) + g_pCurrentModel->hardwareInterfacesInfo.serial_port_count = pNewInfo->serial_port_count; + for( int i=0; iserial_port_count; i++ ) { - strcpy(g_pCurrentModel->hardwareInterfacesInfo.serial_bus_names[i], pNewInfo->serial_bus_names[i]); - g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[i] = pNewInfo->serial_bus_speed[i]; - g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] = pNewInfo->serial_bus_supported_and_usage[i]; + strcpy(g_pCurrentModel->hardwareInterfacesInfo.serial_port_names[i], pNewInfo->serial_port_names[i]); + g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[i] = pNewInfo->serial_port_speed[i]; + g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] = pNewInfo->serial_port_supported_and_usage[i]; } - int iCount = g_pCurrentModel->hardwareInterfacesInfo.serial_bus_count; + int iCount = g_pCurrentModel->hardwareInterfacesInfo.serial_port_count; + log_line("Received %d serial ports. Hardware has %d serial ports.", iCount, hardware_get_serial_ports_count()); if ( iCount > hardware_get_serial_ports_count() ) iCount = hardware_get_serial_ports_count(); @@ -2804,19 +2855,19 @@ bool process_command(u8* pBuffer, int length) continue; if ( pPortInfo->iPortUsage == SERIAL_PORT_USAGE_SIK_RADIO ) - if ( pPortInfo->lPortSpeed != g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[i] ) + if ( pPortInfo->lPortSpeed != g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[i] ) if ( hardware_serial_is_sik_radio(pPortInfo->szPortDeviceName) ) { // Changed the serial speed of a SiK radio interface log_line("Received command to change the serial speed of a SiK radio interface. Serial port: [%s], old speed: %ld bps, new speed: %d bps", pPortInfo->szPortDeviceName, pPortInfo->lPortSpeed, - g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[i] ); + g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[i] ); iSikPortSpeedToUse = (int)pPortInfo->lPortSpeed; iSiKPortToUpdate = i; } - pPortInfo->lPortSpeed = g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[i]; - pPortInfo->iPortUsage = (int)(g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF); + pPortInfo->lPortSpeed = g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[i]; + pPortInfo->iPortUsage = (int)(g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF); } hardware_serial_save_configuration(); @@ -2872,15 +2923,15 @@ bool process_command(u8* pBuffer, int length) // Remove serial port used, if telemetry is set to None. if ( g_pCurrentModel->telemetry_params.fc_telemetry_type == TELEMETRY_TYPE_NONE ) { - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) { - u32 uPortTelemetryType = g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF; + u32 uPortTelemetryType = g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF; if ( (uPortTelemetryType == SERIAL_PORT_USAGE_TELEMETRY_MAVLINK) || (uPortTelemetryType == SERIAL_PORT_USAGE_TELEMETRY_LTM) || (uPortTelemetryType == SERIAL_PORT_USAGE_MSP_OSD) ) { // Remove serial port usage (set it to none) - g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] &= 0xFFFFFF00; + g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] &= 0xFFFFFF00; log_line("Did set serial port %d to type None as it was used for telemetry."); } } @@ -2889,11 +2940,11 @@ bool process_command(u8* pBuffer, int length) if ( g_pCurrentModel->telemetry_params.fc_telemetry_type != TELEMETRY_TYPE_NONE ) { int iCurrentSerialPortIndexForTelemetry = -1; - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) { - u32 uPortTelemetryType = g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF; + u32 uPortTelemetryType = g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF; - if ( g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) + if ( g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) if ( (uPortTelemetryType == SERIAL_PORT_USAGE_TELEMETRY_MAVLINK) || (uPortTelemetryType == SERIAL_PORT_USAGE_TELEMETRY_LTM) || (uPortTelemetryType == SERIAL_PORT_USAGE_MSP_OSD) ) @@ -2905,11 +2956,11 @@ bool process_command(u8* pBuffer, int length) log_line("Currently serial port index used for telemetry: %d", iCurrentSerialPortIndexForTelemetry); if ( -1 == iCurrentSerialPortIndexForTelemetry ) { - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) { - u32 uPortUsage = g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF; + u32 uPortUsage = g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF; - if ( g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) + if ( g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) if ( uPortUsage == SERIAL_PORT_USAGE_NONE ) { iCurrentSerialPortIndexForTelemetry = i; @@ -2922,16 +2973,16 @@ bool process_command(u8* pBuffer, int length) { log_line("Found a default serial port for telemetry. Serial port index %d", iCurrentSerialPortIndexForTelemetry); - if ( g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[iCurrentSerialPortIndexForTelemetry] <= 0 ) - g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[iCurrentSerialPortIndexForTelemetry] = DEFAULT_FC_TELEMETRY_SERIAL_SPEED; + if ( g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[iCurrentSerialPortIndexForTelemetry] <= 0 ) + g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[iCurrentSerialPortIndexForTelemetry] = DEFAULT_FC_TELEMETRY_SERIAL_SPEED; - g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[iCurrentSerialPortIndexForTelemetry] &= 0xFFFFFF00; + g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[iCurrentSerialPortIndexForTelemetry] &= 0xFFFFFF00; if ( g_pCurrentModel->telemetry_params.fc_telemetry_type == TELEMETRY_TYPE_MAVLINK ) - g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_TELEMETRY_MAVLINK; + g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_TELEMETRY_MAVLINK; if ( g_pCurrentModel->telemetry_params.fc_telemetry_type == TELEMETRY_TYPE_LTM ) - g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_TELEMETRY_LTM; + g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_TELEMETRY_LTM; if ( g_pCurrentModel->telemetry_params.fc_telemetry_type == TELEMETRY_TYPE_MSP ) - g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_MSP_OSD; + g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[iCurrentSerialPortIndexForTelemetry] |= SERIAL_PORT_USAGE_MSP_OSD; } } } @@ -3345,170 +3396,30 @@ bool process_command(u8* pBuffer, int length) if ( uCommandType == COMMAND_ID_SET_TX_POWERS ) { u8* pData = pBuffer + sizeof(t_packet_header)+sizeof(t_packet_header_command); - bool bUpdated = false; - bool bUpdatedWiFi = false; - - if ( iParamsLength >= 11 ) + if ( iParamsLength < 1 ) { - pData += 8; - if ( ( *pData == 0x81 ) && ( *(pData+2) == 0x81 ) ) - { - int iSiKPower = *(pData+1); - log_line("Received message with SiK radio power level: %d", iSiKPower); - - if ( iSiKPower > 0 && iSiKPower < 30 ) - if ( g_pCurrentModel->radioInterfacesParams.txPowerSiK != iSiKPower ) - { - log_line("Updated SiK radio power level to %d", iSiKPower); - g_pCurrentModel->radioInterfacesParams.txPowerSiK = iSiKPower; - bUpdated = true; - } - sendCommandReply(COMMAND_RESPONSE_FLAGS_OK, 0, 0); - } - else - { - log_softerror_and_alarm("Received invalid power levels message (for SiK radio interfaces). Ignoring it."); - sendCommandReply(COMMAND_RESPONSE_FLAGS_FAILED, 0, 0); - } - if ( bUpdated ) - { - saveCurrentModel(); - signalReloadModel(MODEL_CHANGED_RADIO_POWERS, 0); - } + log_softerror_and_alarm("Received invalid params to set cards tx powers: no params received."); + sendCommandReply(COMMAND_RESPONSE_FLAGS_FAILED_INVALID_PARAMS, 0, 0); return true; } - - u8 txPowerRTL8812AU = *pData; - pData++; - u8 txPowerRTL8812EU = *pData; - pData++; - u8 txPowerAtheros = *pData; - pData++; - u8 txMaxPowerRTL8812AU = *pData; - pData++; - u8 txMaxPowerRTL8812EU = *pData; - pData++; - u8 txMaxPowerAtheros = *pData; - pData++; - u8 cardIndex = *pData; - pData++; - u8 cardPower = *pData; - pData++; - - log_line("Received radio power levels: 8812AU: %d, 8812EU: %d, Atheros: %d, Max: %d, %d, %d", txPowerRTL8812AU, txPowerRTL8812EU, txPowerAtheros, txMaxPowerRTL8812AU, txMaxPowerRTL8812EU, txMaxPowerAtheros); - log_line("Current radio power levels: 8812AU: %d, 8812EU: %d, Atheros: %d, Max: %d, %d, %d", g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU, g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU, g_pCurrentModel->radioInterfacesParams.txPowerAtheros, - g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812AU, g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812EU, g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros); - - log_line("Current radio interfaces count: RTL8812AU: %d, RTL8812EU: %d, Atheros: %d", - hardware_radio_has_rtl8812au_cards(), hardware_radio_has_rtl8812eu_cards(), hardware_radio_has_atheros_cards()); - - sendCommandReply(COMMAND_RESPONSE_FLAGS_OK, 0, 0); - - if ( (txMaxPowerRTL8812AU != 0xFF) && (txMaxPowerRTL8812AU > 0) && (g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812AU != txMaxPowerRTL8812AU) ) - { - g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812AU = txMaxPowerRTL8812AU; - bUpdated = true; - } - if ( (txMaxPowerRTL8812EU != 0xFF) && (txMaxPowerRTL8812EU > 0) && (g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812EU != txMaxPowerRTL8812EU) ) - { - g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812EU = txMaxPowerRTL8812EU; - bUpdated = true; - } - if ( (txMaxPowerAtheros != 0xFF) && (txMaxPowerAtheros > 0) && (g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros != txMaxPowerAtheros)) - { - g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros = txMaxPowerAtheros; - bUpdated = true; - } - - if ( (txPowerRTL8812AU != 0xFF) && (txPowerRTL8812AU > 0) && (g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU != txPowerRTL8812AU) ) - { - g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU = txPowerRTL8812AU; - bUpdatedWiFi = true; - bUpdated = true; - } - if ( (txPowerRTL8812EU != 0xFF) && (txPowerRTL8812EU > 0) && (g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU != txPowerRTL8812EU) ) - { - g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU = txPowerRTL8812EU; - bUpdatedWiFi = true; - bUpdated = true; - } - if ( (txPowerAtheros != 0xFF) && (txPowerAtheros > 0) && (g_pCurrentModel->radioInterfacesParams.txPowerAtheros != txPowerAtheros) ) - { - g_pCurrentModel->radioInterfacesParams.txPowerAtheros = txPowerAtheros; - bUpdatedWiFi = true; - bUpdated = true; - } - - if ( g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU > g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812AU ) + int iCountCards = iParamsLength-1; + if ( iCountCards != *pData ) { - g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU = g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812AU; - bUpdatedWiFi = true; - bUpdated = true; + log_softerror_and_alarm("Received invalid params to set cards tx powers: count cards (%d) different than received buffer size (%d)", *pData, iParamsLength); + sendCommandReply(COMMAND_RESPONSE_FLAGS_FAILED_INVALID_PARAMS, 0, 0); + return true; } - if ( g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU > g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812EU ) + log_line("Received new tx power levels for %d cards:", iCountCards); + for( int i=0; iradioInterfacesParams.txPowerRTL8812EU = g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812EU; - bUpdatedWiFi = true; - bUpdated = true; - } - if ( g_pCurrentModel->radioInterfacesParams.txPowerAtheros > g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros ) - { - g_pCurrentModel->radioInterfacesParams.txPowerAtheros = g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros; - bUpdatedWiFi = true; - bUpdated = true; - } - - if ( (cardPower != 0xFF) && (cardPower > 0) ) - if ( (cardIndex != 0xFF) && (cardIndex < g_pCurrentModel->radioInterfacesParams.interfaces_count) ) - if ( g_pCurrentModel->radioInterfacesParams.interface_power[cardIndex] != cardPower ) - { - g_pCurrentModel->radioInterfacesParams.interface_power[cardIndex] = cardPower; - bUpdated = true; - } - - if ( bUpdatedWiFi ) - { - #ifdef HW_PLATFORM_RASPBERRY - system("sudo mount -o remount,rw /"); - system("sudo mount -o remount,rw /boot"); - #endif - - if ( hardware_radio_has_atheros_cards() ) - if ( g_pCurrentModel->radioInterfacesParams.txPowerAtheros > 0 ) - hardware_radio_set_txpower_atheros((int)g_pCurrentModel->radioInterfacesParams.txPowerAtheros); - if ( hardware_radio_has_rtl8812au_cards() ) - if ( g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU > 0 ) - hardware_radio_set_txpower_rtl8812au((int)g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU); - if ( hardware_radio_has_rtl8812eu_cards() ) - if ( g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU > 0 ) - hardware_radio_set_txpower_rtl8812eu((int)g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU); - } - - if ( bUpdated ) - { - saveCurrentModel(); - signalReloadModel(MODEL_CHANGED_RADIO_POWERS, 0); + log_line("Radio interface %d new tx raw power to set: %d (current: %d)", i+1, pData[i+1], g_pCurrentModel->radioInterfacesParams.interface_raw_power[i]); + if ( pData[i+1] == g_pCurrentModel->radioInterfacesParams.interface_raw_power[i] ) + continue; + g_pCurrentModel->radioInterfacesParams.interface_raw_power[i] = pData[i+1]; } - return true; - } - - if ( uCommandType == COMMAND_ID_SET_RADIO_SLOTTIME ) - { - sendCommandReply(COMMAND_RESPONSE_FLAGS_OK, 0, 0); - g_pCurrentModel->radioInterfacesParams.slotTime = pPHC->command_param; - saveCurrentModel(); - //sprintf(szBuff, "cp /etc/modprobe.d/ath9k_hw.conf tmp/; sed -i 's/slottime=[0-9]*/slottime=%d/g' tmp/ath9k_hw.conf; cp tmp/ath9k_hw.conf /etc/modprobe.d/", pPHC->command_param ); - //hw_execute_bash_command(szBuff, NULL); - return true; - } - - if ( uCommandType == COMMAND_ID_SET_RADIO_THRESH62 ) - { sendCommandReply(COMMAND_RESPONSE_FLAGS_OK, 0, 0); - g_pCurrentModel->radioInterfacesParams.thresh62 = pPHC->command_param; saveCurrentModel(); - //sprintf(szBuff, "cp /etc/modprobe.d/ath9k_hw.conf tmp/; sed -i 's/thresh62=[0-9]*/thresh62=%d/g' tmp/ath9k_hw.conf; cp tmp/ath9k_hw.conf /etc/modprobe.d/", pPHC->command_param ); - //hw_execute_bash_command(szBuff, NULL); + signalReloadModel(MODEL_CHANGED_RADIO_POWERS, 0); return true; } diff --git a/code/r_vehicle/ruby_tx_telemetry.cpp b/code/r_vehicle/ruby_tx_telemetry.cpp index ee6460d4..ef57314e 100644 --- a/code/r_vehicle/ruby_tx_telemetry.cpp +++ b/code/r_vehicle/ruby_tx_telemetry.cpp @@ -110,8 +110,8 @@ u32 s_uLastTotalPacketsReceived = 0; t_packet_header_rc_info_downstream* s_pPHDownstreamInfoRC = NULL; // Info to send back to ground -shared_mem_video_info_stats* s_pSM_VideoInfoStats = NULL; -shared_mem_video_info_stats* s_pSM_VideoInfoStatsRadioOut = NULL; +//shared_mem_video_frames_stats* s_pSM_VideoInfoStats = NULL; +//shared_mem_video_frames_stats* s_pSM_VideoInfoStatsRadioOut = NULL; shared_mem_radio_stats_rx_hist* s_pSM_HistoryRxStats = NULL; static u32 s_uCurrentVideoProfile = MAX_U32; @@ -949,11 +949,10 @@ void check_send_telemetry_to_controller() sPHRTE.flags &= ~(FLAG_RUBY_TELEMETRY_RC_FAILSAFE | FLAG_RUBY_TELEMETRY_RC_ALIVE); - if ( telemetry_time_last_telemetry_received() + TIMEOUT_TELEMETRY_LOST > g_TimeNow ) + if ( (g_TimeNow > TIMEOUT_FC_TELEMETRY_LOST) && (telemetry_time_last_telemetry_received() > g_TimeNow - TIMEOUT_FC_TELEMETRY_LOST) ) sPHRTE.flags |= FLAG_RUBY_TELEMETRY_HAS_VEHICLE_TELEMETRY_DATA; else sPHRTE.flags &= ~(FLAG_RUBY_TELEMETRY_HAS_VEHICLE_TELEMETRY_DATA); - #ifdef FEATURE_ENABLE_RC if ( g_pCurrentModel->rc_params.rc_enabled && NULL != s_pPHDownstreamInfoRC ) { @@ -1172,11 +1171,12 @@ void check_send_telemetry_to_controller() // -------------------------------------- - // Send video info stats + // Send video frames stats + /* if ( NULL == s_pSM_VideoInfoStats ) { - s_pSM_VideoInfoStats = shared_mem_video_info_stats_open_for_read(); + s_pSM_VideoInfoStats = shared_mem_video_frames_stats_open_for_read(); if ( NULL == s_pSM_VideoInfoStats ) log_softerror_and_alarm("Failed to open shared mem video info stats for reading."); else @@ -1185,7 +1185,7 @@ void check_send_telemetry_to_controller() if ( NULL == s_pSM_VideoInfoStatsRadioOut ) { - s_pSM_VideoInfoStatsRadioOut = shared_mem_video_info_stats_radio_out_open_for_read(); + s_pSM_VideoInfoStatsRadioOut = shared_mem_video_frames_stats_radio_out_open_for_read(); if ( NULL == s_pSM_VideoInfoStatsRadioOut ) log_softerror_and_alarm("Failed to open shared mem video info stats radio out for reading."); else @@ -1193,15 +1193,15 @@ void check_send_telemetry_to_controller() } if ( (NULL != g_pCurrentModel) && (NULL != s_pSM_VideoInfoStats) && (NULL != s_pSM_VideoInfoStatsRadioOut) ) - if ( g_pCurrentModel->osd_params.osd_flags[g_pCurrentModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_KEYFRAMES_INFO) + if ( g_pCurrentModel->osd_params.osd_flags[g_pCurrentModel->osd_params.layout] & OSD_FLAG_SHOW_STATS_VIDEO_H264_FRAMES_INFO) { radio_packet_init(&sPH, PACKET_COMPONENT_TELEMETRY, PACKET_TYPE_RUBY_TELEMETRY_VIDEO_INFO_STATS, STREAM_ID_TELEMETRY); sPH.vehicle_id_src = g_pCurrentModel->uVehicleId; - sPH.total_length = (u16)sizeof(t_packet_header) + 2*(u16)sizeof(shared_mem_video_info_stats); + sPH.total_length = (u16)sizeof(t_packet_header) + 2*(u16)sizeof(shared_mem_video_frames_stats); memcpy(buffer, &sPH, sizeof(t_packet_header)); - memcpy(buffer+sizeof(t_packet_header), (u8*)s_pSM_VideoInfoStats, sizeof(shared_mem_video_info_stats)); - memcpy(buffer+sizeof(t_packet_header) + sizeof(shared_mem_video_info_stats), (u8*)s_pSM_VideoInfoStatsRadioOut, sizeof(shared_mem_video_info_stats)); + memcpy(buffer+sizeof(t_packet_header), (u8*)s_pSM_VideoInfoStats, sizeof(shared_mem_video_frames_stats)); + memcpy(buffer+sizeof(t_packet_header) + sizeof(shared_mem_video_frames_stats), (u8*)s_pSM_VideoInfoStatsRadioOut, sizeof(shared_mem_video_frames_stats)); if ( g_bRouterReady && (! s_bRadioInterfacesReinitIsInProgress) ) { @@ -1214,6 +1214,7 @@ void check_send_telemetry_to_controller() if ( NULL != g_pProcessStats ) g_pProcessStats->lastIPCOutgoingTime = g_TimeNow; } + */ // FC RC channels and RC extra packets are sent at the same rate as Ruby telemetry @@ -1351,17 +1352,19 @@ void open_shared_mem_objects() else log_line("Opened shared mem for telemetry tx process watchdog stats for writing."); - s_pSM_VideoInfoStats = shared_mem_video_info_stats_open_for_read(); + /* + s_pSM_VideoInfoStats = shared_mem_video_frames_stats_open_for_read(); if ( NULL == s_pSM_VideoInfoStats ) log_softerror_and_alarm("Failed to open shared mem video info stats for reading."); else log_line("Opened shared mem video info stats for reading."); - s_pSM_VideoInfoStatsRadioOut = shared_mem_video_info_stats_radio_out_open_for_read(); + s_pSM_VideoInfoStatsRadioOut = shared_mem_video_frames_stats_radio_out_open_for_read(); if ( NULL == s_pSM_VideoInfoStatsRadioOut ) log_softerror_and_alarm("Failed to open shared mem video info stats radio out for reading."); else log_line("Opened shared mem video info stats radio out for reading."); + */ s_pSM_HistoryRxStats = shared_mem_radio_stats_rx_hist_open_for_read(); if ( NULL == s_pSM_HistoryRxStats ) @@ -1482,13 +1485,13 @@ int main(int argc, char *argv[]) s_iCurrentDataLinkSerialPortIndex = -1; - for( int i=0; ihardwareInterfacesInfo.serial_bus_count; i++ ) + for( int i=0; ihardwareInterfacesInfo.serial_port_count; i++ ) { - if ( g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) - if ( (g_pCurrentModel->hardwareInterfacesInfo.serial_bus_supported_and_usage[i] & 0xFF) == SERIAL_PORT_USAGE_DATA_LINK ) + if ( g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & MODEL_SERIAL_PORT_BIT_SUPPORTED ) + if ( (g_pCurrentModel->hardwareInterfacesInfo.serial_port_supported_and_usage[i] & 0xFF) == SERIAL_PORT_USAGE_DATA_LINK ) { s_iCurrentDataLinkSerialPortIndex = i; - s_uCurrentDataLinkSerialPortSpeed = g_pCurrentModel->hardwareInterfacesInfo.serial_bus_speed[i]; + s_uCurrentDataLinkSerialPortSpeed = g_pCurrentModel->hardwareInterfacesInfo.serial_port_speed[i]; } } @@ -1536,8 +1539,8 @@ int main(int argc, char *argv[]) log_line("Stopping..."); - shared_mem_video_info_stats_close(s_pSM_VideoInfoStats); - shared_mem_video_info_stats_radio_out_close(s_pSM_VideoInfoStatsRadioOut); + //shared_mem_video_frames_stats_close(s_pSM_VideoInfoStats); + //shared_mem_video_frames_stats_radio_out_close(s_pSM_VideoInfoStatsRadioOut); shared_mem_process_stats_close(SHARED_MEM_WATCHDOG_TELEMETRY_TX, g_pProcessStats); shared_mem_radio_stats_rx_hist_close(s_pSM_HistoryRxStats); @@ -1569,7 +1572,7 @@ void _main_loop() int iSleepTime = 15; if ( g_pCurrentModel->telemetry_params.fc_telemetry_type == TELEMETRY_TYPE_NONE ) - iSleepTime = 40; + iSleepTime = 50; while ( !g_bQuit ) { @@ -1586,7 +1589,7 @@ void _main_loop() _periodic_loop(); if ( g_pCurrentModel->telemetry_params.fc_telemetry_type == TELEMETRY_TYPE_NONE ) - iSleepTime = 40; + iSleepTime = 50; else { if ( telemetry_get_serial_port_file() > 0 ) @@ -1597,9 +1600,10 @@ void _main_loop() telemetry_close_serial_port(); telemetry_open_serial_port(); } - telemetry_try_read_serial_port(); - telemetry_periodic_loop(); iSleepTime = 15; + if ( telemetry_try_read_serial_port() > 0 ) + iSleepTime = 5; + telemetry_periodic_loop(); } try_read_serial_datalink(); @@ -1624,7 +1628,8 @@ void _main_loop() if ( g_pCurrentModel->rc_params.rc_enabled ) if ( g_pCurrentModel->rc_params.flags & RC_FLAGS_OUTPUT_ENABLED ) { - iSleepTime = 10; + if ( iSleepTime > 10 ) + iSleepTime = 10; _send_rc_data_to_FC(); } @@ -1656,7 +1661,6 @@ void _main_loop() continue; } */ - iSleepTime = 15; check_send_telemetry_to_controller(); diff --git a/code/r_vehicle/shared_vars.cpp b/code/r_vehicle/shared_vars.cpp index 048cbad0..aff50cd4 100644 --- a/code/r_vehicle/shared_vars.cpp +++ b/code/r_vehicle/shared_vars.cpp @@ -63,10 +63,10 @@ t_packet_data_controller_link_stats g_PD_LastRecvControllerLinksStats; shared_mem_video_link_graphs g_SM_VideoLinkGraphs; shared_mem_dev_video_bitrate_history g_SM_DevVideoBitrateHistory; -shared_mem_video_info_stats g_VideoInfoStatsCameraOutput; -shared_mem_video_info_stats g_VideoInfoStatsRadioOut; -shared_mem_video_info_stats* g_pSM_VideoInfoStatsRadioOut = NULL; -shared_mem_video_info_stats* g_pSM_VideoInfoStatsCameraOutput = NULL; +//shared_mem_video_frames_stats g_VideoInfoStatsCameraOutput; +//shared_mem_video_frames_stats* g_pSM_VideoInfoStatsRadioOut = NULL; +//shared_mem_video_frames_stats g_VideoInfoStatsRadioOut; +//shared_mem_video_frames_stats* g_pSM_VideoInfoStatsCameraOutput = NULL; int g_iDebugShowKeyFramesAfterRelaySwitch = 0; diff --git a/code/r_vehicle/shared_vars.h b/code/r_vehicle/shared_vars.h index f54dffad..2717496d 100644 --- a/code/r_vehicle/shared_vars.h +++ b/code/r_vehicle/shared_vars.h @@ -91,10 +91,10 @@ extern t_packet_data_controller_link_stats g_PD_LastRecvControllerLinksStats; extern shared_mem_video_link_graphs g_SM_VideoLinkGraphs; extern shared_mem_dev_video_bitrate_history g_SM_DevVideoBitrateHistory; -extern shared_mem_video_info_stats g_VideoInfoStatsCameraOutput; -extern shared_mem_video_info_stats g_VideoInfoStatsRadioOut; -extern shared_mem_video_info_stats* g_pSM_VideoInfoStatsCameraOutput; -extern shared_mem_video_info_stats* g_pSM_VideoInfoStatsRadioOut; +//extern shared_mem_video_frames_stats g_VideoInfoStatsCameraOutput; +//extern shared_mem_video_frames_stats* g_pSM_VideoInfoStatsCameraOutput; +//extern shared_mem_video_frames_stats g_VideoInfoStatsRadioOut; +//extern shared_mem_video_frames_stats* g_pSM_VideoInfoStatsRadioOut; extern int g_iDebugShowKeyFramesAfterRelaySwitch; diff --git a/code/r_vehicle/telemetry_mavlink.cpp b/code/r_vehicle/telemetry_mavlink.cpp index a2e9ba36..2ea22fe9 100644 --- a/code/r_vehicle/telemetry_mavlink.cpp +++ b/code/r_vehicle/telemetry_mavlink.cpp @@ -67,8 +67,6 @@ void _telemetry_mavlink_send_setup() if ( s_bDidSentMAVLinkSetup ) return; - set_time_last_mavlink_message_from_fc(g_TimeNow - 1200); - int componentId = MAV_COMP_ID_MISSIONPLANNER; //int componentId = MAV_COMP_ID_SYSTEM_CONTROL; //int componentId = 255; @@ -362,11 +360,10 @@ void _preprocess_fc_telemetry(t_packet_header_fc_telemetry* pPHFCT) { pPHFCT->fc_telemetry_type = g_pCurrentModel->telemetry_params.fc_telemetry_type; - if ( (g_TimeNow > TIMEOUT_TELEMETRY_LOST) && (get_time_last_mavlink_message_from_fc() + TIMEOUT_TELEMETRY_LOST < g_TimeNow) ) + if ( (g_TimeNow < TIMEOUT_FC_TELEMETRY_LOST) || (get_time_last_mavlink_message_from_fc() < g_TimeNow - TIMEOUT_FC_TELEMETRY_LOST) ) pPHFCT->flags |= FC_TELE_FLAGS_NO_FC_TELEMETRY; else pPHFCT->flags &= ~FC_TELE_FLAGS_NO_FC_TELEMETRY; - if ( g_bDebug ) { pPHFCT->flags &= ~FC_TELE_FLAGS_NO_FC_TELEMETRY; diff --git a/code/r_vehicle/test_link_params.cpp b/code/r_vehicle/test_link_params.cpp index 4487b9b3..620f98f3 100644 --- a/code/r_vehicle/test_link_params.cpp +++ b/code/r_vehicle/test_link_params.cpp @@ -86,8 +86,9 @@ void _test_link_end_and_notify() memcpy(&(g_pCurrentModel->radioLinksParams), &s_RadioLinksParamsToTest, sizeof(type_radio_links_parameters)); - log_line("Current radio power levels: 8812AU: %d, 8812EU: %d, Atheros: %d, Max: %d, %d, %d", g_pCurrentModel->radioInterfacesParams.txPowerRTL8812AU, g_pCurrentModel->radioInterfacesParams.txPowerRTL8812EU, g_pCurrentModel->radioInterfacesParams.txPowerAtheros, - g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812AU, g_pCurrentModel->radioInterfacesParams.txMaxPowerRTL8812EU, g_pCurrentModel->radioInterfacesParams.txMaxPowerAtheros); + log_line("Current radio power levels:"); + for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) + log_line("Radio interface %d raw power level: %d", i+1, g_pCurrentModel->radioInterfacesParams.interface_raw_power[i]); log_line("Current radio interfaces count: RTL8812AU: %d, RTL8812EU: %d, Atheros: %d", hardware_radio_has_rtl8812au_cards(), hardware_radio_has_rtl8812eu_cards(), hardware_radio_has_atheros_cards()); diff --git a/code/r_vehicle/timers.cpp b/code/r_vehicle/timers.cpp index 7a5d596e..ef245fb4 100644 --- a/code/r_vehicle/timers.cpp +++ b/code/r_vehicle/timers.cpp @@ -55,3 +55,4 @@ u32 g_uTimeLastVideoTxOverload = 0; u32 g_uTimeToSaveCameraParams = 0; u32 g_uTimeStartNegociatingRadioLinks = 0; +u32 g_uTimeLastNegociateRadioLinksCommand = 0; diff --git a/code/r_vehicle/timers.h b/code/r_vehicle/timers.h index a630dcc5..8b6a1672 100644 --- a/code/r_vehicle/timers.h +++ b/code/r_vehicle/timers.h @@ -59,3 +59,4 @@ extern u32 g_uTimeLastVideoTxOverload; extern u32 g_uTimeToSaveCameraParams; extern u32 g_uTimeStartNegociatingRadioLinks; +extern u32 g_uTimeLastNegociateRadioLinksCommand; diff --git a/code/r_vehicle/video_source_csi.cpp b/code/r_vehicle/video_source_csi.cpp index a27dbe30..15b3980d 100644 --- a/code/r_vehicle/video_source_csi.cpp +++ b/code/r_vehicle/video_source_csi.cpp @@ -84,7 +84,6 @@ u32 s_uDebugTimeLastCSIVideoInputCheck = 0; u32 s_uDebugCSIInputBytes = 0; u32 s_uDebugCSIInputReads = 0; - static void * _thread_watchdog_video_capture(void *ignored_argument) { int iCount = 0; @@ -352,9 +351,42 @@ u8* video_source_csi_read(int* piReadSize, bool* pbIsInsideIFrame) s_uDebugCSIInputReads++; *piReadSize = iRead; - s_ParserH264_CSICameraOutput.parseData(s_uInputVideoCSIPipeBuffer, iRead, g_TimeNow); + bool bHasIFrameData = false; + bool bHasPPSFrames = false; + int iParsePos = 0; + int iSizeLeft = iRead; + while ( iSizeLeft > 0 ) + { + int iParsed = s_ParserH264_CSICameraOutput.parseDataUntillStartOfNextNAL(&s_uInputVideoCSIPipeBuffer[iParsePos], iSizeLeft, g_TimeNow); + if ( iParsed >= iSizeLeft ) + break; + if ( s_ParserH264_CSICameraOutput.getPreviousFrameType() == 5 ) + bHasIFrameData = true; + if ( s_ParserH264_CSICameraOutput.getCurrentFrameType() == 5 ) + bHasIFrameData = true; + + if ( (s_ParserH264_CSICameraOutput.getCurrentFrameType() == 7) || + (s_ParserH264_CSICameraOutput.getCurrentFrameType() == 8) ) + bHasPPSFrames = true; + //log_line("DEBUG start %u (%d b) of NAL %d, prev NAL: %d, prev size: %d", + // s_uDebugCSIInputReads, iRead, s_ParserH264_CSICameraOutput.getCurrentFrameType(), + // s_ParserH264_CSICameraOutput.getPreviousFrameType(), + // s_ParserH264_CSICameraOutput.getSizeOfLastCompleteFrameInBytes()); + iParsePos += iParsed+1; + iSizeLeft -= iParsed+1; + } if ( NULL != pbIsInsideIFrame ) - *pbIsInsideIFrame = s_ParserH264_CSICameraOutput.IsInsideIFrame(); + *pbIsInsideIFrame = bHasIFrameData; + + /* + static int sssiii = 0; + if ( bHasPPSFrames && iRead < 50 ) + { + sssiii++; + if ( sssiii > 10 ) + *piReadSize = 0; + } + */ return s_uInputVideoCSIPipeBuffer; } diff --git a/code/r_vehicle/video_source_majestic.cpp b/code/r_vehicle/video_source_majestic.cpp index 69732139..6207be2f 100644 --- a/code/r_vehicle/video_source_majestic.cpp +++ b/code/r_vehicle/video_source_majestic.cpp @@ -78,15 +78,23 @@ bool s_bLastReadIsSingleNAL = false; bool s_bLastReadIsEndNAL = false; bool s_bIsInsideIFrameNAL = false; bool s_bIsInsidePictureFrameNAL = false; - +int s_iLastNALSize = 0; u32 s_uTimeLastCheckMajestic = 0; int s_iCountMajestigProcessNotRunning = 0; +u32 s_uLastVideoSourceReadTimestamps[4]; +u32 s_uLastAlarmUDPOveflowTimestamp = 0; +u32 s_uLastTimeMajesticUpdate = 0; + void video_source_majestic_start_capture_program(); void video_source_majestic_stop_capture_program(int iSignal); void video_source_majestic_init_all_params() { + s_uLastTimeMajesticUpdate = g_TimeNow; + for( int i=0; i<(int)(sizeof(s_uLastVideoSourceReadTimestamps)/sizeof(s_uLastVideoSourceReadTimestamps[0])); i++ ) + s_uLastVideoSourceReadTimestamps[i] = 0; + log_line("[VideoSourceUDP] Majestic file size: %d bytes", get_filesize("/usr/bin/majestic") ); hardware_set_oipc_gpu_boost(g_pCurrentModel->processesPriorities.iFreqGPU); @@ -172,6 +180,7 @@ void video_source_majestic_init_all_params() else log_softerror_and_alarm("[VideoSourceUDP] Can't find the PID of majestic"); } + s_uLastTimeMajesticUpdate = g_TimeNow; } void video_source_majestic_close() @@ -208,12 +217,21 @@ int video_source_majestic_open(int iUDPPort) if ( 0 != setsockopt(s_fInputVideoStreamUDPSocket, SOL_SOCKET, SO_RXQ_OVFL, (const void *)&optval , sizeof(optval)) ) log_softerror_and_alarm("[VideoSourceUDP] Unable to set SO_RXQ_OVFL: %s", strerror(errno)); - /* - int iRecvSize = MAX_PACKET_TOTAL_SIZE; - if( 0 != setsockopt(s_fInputVideoStreamUDPSocket, SOL_SOCKET, SO_RCVBUF, (const void *)&iRecvSize , sizeof(iRecvSize))) + + int iRecvSize = 0; + socklen_t iParamLen = sizeof(iRecvSize); + getsockopt(s_fInputVideoStreamUDPSocket, SOL_SOCKET, SO_RCVBUF, &iRecvSize, &iParamLen); + log_line("[VideoSourceUDP] Current socket recv buffer size: %d", iRecvSize); + + int iWantedRecvSize = 512*1024; + if( 0 != setsockopt(s_fInputVideoStreamUDPSocket, SOL_SOCKET, SO_RCVBUF, (const void *)&iWantedRecvSize, sizeof(iWantedRecvSize))) log_softerror_and_alarm("[VideoSourceUDP] Unable to set SO_RCVBUF: %s", strerror(errno)); - */ + iRecvSize = 0; + iParamLen = sizeof(iRecvSize); + getsockopt(s_fInputVideoStreamUDPSocket, SOL_SOCKET, SO_RCVBUF, &iRecvSize, &iParamLen); + log_line("[VideoSourceUDP] New current socket recv buffer size: %d (requested: %d)", iRecvSize, iWantedRecvSize); + memset(&server_addr, 0, sizeof(server_addr)); server_addr.sin_family = AF_INET; server_addr.sin_addr.s_addr = htonl(INADDR_ANY); @@ -260,11 +278,15 @@ void video_source_majestic_start_capture_program() else log_softerror_and_alarm("[VideoSourceUDP] Can't find the PID of majestic"); } + + hardware_camera_set_daylight_off( g_pCurrentModel->camera_params[g_pCurrentModel->iCurrentCamera].profiles[g_pCurrentModel->camera_params[g_pCurrentModel->iCurrentCamera].iCurrentProfile].uFlags & CAMERA_FLAG_OPENIPC_DAYLIGHT_OFF); + adaptive_video_on_capture_restarted(); s_uTimeLastCheckMajestic = g_TimeNow-3000; s_iCountMajestigProcessNotRunning = 0; s_uTimeStartVideoInput = g_TimeNow; s_bLogStartOfInputVideoData = true; + s_uLastTimeMajesticUpdate = g_TimeNow; } void video_source_majestic_stop_capture_program(int iSignal) @@ -301,24 +323,38 @@ void video_source_majestic_set_keyframe_value(float fGOP) { char szComm[128]; char szOutput[256]; - sprintf(szComm, "curl localhost/api/v1/set?video0.gopSize=%.1f", fGOP); + sprintf(szComm, "curl -s localhost/api/v1/set?video0.gopSize=%.1f", fGOP); hw_execute_bash_command_raw(szComm, szOutput); - //hw_execute_bash_command_raw("curl localhost/api/v1/reload", szOutput); + //hw_execute_bash_command_raw("curl -s localhost/api/v1/reload", szOutput); //sprintf(szComm, "cli -s .video0.gopSize %.1f", fGOP); //hw_execute_bash_command_raw(szComm, NULL); //hw_execute_bash_command_raw("killall -1 majestic", NULL); + s_uLastTimeMajesticUpdate = g_TimeNow; } void video_source_majestic_set_videobitrate_value(u32 uBitrate) { char szComm[128]; //char szOutput[256]; - sprintf(szComm, "curl localhost/api/v1/set?video0.bitrate=%u", uBitrate/1000); + sprintf(szComm, "curl -s localhost/api/v1/set?video0.bitrate=%u", uBitrate/1000); hw_execute_bash_command_raw(szComm, NULL); sprintf(szComm, "cli -s .video0.bitrate %u", uBitrate/1000); hw_execute_bash_command(szComm, NULL); - //hw_execute_bash_command_raw("curl localhost/api/v1/reload", szOutput); + //hw_execute_bash_command_raw("curl -s localhost/api/v1/reload", szOutput); + s_uLastTimeMajesticUpdate = g_TimeNow; +} + +void video_source_majestic_set_qpdelta_value(int iqpdelta) +{ + char szComm[128]; + //char szOutput[256]; + sprintf(szComm, "curl -s localhost/api/v1/set?video0.qpDelta=%d", iqpdelta); + hw_execute_bash_command_raw(szComm, NULL); + sprintf(szComm, "cli -s .video0.qpDelta %d", iqpdelta); + hw_execute_bash_command(szComm, NULL); + //hw_execute_bash_command_raw("curl -s localhost/api/v1/reload", szOutput); + s_uLastTimeMajesticUpdate = g_TimeNow; } int _video_source_majestic_try_read_input_udp_data(bool bAsync) @@ -384,6 +420,10 @@ int _video_source_majestic_try_read_input_udp_data(bool bAsync) return -1; } + for( int i=3; i>0; i-- ) + s_uLastVideoSourceReadTimestamps[i] = s_uLastVideoSourceReadTimestamps[i-1]; + s_uLastVideoSourceReadTimestamps[0] = g_TimeNow; + if ( nRecvBytes > MAX_PACKET_TOTAL_SIZE ) { log_softerror_and_alarm("[VideoSourceUDP] Read too much data %d bytes from UDP socket", nRecvBytes); @@ -394,7 +434,30 @@ int _video_source_majestic_try_read_input_udp_data(bool bAsync) uint32_t cur_rxq_overflow = extract_udp_rxq_overflow(&msghdr); if (cur_rxq_overflow != rxq_overflow) { - log_softerror_and_alarm("[VideoSourceUDP] UDP rxq overflow: %u packets dropped (from %u to %u)", cur_rxq_overflow - rxq_overflow, rxq_overflow, cur_rxq_overflow); + u32 uDroppedCount = cur_rxq_overflow - rxq_overflow; + log_softerror_and_alarm("[VideoSourceUDP] UDP rxq overflow: %u packets dropped (from %u to %u)", uDroppedCount, rxq_overflow, cur_rxq_overflow); + + if ( g_TimeNow > s_uLastAlarmUDPOveflowTimestamp + 10000 ) + if ( g_TimeNow > g_TimeStart + 10000 ) + if ( g_TimeNow > s_uLastTimeMajesticUpdate + 3000 ) + { + s_uLastAlarmUDPOveflowTimestamp = g_TimeNow; + u32 uFlags2 = 0; + u32 uDelta = s_uLastVideoSourceReadTimestamps[0] - s_uLastVideoSourceReadTimestamps[1]; + if ( uDelta > 255 ) + uDelta = 255; + uFlags2 |= uDelta & 0xFF; + uDelta = s_uLastVideoSourceReadTimestamps[1] - s_uLastVideoSourceReadTimestamps[2]; + if ( uDelta > 255 ) + uDelta = 255; + uFlags2 |= (uDelta & 0xFF) << 8; + uDelta = s_uLastVideoSourceReadTimestamps[2] - s_uLastVideoSourceReadTimestamps[3]; + if ( uDelta > 255 ) + uDelta = 255; + uFlags2 |= (uDelta & 0xFF) << 16; + + send_alarm_to_controller(ALARM_ID_VIDEO_CAPTURE_MALFUNCTION, 0x0002 | ((uDroppedCount & 0xFF) << 8), uFlags2, 5); + } rxq_overflow = cur_rxq_overflow; } } @@ -466,7 +529,7 @@ int _video_source_majestic_parse_rtp_data(u8* pInputRawData, int iInputBytes) u16 uRTPSeqNb = (((u16)pInputRawData[2]) << 8) | pInputRawData[3]; - if ( 0 != s_uLastRTLSeqNumberInUDPFrame ) + if ( (0 != s_uLastRTLSeqNumberInUDPFrame) && (65535 != s_uLastRTLSeqNumberInUDPFrame) ) if ( (s_uLastRTLSeqNumberInUDPFrame + 1) != uRTPSeqNb ) log_softerror_and_alarm("[VideoSourceUDP] Read skipped RTP frames, from seqnb %d to seqnb %d", s_uLastRTLSeqNumberInUDPFrame, uRTPSeqNb); s_uLastRTLSeqNumberInUDPFrame = uRTPSeqNb; @@ -499,7 +562,6 @@ int _video_source_majestic_parse_rtp_data(u8* pInputRawData, int iInputBytes) // Single compact (non-fragmented, non I/P frame (slice)) NAL unit (ie. SPS, PPS, etc) if ( (uNALTypeH264 != 28) && (uNALTypeH265 != 49) ) { - //log_line("DEBUG single NAL-264 %d, NAL-265 %d, header byte: %d", uNALTypeH264, uNALTypeH265, uNALHeaderByte); // Regular NAL unit s_bLastReadIsSingleNAL = true; s_bLastReadIsEndNAL = true; @@ -509,7 +571,9 @@ int _video_source_majestic_parse_rtp_data(u8* pInputRawData, int iInputBytes) memcpy(s_uOutputUDPNALFrameSegment, uNALOutputHeader, iNALOutputHeaderSize); memcpy(&s_uOutputUDPNALFrameSegment[iNALOutputHeaderSize], pInputRawData, iInputBytes); iOutputBytes = iInputBytes + iNALOutputHeaderSize; - //log_line("DEBUG parsed regular NAL %d, header byte %d, returned %d bytes as a NAL", uNALTypeH264, uNALHeaderByte, iOutputBytes ); + s_iLastNALSize += iOutputBytes; + //log_line("DEBUG NAL SPS/PPS: %d bytes", s_iLastNALSize); + s_iLastNALSize = 0; return iOutputBytes; } @@ -567,15 +631,21 @@ int _video_source_majestic_parse_rtp_data(u8* pInputRawData, int iInputBytes) } - //log_line("DEBUG fragment NAL-264 %d, NAL-265 %d, header byte: %d, start: %d, end: %d", - // uNALTypeH264, uNALTypeH265, uNALHeaderByte, uFUStartBit? 1:0, uFUEndBit?1:0); - if ( uFUEndBit ) + { s_bLastReadIsEndNAL = true; + s_iLastNALSize += iInputBytes; + //if ( s_bIsInsideIFrameNAL ) + // log_line("DEBUG NAL I: %d bytes", s_iLastNALSize); + //else + // log_line("DEBUG NAL P: %d bytes", s_iLastNALSize); + s_iLastNALSize = 0; + } + else + s_iLastNALSize += iInputBytes; if (uFUStartBit) { - //log_line("DEBUG start bit"); memcpy(s_uOutputUDPNALFrameSegment, uNALOutputHeader, iNALOutputHeaderSize); memcpy(&s_uOutputUDPNALFrameSegment[iNALOutputHeaderSize], pInputRawData, iInputBytes); iOutputBytes = iInputBytes + iNALOutputHeaderSize; @@ -589,7 +659,6 @@ int _video_source_majestic_parse_rtp_data(u8* pInputRawData, int iInputBytes) //log_line("DEBUG parsed middle of NAL, type %d, end bit: %d, output %d bytes as middle of NAL", // uNALTypeH264, uFUEndBit?1:0, iOutputBytes); } - return iOutputBytes; } @@ -661,30 +730,30 @@ void _video_source_majestic_check_params_update() bool bUpdatedImageParams = false; if ( (s_uRequestedVideoMajesticCaptureUpdateReason & 0xFF) == MODEL_CHANGED_CAMERA_BRIGHTNESS ) { - sprintf(szComm, "curl localhost/api/v1/set?image.luminance=%u", uParam); + sprintf(szComm, "curl -s localhost/api/v1/set?image.luminance=%u", uParam); hw_execute_bash_command_raw(szComm, szOutput); - //hw_execute_bash_command_raw("curl localhost/api/v1/reload", szOutput); + //hw_execute_bash_command_raw("curl -s localhost/api/v1/reload", szOutput); bUpdatedImageParams = true; } else if ( (s_uRequestedVideoMajesticCaptureUpdateReason & 0xFF) == MODEL_CHANGED_CAMERA_CONTRAST ) { - sprintf(szComm, "curl localhost/api/v1/set?image.contrast=%u", uParam); + sprintf(szComm, "curl -s localhost/api/v1/set?image.contrast=%u", uParam); hw_execute_bash_command_raw(szComm, szOutput); - //hw_execute_bash_command_raw("curl localhost/api/v1/reload", szOutput); + //hw_execute_bash_command_raw("curl -s localhost/api/v1/reload", szOutput); bUpdatedImageParams = true; } else if ( (s_uRequestedVideoMajesticCaptureUpdateReason & 0xFF) == MODEL_CHANGED_CAMERA_SATURATION ) { - sprintf(szComm, "curl localhost/api/v1/set?image.saturation=%u", uParam/2); + sprintf(szComm, "curl -s localhost/api/v1/set?image.saturation=%u", uParam/2); hw_execute_bash_command_raw(szComm, szOutput); - //hw_execute_bash_command_raw("curl localhost/api/v1/reload", szOutput); + //hw_execute_bash_command_raw("curl -s localhost/api/v1/reload", szOutput); bUpdatedImageParams = true; } else if ( (s_uRequestedVideoMajesticCaptureUpdateReason & 0xFF) == MODEL_CHANGED_CAMERA_HUE ) { - sprintf(szComm, "curl localhost/api/v1/set?image.hue=%u", uParam); + sprintf(szComm, "curl -s localhost/api/v1/set?image.hue=%u", uParam); hw_execute_bash_command_raw(szComm, szOutput); - //hw_execute_bash_command_raw("curl localhost/api/v1/reload", szOutput); + //hw_execute_bash_command_raw("curl -s localhost/api/v1/reload", szOutput); bUpdatedImageParams = true; } @@ -694,6 +763,7 @@ void _video_source_majestic_check_params_update() s_bHasPendingMajesticRealTimeChanges = true; s_uTimeLastMajesticImageRealTimeUpdate = g_TimeNow; s_uRequestedVideoMajesticCaptureUpdateReason = 0; + s_uLastTimeMajesticUpdate = g_TimeNow; return; } @@ -801,6 +871,7 @@ void video_source_majestic_periodic_checks() camera_profile_parameters_t* pCameraParams = &(g_pCurrentModel->camera_params[g_pCurrentModel->iCurrentCamera].profiles[g_pCurrentModel->camera_params[g_pCurrentModel->iCurrentCamera].iCurrentProfile]); // Save image settings to yaml file hardware_camera_apply_all_majestic_camera_settings(pCameraParams); + s_uLastTimeMajesticUpdate = g_TimeNow; } if ( s_bRequestedVideoMajesticCaptureUpdate ) diff --git a/code/r_vehicle/video_source_majestic.h b/code/r_vehicle/video_source_majestic.h index 0304c194..1b8dfdf1 100644 --- a/code/r_vehicle/video_source_majestic.h +++ b/code/r_vehicle/video_source_majestic.h @@ -12,6 +12,7 @@ void video_source_majestic_stop_capture_program(int iSignal); void video_source_majestic_request_update_program(u32 uChangeReason); void video_source_majestic_set_keyframe_value(float fGOP); void video_source_majestic_set_videobitrate_value(u32 uBitrate); +void video_source_majestic_set_qpdelta_value(int iqpdelta); // Returns the buffer and number of bytes read u8* video_source_majestic_read(int* piReadSize, bool bAsync); diff --git a/code/r_vehicle/video_tx_buffers.cpp b/code/r_vehicle/video_tx_buffers.cpp index 681fb236..998690b1 100644 --- a/code/r_vehicle/video_tx_buffers.cpp +++ b/code/r_vehicle/video_tx_buffers.cpp @@ -72,6 +72,7 @@ VideoTxPacketsBuffer::VideoTxPacketsBuffer(int iVideoStreamIndex, int iCameraInd m_VideoPackets[i][k].pPHVF = NULL; m_VideoPackets[i][k].pVideoData = NULL; } + m_uCurrentFrameId = 0; m_iCurrentBufferIndexToSend = 0; m_iCurrentBufferPacketIndexToSend = 0; m_iNextBufferIndexToFill = 0; @@ -189,6 +190,7 @@ void VideoTxPacketsBuffer::_fillVideoPacketHeaders(int iBufferIndex, int iPacket t_packet_header_video_full_98* pCurrentVideoPacketHeader = m_VideoPackets[iBufferIndex][iPacketIndex].pPHVF; memcpy(pCurrentVideoPacketHeader, &m_PacketHeaderVideo, sizeof(t_packet_header_video_full_98)); + pCurrentVideoPacketHeader->uFrameId = m_uCurrentFrameId; pCurrentVideoPacketHeader->uCurrentBlockIndex = m_uNextVideoBlockIndexToGenerate; pCurrentVideoPacketHeader->uCurrentBlockPacketIndex = m_uNextVideoBlockPacketIndexToGenerate; @@ -319,6 +321,7 @@ void VideoTxPacketsBuffer::fillVideoPackets(u8* pVideoData, int iDataSize, bool { addNewVideoPacket(m_TempVideoBuffer, m_iTempVideoBufferFilledBytes, bEndOfFrame, bIsInsideIFrame); m_iTempVideoBufferFilledBytes = 0; + m_uCurrentFrameId++; } return; } @@ -351,7 +354,7 @@ void VideoTxPacketsBuffer::addNewVideoPacket(u8* pVideoData, int iDataSize, bool // Update packet headers _fillVideoPacketHeaders(m_iNextBufferIndexToFill, m_iNextBufferPacketIndexToFill, iDataSize + sizeof(u16), bEndOfFrame, bIsInsideIFrame); - t_packet_header* pCurrentPacketHeader = m_VideoPackets[m_iNextBufferIndexToFill][m_iNextBufferPacketIndexToFill].pPH; + //t_packet_header* pCurrentPacketHeader = m_VideoPackets[m_iNextBufferIndexToFill][m_iNextBufferPacketIndexToFill].pPH; t_packet_header_video_full_98* pCurrentVideoPacketHeader = m_VideoPackets[m_iNextBufferIndexToFill][m_iNextBufferPacketIndexToFill].pPHVF; u8* pVideoDestination = m_VideoPackets[m_iNextBufferIndexToFill][m_iNextBufferPacketIndexToFill].pVideoData; if ( m_PacketHeaderVideo.uVideoStatusFlags2 & VIDEO_STATUS_FLAGS2_HAS_DEBUG_TIMESTAMPS ) @@ -426,7 +429,7 @@ void VideoTxPacketsBuffer::addNewVideoPacket(u8* pVideoData, int iDataSize, bool // Update packet headers _fillVideoPacketHeaders(m_iNextBufferIndexToFill, i+iECDelta, m_PacketHeaderVideo.uCurrentBlockPacketSize, bEndOfFrame, bIsInsideIFrame); - pCurrentPacketHeader = m_VideoPackets[m_iNextBufferIndexToFill][i+iECDelta].pPH; + //pCurrentPacketHeader = m_VideoPackets[m_iNextBufferIndexToFill][i+iECDelta].pPH; pCurrentVideoPacketHeader = m_VideoPackets[m_iNextBufferIndexToFill][i+iECDelta].pPHVF; pVideoDestination = m_VideoPackets[m_iNextBufferIndexToFill][i+iECDelta].pVideoData; diff --git a/code/r_vehicle/video_tx_buffers.h b/code/r_vehicle/video_tx_buffers.h index e4392e61..0630e2e2 100644 --- a/code/r_vehicle/video_tx_buffers.h +++ b/code/r_vehicle/video_tx_buffers.h @@ -44,6 +44,7 @@ class VideoTxPacketsBuffer int m_iCameraIndex; int m_iVideoStreamInfoIndex; + u16 m_uCurrentFrameId; u32 m_uNextVideoBlockIndexToGenerate; u32 m_uNextVideoBlockPacketIndexToGenerate; u32 m_uNextBlockPacketSize; diff --git a/code/radio/radio_duplicate_det.c b/code/radio/radio_duplicate_det.c index 552332f7..2e403c7c 100644 --- a/code/radio/radio_duplicate_det.c +++ b/code/radio/radio_duplicate_det.c @@ -61,12 +61,12 @@ t_vehicle_history_packets_indexes s_ListHistoryRxPacketsVehicles[MAX_CONCURENT_V extern u32 s_uRadioRxTimeNow; -void _radio_dd_reset_duplication_stats_for_vehicle(int iVehicleIndex) +void _radio_dd_reset_duplication_stats_for_vehicle(int iVehicleIndex, int iReason) { if ( iVehicleIndex < 0 || iVehicleIndex >= MAX_CONCURENT_VEHICLES ) return; - log_line("[RadioRxThread] Reset duplicate detection info for VID %u, index %d", s_ListHistoryRxPacketsVehicles[iVehicleIndex].uVehicleId, iVehicleIndex); + log_line("[RadioRxThread] Reset duplicate detection info for VID %u, buff index %d, reason: %d", s_ListHistoryRxPacketsVehicles[iVehicleIndex].uVehicleId, iVehicleIndex, iReason); s_ListHistoryRxPacketsVehicles[iVehicleIndex].uVehicleId = 0; s_ListHistoryRxPacketsVehicles[iVehicleIndex].iRestartDetected = 0; @@ -83,7 +83,7 @@ void _radio_dd_reset_duplication_stats_for_vehicle(int iVehicleIndex) void radio_duplicate_detection_init() { for( int i=0; i= (int)sizeof(t_packet_header)) ) { t_packet_header* pPH = (t_packet_header*)pPacketBuffer; - log_line("[RadioDuplicateDetection] Received packet type: %s, %d bytes, source VID: %u, dest VID:%u", - str_get_packet_type(pPH->packet_type), pPH->total_length, pPH->vehicle_id_src, pPH->vehicle_id_dest); + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + log_line("[RadioDuplicateDetection] Received packet type: %s, %d bytes, source VID: %u, dest VID:%u", + str_get_packet_type(pPH->packet_type), pPH->total_length, pPH->vehicle_id_src, pPH->vehicle_id_dest); + } + else if ( (NULL != pPacketBuffer) && (iPacketLength >= (int)sizeof(t_packet_header_compressed)) ) + { + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pPacketBuffer; + if ( (pPHC->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + log_line("[RadioDuplicateDetection] Received packet type: %s, %d bytes, source VID: %u, dest VID:%u", + str_get_packet_type(pPHC->packet_type), pPHC->total_length, pPHC->vehicle_id_src, pPHC->vehicle_id_dest); } char szBuff[256]; @@ -172,7 +180,7 @@ int _radio_dup_detection_get_runtime_index_for_vid(u32 uVehicleId, u8* pPacketBu } s_ListHistoryRxPacketsVehicles[iStatsIndex].uVehicleId = uVehicleId; - _radio_dd_reset_duplication_stats_for_vehicle(iStatsIndex); + _radio_dd_reset_duplication_stats_for_vehicle(iStatsIndex, 1); s_ListHistoryRxPacketsVehicles[iStatsIndex].uVehicleId = uVehicleId; szBuff[0] = 0; @@ -196,10 +204,26 @@ int radio_dup_detection_is_duplicate(int iRadioInterfaceIndex, u8* pPacketBuffer return 1; t_packet_header* pPH = (t_packet_header*)pPacketBuffer; - u32 uVehicleId = pPH->vehicle_id_src; - u32 uStreamPacketIndex = (pPH->stream_packet_idx) & PACKET_FLAGS_MASK_STREAM_PACKET_IDX; - u32 uStreamIndex = (pPH->stream_packet_idx)>>PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pPacketBuffer; + u32 uVehicleId = 0; + u32 uStreamPacketIndex = 0; + u32 uStreamIndex = 0; + u8 uPacketType = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + uVehicleId = pPHC->vehicle_id_src; + uStreamPacketIndex = (pPHC->stream_packet_idx) & PACKET_FLAGS_MASK_STREAM_PACKET_IDX; + uStreamIndex = (pPHC->stream_packet_idx)>>PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + uPacketType = pPHC->packet_type; + } + else + { + uVehicleId = pPH->vehicle_id_src; + uStreamPacketIndex = (pPH->stream_packet_idx) & PACKET_FLAGS_MASK_STREAM_PACKET_IDX; + uStreamIndex = (pPH->stream_packet_idx)>>PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; + uPacketType = pPH->packet_type; + } int iStatsIndex = -1; iStatsIndex = _radio_dup_detection_get_runtime_index_for_vid(uVehicleId, pPacketBuffer, iPacketLength); @@ -211,19 +235,20 @@ int radio_dup_detection_is_duplicate(int iRadioInterfaceIndex, u8* pPacketBuffer static u32 s_TimeLastLogAlarmStreamPacketsVariation = 0; + u32 uMaxDeltaForVideoStream = 2000; u32 uMaxDeltaForDataStream = 50; if ( hardware_radio_index_is_serial_radio(iRadioInterfaceIndex) ) uMaxDeltaForDataStream = 200; if ((pDupInfo->streamsPacketsHistory[uStreamIndex].uMaxReceivedPacketIndex > uMaxDeltaForDataStream ) && - ((pPH->stream_packet_idx & PACKET_FLAGS_MASK_STREAM_PACKET_IDX) < pDupInfo->streamsPacketsHistory[uStreamIndex].uMaxReceivedPacketIndex - uMaxDeltaForDataStream) ) + (uStreamPacketIndex < pDupInfo->streamsPacketsHistory[uStreamIndex].uMaxReceivedPacketIndex - uMaxDeltaForDataStream) ) if ( pDupInfo->streamsPacketsHistory[uStreamIndex].uLastTimeReceivedPacket > uTimeNow - 4000 ) if ( uTimeNow > s_TimeLastLogAlarmStreamPacketsVariation + 1000 ) { s_TimeLastLogAlarmStreamPacketsVariation = get_current_timestamp_ms(); log_line("[RadioDuplicateDetection] Received stream-%d packet index %u on radio interface %d, is %u packets older than max packet for the stream (%u).", - (int)uStreamIndex, iRadioInterfaceIndex+1, (pPH->stream_packet_idx & PACKET_FLAGS_MASK_STREAM_PACKET_IDX), - pDupInfo->streamsPacketsHistory[uStreamIndex].uMaxReceivedPacketIndex-(pPH->stream_packet_idx & PACKET_FLAGS_MASK_STREAM_PACKET_IDX), + (int)uStreamIndex, iRadioInterfaceIndex+1, uStreamPacketIndex, + pDupInfo->streamsPacketsHistory[uStreamIndex].uMaxReceivedPacketIndex-uStreamPacketIndex, pDupInfo->streamsPacketsHistory[uStreamIndex].uMaxReceivedPacketIndex); } @@ -232,16 +257,16 @@ int radio_dup_detection_is_duplicate(int iRadioInterfaceIndex, u8* pPacketBuffer int iStreamRestarted = 0; - if ( uStreamIndex >= STREAM_ID_VIDEO_1 ) - if ( pDupInfo->streamsPacketsHistory[uStreamIndex].uMaxReceivedPacketIndex > uStreamPacketIndex + 4000 ) + if ( (uStreamIndex >= STREAM_ID_VIDEO_1) || (uStreamIndex == STREAM_ID_COMPRESSED) ) + if ( pDupInfo->streamsPacketsHistory[uStreamIndex].uMaxReceivedPacketIndex > uStreamPacketIndex + uMaxDeltaForVideoStream ) iStreamRestarted = 1; - if ( uStreamIndex < STREAM_ID_VIDEO_1 ) + if ( (uStreamIndex < STREAM_ID_VIDEO_1) && (uStreamIndex != STREAM_ID_COMPRESSED) ) if ( pDupInfo->streamsPacketsHistory[uStreamIndex].uMaxReceivedPacketIndex > uStreamPacketIndex + uMaxDeltaForDataStream ) iStreamRestarted = 1; - if ( uStreamPacketIndex < pDupInfo->streamsPacketsHistory[uStreamIndex].uMaxReceivedPacketIndex ) - if ( pDupInfo->streamsPacketsHistory[uStreamIndex].uLastTimeReceivedPacket < uTimeNow - 4000 ) + if ( pDupInfo->streamsPacketsHistory[uStreamIndex].uLastTimeReceivedPacket < uTimeNow - 8000 ) + if ( uStreamPacketIndex+10 < pDupInfo->streamsPacketsHistory[uStreamIndex].uMaxReceivedPacketIndex ) iStreamRestarted = 1; if ( iStreamRestarted ) @@ -250,7 +275,7 @@ int radio_dup_detection_is_duplicate(int iRadioInterfaceIndex, u8* pPacketBuffer uVehicleId, uStreamIndex, str_get_radio_stream_name(uStreamIndex), uStreamPacketIndex, pDupInfo->streamsPacketsHistory[uStreamIndex].uMaxReceivedPacketIndex, uTimeNow - pDupInfo->streamsPacketsHistory[uStreamIndex].uLastTimeReceivedPacket ); - _radio_dd_reset_duplication_stats_for_vehicle(iStatsIndex); + _radio_dd_reset_duplication_stats_for_vehicle(iStatsIndex, 2); pDupInfo->iRestartDetected = 1; pDupInfo->uVehicleId = uVehicleId; } @@ -266,7 +291,7 @@ int radio_dup_detection_is_duplicate(int iRadioInterfaceIndex, u8* pPacketBuffer if ( uStreamPacketIndex == pDupInfo->streamsPacketsHistory[uStreamIndex].packetsHashIndexes[iHashIndex] ) bIsDuplicatePacket = 1; - if ( (pPH->packet_type == PACKET_TYPE_RUBY_PING_CLOCK) || (pPH->packet_type == PACKET_TYPE_RUBY_PING_CLOCK_REPLY) ) + if ( (uPacketType == PACKET_TYPE_RUBY_PING_CLOCK) || (uPacketType == PACKET_TYPE_RUBY_PING_CLOCK_REPLY) ) bIsDuplicatePacket = 0; if ( bIsDuplicatePacket ) @@ -291,7 +316,7 @@ void radio_duplicate_detection_remove_data_for_all_except(u32 uVehicleId) for( int i=0; iuVehicleId = uVehicleId; + // End: Compute index of stats to use //---------------------------------------------- + return pStatsVehicle; +} - pStatsVehicle->uVehicleId = uVehicleId; +// returns the number of missing packets detected on the radio link +int _radio_rx_update_local_stats_on_new_radio_packet(int iInterface, int iIsShortPacket, u32 uVehicleId, u8* pPacket, int iLength, int iDataIsOk) +{ + if ( (NULL == pPacket) || ( iLength <= 2 ) ) + return 0; + + int nReturnLost = 0; + + t_radio_rx_state_vehicle* pStatsVehicle = _radio_rx_get_stats_structure_for_vehicle(uVehicleId); if ( iDataIsOk ) { @@ -166,22 +174,27 @@ int _radio_rx_update_local_stats_on_new_radio_packet(int iInterface, int iIsShor else { t_packet_header* pPH = (t_packet_header*)pPacket; - if ( pStatsVehicle->uLastRxRadioLinkPacketIndex[iInterface] > 0 ) - if ( pPH->radio_link_packet_index > pStatsVehicle->uLastRxRadioLinkPacketIndex[iInterface]+1 ) + + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) { - u32 lost = pPH->radio_link_packet_index - (pStatsVehicle->uLastRxRadioLinkPacketIndex[iInterface] + 1); - pStatsVehicle->uTotalRxPacketsLost += lost; - pStatsVehicle->uTmpRxPacketsLost += lost; - nReturnLost = lost; - } + // Check for lost packets + if ( pStatsVehicle->uLastRxRadioLinkPacketIndex[iInterface] > 0 ) + if ( pPH->radio_link_packet_index > pStatsVehicle->uLastRxRadioLinkPacketIndex[iInterface]+1 ) + { + u32 lost = pPH->radio_link_packet_index - (pStatsVehicle->uLastRxRadioLinkPacketIndex[iInterface] + 1); + pStatsVehicle->uTotalRxPacketsLost += lost; + pStatsVehicle->uTmpRxPacketsLost += lost; + nReturnLost = lost; + } - if ( pStatsVehicle->uLastRxRadioLinkPacketIndex[iInterface] > 0 ) - if ( pStatsVehicle->uLastRxRadioLinkPacketIndex[iInterface] < 0xFA00 ) - if ( pPH->radio_link_packet_index > 0x0500 ) - if ( pPH->radio_link_packet_index < pStatsVehicle->uLastRxRadioLinkPacketIndex[iInterface] ) - radio_dup_detection_set_vehicle_restarted_flag(pPH->vehicle_id_src); + // Check for restarted on the other end + //if ( pStatsVehicle->uLastRxRadioLinkPacketIndex[iInterface] > 10 ) + //if ( pStatsVehicle->uLastRxRadioLinkPacketIndex[iInterface] < 0xFFFF-10 ) // pPH->radio_link_packet_index is 16 bits + //if ( pPH->radio_link_packet_index < pStatsVehicle->uLastRxRadioLinkPacketIndex[iInterface]-10 ) + // radio_dup_detection_set_vehicle_restarted_flag(pPH->vehicle_id_src); - pStatsVehicle->uLastRxRadioLinkPacketIndex[iInterface] = pPH->radio_link_packet_index; + pStatsVehicle->uLastRxRadioLinkPacketIndex[iInterface] = pPH->radio_link_packet_index; + } } return nReturnLost; } @@ -216,58 +229,121 @@ void _radio_rx_update_fd_sets() s_iRadioRxMaxFD++; } + + +u8* _radio_rx_wait_get_queue_packet(t_radio_rx_state_packets_queue* pQueue, int iHighPriorityQueue, u32 uTimeoutMicroSec, int* pLength, int* pIsShortPacket, int* pRadioInterfaceIndex) +{ + int iRes = -1; + + if ( 0 == uTimeoutMicroSec ) + { + iRes = sem_trywait(pQueue->pSemaphoreRead); + } + else + { + struct timespec ts; + clock_gettime(CLOCK_REALTIME, &ts); + ts.tv_nsec += 1000*uTimeoutMicroSec; + iRes = sem_timedwait(pQueue->pSemaphoreRead, &ts); + } + if ( 0 != iRes ) + return NULL; + + int iIndexToCopy = 0; + + iIndexToCopy = pQueue->iCurrentPacketIndexToConsume; + if ( NULL != pLength ) + *pLength = pQueue->iPacketsLengths[iIndexToCopy]; + if ( NULL != pIsShortPacket ) + *pIsShortPacket = pQueue->uPacketsAreShort[iIndexToCopy]; + if ( NULL != pRadioInterfaceIndex ) + *pRadioInterfaceIndex = pQueue->uPacketsRxInterface[iIndexToCopy]; + + memcpy(s_tmpLastProcessedRadioRxPacket, pQueue->pPacketsBuffers[iIndexToCopy], pQueue->iPacketsLengths[iIndexToCopy]); + + pQueue->iCurrentPacketIndexToConsume++; + if ( pQueue->iCurrentPacketIndexToConsume >= pQueue->iQueueSize ) + pQueue->iCurrentPacketIndexToConsume = 0; + + return s_tmpLastProcessedRadioRxPacket; +} + +u8* radio_rx_wait_get_next_received_high_prio_packet(u32 uTimeoutMicroSec, int* pLength, int* pIsShortPacket, int* pRadioInterfaceIndex) +{ + if ( NULL != pLength ) + *pLength = 0; + if ( NULL != pIsShortPacket ) + *pIsShortPacket = 0; + if ( NULL != pRadioInterfaceIndex ) + *pRadioInterfaceIndex = 0; + if ( 0 == s_iRadioRxInitialized ) + return NULL; + + return _radio_rx_wait_get_queue_packet(&(s_RadioRxState.queue_high_priority), 1, uTimeoutMicroSec, pLength, pIsShortPacket, pRadioInterfaceIndex); +} + +u8* radio_rx_wait_get_next_received_reg_prio_packet(u32 uTimeoutMicroSec, int* pLength, int* pIsShortPacket, int* pRadioInterfaceIndex) +{ + if ( NULL != pLength ) + *pLength = 0; + if ( NULL != pIsShortPacket ) + *pIsShortPacket = 0; + if ( NULL != pRadioInterfaceIndex ) + *pRadioInterfaceIndex = 0; + if ( 0 == s_iRadioRxInitialized ) + return NULL; + + return _radio_rx_wait_get_queue_packet(&(s_RadioRxState.queue_reg_priority), 0, uTimeoutMicroSec, pLength, pIsShortPacket, pRadioInterfaceIndex); +} + void _radio_rx_add_packet_to_rx_queue(u8* pPacket, int iLength, int iRadioInterface) { if ( (NULL == pPacket) || (iLength <= 0) || s_iRadioRxMarkedForQuit ) return; - t_radio_rx_state_packets_queue* pQueue = &s_RadioRxState.queue_reg_priority; t_packet_header* pPH = (t_packet_header*)pPacket; - if ( radio_packet_type_is_high_priority( pPH->packet_type ) ) - pQueue = &s_RadioRxState.queue_high_priority; + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pPacket; + u8 uPacketType = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + uPacketType = pPHC->packet_type; + else + uPacketType = pPH->packet_type; - // Add the packet to the queue - pQueue->uPacketsRxInterface[pQueue->iCurrentRxPacketIndex] = iRadioInterface; - pQueue->uPacketsAreShort[pQueue->iCurrentRxPacketIndex] = 0; - pQueue->iPacketsLengths[pQueue->iCurrentRxPacketIndex] = iLength; - memcpy(pQueue->pPacketsBuffers[pQueue->iCurrentRxPacketIndex], pPacket, iLength); - - u32 uTimeStartTryLock = get_current_timestamp_ms(); - int iLock = -1; - while ( (iLock != 0 ) && (get_current_timestamp_ms() <= uTimeStartTryLock+5) ) - { - iLock = pthread_mutex_trylock(&(pQueue->mutex)); - hardware_sleep_micros(100); - } + t_radio_rx_state_packets_queue* pQueue = &s_RadioRxState.queue_reg_priority; + if ( radio_packet_type_is_high_priority( uPacketType ) ) + pQueue = &s_RadioRxState.queue_high_priority; - if ( iLock != 0 ) - log_softerror_and_alarm("[RadioRxThread] Doing unguarded rx buffers manipulation"); - // No more room? Discard it - if ( pQueue->iCurrentRxPacketsInQueue >= MAX_RX_PACKETS_QUEUE ) + if ( ((pQueue->iCurrentPacketIndexToWrite+1) % pQueue->iQueueSize) == (pQueue->iCurrentPacketIndexToConsume % pQueue->iQueueSize) ) { - if ( 0 == iLock ) - pthread_mutex_unlock(&(pQueue->mutex)); s_uRadioRxLastTimeQueue += get_current_timestamp_ms() - s_uRadioRxTimeNow; return; } - pQueue->iCurrentRxPacketsInQueue++; - pQueue->iCurrentRxPacketIndex++; - if ( pQueue->iCurrentRxPacketIndex >= MAX_RX_PACKETS_QUEUE ) - pQueue->iCurrentRxPacketIndex = 0; - - if ( pQueue->iCurrentRxPacketsInQueue > pQueue->iStatsMaxPacketsInQueueLastMinute ) - pQueue->iStatsMaxPacketsInQueueLastMinute = pQueue->iCurrentRxPacketsInQueue; - if ( pQueue->iCurrentRxPacketsInQueue > pQueue->iStatsMaxPacketsInQueue ) - pQueue->iStatsMaxPacketsInQueue = pQueue->iCurrentRxPacketsInQueue; + // Add the packet to the queue + pQueue->uPacketsRxInterface[pQueue->iCurrentPacketIndexToWrite] = iRadioInterface; + pQueue->uPacketsAreShort[pQueue->iCurrentPacketIndexToWrite] = 0; + pQueue->iPacketsLengths[pQueue->iCurrentPacketIndexToWrite] = iLength; + memcpy(pQueue->pPacketsBuffers[pQueue->iCurrentPacketIndexToWrite], pPacket, iLength); + + pQueue->iCurrentPacketIndexToWrite++; + if ( pQueue->iCurrentPacketIndexToWrite >= pQueue->iQueueSize ) + pQueue->iCurrentPacketIndexToWrite = 0; - if ( NULL != pQueue->pSemaphore ) - sem_post(pQueue->pSemaphore); + int iCountPackets = pQueue->iCurrentPacketIndexToWrite - pQueue->iCurrentPacketIndexToConsume; + if ( pQueue->iCurrentPacketIndexToWrite < pQueue->iCurrentPacketIndexToConsume ) + iCountPackets = pQueue->iCurrentPacketIndexToWrite + (pQueue->iQueueSize - pQueue->iCurrentPacketIndexToConsume); - if ( 0 == iLock ) - pthread_mutex_unlock(&(pQueue->mutex)); + if ( iCountPackets > pQueue->iStatsMaxPacketsInQueueLastMinute ) + pQueue->iStatsMaxPacketsInQueueLastMinute = iCountPackets; + if ( iCountPackets > pQueue->iStatsMaxPacketsInQueue ) + pQueue->iStatsMaxPacketsInQueue = iCountPackets; + if ( NULL != pQueue->pSemaphoreWrite ) + { + if ( 0 != sem_post(pQueue->pSemaphoreWrite) ) + log_softerror_and_alarm("Failed to set semaphore."); + } s_uRadioRxLastTimeQueue += get_current_timestamp_ms() - s_uRadioRxTimeNow; } @@ -315,7 +391,14 @@ int _radio_rx_process_serial_short_packet(int iInterfaceIndex, u8* pPacketBuffer if ( pPHS->data_length >= sizeof(t_packet_header) - sizeof(u32) ) { t_packet_header* pPH = (t_packet_header*)(pPacketBuffer + sizeof(t_packet_header_short)); - s_uLastRxShortPacketsVehicleIds[iInterfaceIndex] = pPH->vehicle_id_src; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + s_uLastRxShortPacketsVehicleIds[iInterfaceIndex] = pPH->vehicle_id_src; + } + else if ( pPHS->data_length >= sizeof(t_packet_header_compressed) - sizeof(u32) ) + { + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)(pPacketBuffer + sizeof(t_packet_header_short)); + if ( (pPHC->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + s_uLastRxShortPacketsVehicleIds[iInterfaceIndex] = pPHC->vehicle_id_src; } } @@ -343,6 +426,7 @@ int _radio_rx_process_serial_short_packet(int iInterfaceIndex, u8* pPacketBuffer if ( s_uBuffersFullMessagesReadPos[iInterfaceIndex] >= sizeof(t_packet_header) ) { t_packet_header* pPH = (t_packet_header*) s_uBuffersFullMessages[iInterfaceIndex]; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) if ( (pPH->total_length >= sizeof(t_packet_header)) && (s_uBuffersFullMessagesReadPos[iInterfaceIndex] >= pPH->total_length) ) { u32 uCRC = base_compute_crc32(&s_uBuffersFullMessages[iInterfaceIndex][sizeof(u32)], pPH->total_length - sizeof(u32)); @@ -353,6 +437,20 @@ int _radio_rx_process_serial_short_packet(int iInterfaceIndex, u8* pPacketBuffer } } } + else if ( s_uBuffersFullMessagesReadPos[iInterfaceIndex] >= sizeof(t_packet_header_compressed) ) + { + t_packet_header_compressed* pPHC = (t_packet_header_compressed*) s_uBuffersFullMessages[iInterfaceIndex]; + if ( (pPHC->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + if ( (pPHC->total_length >= sizeof(t_packet_header_compressed)) && (s_uBuffersFullMessagesReadPos[iInterfaceIndex] >= pPHC->total_length) ) + { + u8 uCRC = base_compute_crc8(&s_uBuffersFullMessages[iInterfaceIndex][sizeof(u8)], pPHC->total_length - sizeof(u8)); + if ( uCRC == pPHC->uCRC ) + { + s_uBuffersFullMessagesReadPos[iInterfaceIndex] = 0; + _radio_rx_check_add_packet_to_rx_queue(s_uBuffersFullMessages[iInterfaceIndex], pPHC->total_length, iInterfaceIndex); + } + } + } // Too much data? Then reset the buffer and wait for the start of a new full packet. if ( s_uBuffersFullMessagesReadPos[iInterfaceIndex] >= MAX_PACKET_TOTAL_SIZE*2 - 255 ) @@ -480,6 +578,9 @@ int _radio_rx_parse_received_wifi_radio_data(int iInterfaceIndex) u8* pBuffer = NULL; int iCountParsed = 0; + static int sdebugCountParser = 0; + sdebugCountParser++; + for( int iCountReads=0; iCountReads<3; iCountReads++ ) { iBufferLength = 0; @@ -503,47 +604,93 @@ int _radio_rx_parse_received_wifi_radio_data(int iInterfaceIndex) int iCountPackets = 0; int iIsVideoData = 0; - - while ( (iLength > 0) && (NULL != pData) ) + int iRemainingLength = iLength; + while ( (iRemainingLength > 0) && (NULL != pData) ) { t_packet_header* pPH = (t_packet_header*)pData; - + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pData; + u8 uPacketType = 0; + int iThisLen = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + iThisLen = pPHC->total_length; + uPacketType = pPHC->packet_type; + } + else + { + iThisLen = pPH->total_length; + uPacketType = pPH->packet_type; + } if ( s_iRadioRxDevMode ) - if ( pPH->packet_type == PACKET_TYPE_RUBY_PING_CLOCK ) + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + if ( uPacketType == PACKET_TYPE_RUBY_PING_CLOCK ) { s_uLastRadioPingSentTime = get_current_timestamp_ms(); s_uLastRadioPingId = *(pData +sizeof(t_packet_header)); } - if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) - iIsVideoData = 1; + if ( radio_packet_type_is_high_priority(uPacketType) || (pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED) ) + if ( NULL != s_pPacketsCounterOutputHighPriority ) + s_pPacketsCounterOutputHighPriority[iInterfaceIndex]++; + + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) + if ( pPH->packet_type == PACKET_TYPE_VIDEO_DATA_98 ) { + iIsVideoData = 1; t_packet_header_video_full_98* pPHVF = (t_packet_header_video_full_98*) (pData+sizeof(t_packet_header)); - if ( pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED ) - { - if ( NULL != s_pPacketsCounterOutputRetrVideo ) - s_pPacketsCounterOutputRetrVideo[iInterfaceIndex] = s_pPacketsCounterOutputRetrVideo[iInterfaceIndex]+1; - } - else + /* + static u32 sdebugRBlockIndex = 0; + static u32 sdebugRBlockPacketIndex = 0; + static u32 sdebugRRadioPacketIndex = 0; + static u32 sdebugRStreamPacketIndex = 0; + static u32 sdebugRPacektFlags = 0; + static int sdebugRTotalLength = 0; + if ( (pPHVF->uCurrentBlockIndex < sdebugRBlockIndex) || + ((pPHVF->uCurrentBlockIndex == sdebugRBlockIndex) && (pPHVF->uCurrentBlockPacketIndex < sdebugRBlockPacketIndex)) || + ((pPH->radio_link_packet_index < sdebugRRadioPacketIndex) && pPH->radio_link_packet_index != 0) || + (pPH->stream_packet_idx < sdebugRStreamPacketIndex) ) + if ( ! (pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED) ) + if ( ! (sdebugRPacektFlags & PACKET_FLAGS_BIT_RETRANSMITED) ) + { + log_line("DEBUG radio (%d, %d, %d) recv out of order video packet: [%u/%u], last received: [%u/%u], type: %s", + sdebugCountParser, iCountReads, iCountPackets, pPHVF->uCurrentBlockIndex, pPHVF->uCurrentBlockPacketIndex, sdebugRBlockIndex, sdebugRBlockPacketIndex, + str_get_packet_type(pPH->packet_type) ); + log_line("DEBUG recv/last radio packet index: %u %u", pPH->radio_link_packet_index, sdebugRRadioPacketIndex); + log_line("DEBUG recv/last stream packet index: %u %u", pPH->stream_packet_idx, sdebugRStreamPacketIndex); + log_line("DEBUG recv/last retr type: %d %d", pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED, sdebugRPacektFlags & PACKET_FLAGS_BIT_RETRANSMITED); + log_line("DEBUG recv/last component: %d %d", pPH->packet_flags & PACKET_FLAGS_MASK_MODULE, sdebugRPacektFlags & PACKET_FLAGS_MASK_MODULE); + log_line("DEBUG recv/last length: %d %d (headers: %d+%d)", pPH->total_length, sdebugRTotalLength, sizeof(t_packet_header), sizeof(t_packet_header_video_full_98)); + } + sdebugRBlockIndex = pPHVF->uCurrentBlockIndex; + sdebugRBlockPacketIndex = pPHVF->uCurrentBlockPacketIndex; + sdebugRRadioPacketIndex = pPH->radio_link_packet_index; + sdebugRStreamPacketIndex = pPH->stream_packet_idx; + sdebugRPacektFlags = pPH->packet_flags; + sdebugRTotalLength = pPH->total_length; + */ + + if ( ! (pPH->packet_flags & PACKET_FLAGS_BIT_RETRANSMITED) ) { if ( pPHVF->uCurrentBlockPacketIndex >= pPHVF->uCurrentBlockDataPackets ) { if ( NULL != s_pPacketsCounterOutputECVideo ) - s_pPacketsCounterOutputECVideo[iInterfaceIndex] = s_pPacketsCounterOutputECVideo[iInterfaceIndex]+1; + s_pPacketsCounterOutputECVideo[iInterfaceIndex]++; } else { if ( NULL != s_pPacketsCounterOutputVideo ) - s_pPacketsCounterOutputVideo[iInterfaceIndex] = s_pPacketsCounterOutputVideo[iInterfaceIndex]+1; + s_pPacketsCounterOutputVideo[iInterfaceIndex]++; } } } + + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_COMPONENT_VIDEO ) if ( NULL != s_pPacketsCounterOutputData ) - s_pPacketsCounterOutputData[iInterfaceIndex] = s_pPacketsCounterOutputData[iInterfaceIndex]+1; + s_pPacketsCounterOutputData[iInterfaceIndex]++; // To fix /* @@ -562,7 +709,7 @@ int _radio_rx_parse_received_wifi_radio_data(int iInterfaceIndex) */ iCountPackets++; int bCRCOk = 0; - int iPacketLength = packet_process_and_check(iInterfaceIndex, pData, iLength, &bCRCOk); + int iPacketLength = packet_process_and_check(iInterfaceIndex, pData, iRemainingLength, &bCRCOk); if ( iPacketLength <= 0 ) { @@ -577,40 +724,48 @@ int _radio_rx_parse_received_wifi_radio_data(int iInterfaceIndex) iInterfaceIndex+1, pPH->total_length, str_get_packet_type(pPH->packet_type)); iDataIsOk = 0; pData += pPH->total_length; - iLength -= pPH->total_length; + iRemainingLength -= pPH->total_length; continue; } - if ( (iPacketLength != pPH->total_length) || (pPH->total_length >= MAX_PACKET_TOTAL_SIZE) ) + if ( (iPacketLength != iThisLen) || (iThisLen >= MAX_PACKET_TOTAL_SIZE) ) { - log_softerror_and_alarm("[RadioRxThread] Received broken packet (computed size: %d). Packet size: %d bytes, type: %s", iPacketLength, pPH->total_length, str_get_packet_type(pPH->packet_type)); + log_softerror_and_alarm("[RadioRxThread] Received broken packet (computed size: %d). Packet size: %d bytes, type: %s", iPacketLength, iThisLen, str_get_packet_type(pPH->packet_type)); iDataIsOk = 0; - pData += pPH->total_length; - iLength -= pPH->total_length; + pData += iThisLen; + iRemainingLength -= iThisLen; continue; } - _radio_rx_check_add_packet_to_rx_queue(pData, pPH->total_length, iInterfaceIndex); + _radio_rx_check_add_packet_to_rx_queue(pData, iThisLen, iInterfaceIndex); - pData += pPH->total_length; - iLength -= pPH->total_length; + pData += iThisLen; + iRemainingLength -= iThisLen; } - // To fix, remove - //t_packet_header* pPH2 = (t_packet_header*)pBuffer; - //if ( (pPH2->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_COMPONENT_VIDEO ) - //if ( NULL != s_pVideoPacketsCounterOutput ) - // continue; - s_uRadioRxTimeNow = get_current_timestamp_ms(); + if ( NULL != s_pRxAirGapTracking ) + { + u32 uGap = s_uRadioRxTimeNow - s_uRadioRxLastReceivedPacket; + if ( uGap > 255 ) + uGap = 255; + if ( uGap > *s_pRxAirGapTracking ) + *s_pRxAirGapTracking = uGap; + } + s_uRadioRxLastReceivedPacket = s_uRadioRxTimeNow; t_packet_header* pPH = (t_packet_header*)pBuffer; - u32 uVehicleId = pPH->vehicle_id_src; + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pBuffer; + u32 uVehicleId = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + uVehicleId = pPH->vehicle_id_src; + else + uVehicleId = pPHC->vehicle_id_src; int nLost = _radio_rx_update_local_stats_on_new_radio_packet(iInterfaceIndex, 0, uVehicleId, pBuffer, iBufferLength, iDataIsOk); if ( nLost > 0 ) { if ( NULL != s_pPacketsCounterOutputMissing) - s_pPacketsCounterOutputMissing[iInterfaceIndex] = s_pPacketsCounterOutputMissing[iInterfaceIndex]+1; + s_pPacketsCounterOutputMissing[iInterfaceIndex]++; if ( NULL != s_pPacketsCounterOutputMissingMaxGap ) if ( nLost > s_pPacketsCounterOutputMissingMaxGap[iInterfaceIndex] ) s_pPacketsCounterOutputMissingMaxGap[iInterfaceIndex] = (u8)nLost; @@ -783,7 +938,6 @@ static void * _thread_radio_rx(void *argument) uTimeLastRead = uTime; int nResult = select(s_iRadioRxMaxFD, &s_RadioRxReadSet, NULL, NULL, &s_iRadioRxReadTimeInterval); - s_uRadioRxLastTimeRead += get_current_timestamp_micros() - uTimeLastRead; s_uRadioRxLastTimeQueue = 0; @@ -850,8 +1004,6 @@ int radio_rx_start_rx_thread(shared_mem_radio_stats* pSMRadioStats, shared_mem_r if ( s_iRadioRxInitialized ) return 1; - _radio_rx_update_fd_sets(); - s_pSMRadioStats = pSMRadioStats; s_pSMRadioRxGraphs = pSMRadioRxGraphs; s_iSearchMode = iSearchMode; @@ -864,17 +1016,11 @@ int radio_rx_start_rx_thread(shared_mem_radio_stats* pSMRadioStats, shared_mem_r s_iRadioRxAllInterfacesPaused = 0; - for( int i=0; i 0 ) { s_iRadioRxPausedInterfaces[iInterfaceIndex]--; if ( s_iRadioRxPausedInterfaces[iInterfaceIndex] == 0 ) s_iRadioRxAllInterfacesPaused = 0; } - pthread_mutex_unlock(&(s_RadioRxState.queue_reg_priority.mutex)); - pthread_mutex_unlock(&(s_RadioRxState.queue_high_priority.mutex)); - _radio_rx_update_fd_sets(); s_bHasPendingOperation = 0; s_bCanDoOperations = 0; } @@ -1102,16 +1265,21 @@ void radio_rx_set_dev_mode() } // Pointers to array of int-s (max radio cards, for each card) -void radio_rx_set_packet_counter_output(u8* pCounterOutputVideo, u8* pCounterOutputECVideo, u8* pCounterOutputRetrVideo, u8* pCounterOutputData, u8* pCounterMissingPackets, u8* pCounterMissingPacketsMaxGap) +void radio_rx_set_packet_counter_output(u8* pCounterOutputVideo, u8* pCounterOutputECVideo, u8* pCounterOutputHighPriority, u8* pCounterOutputData, u8* pCounterMissingPackets, u8* pCounterMissingPacketsMaxGap) { s_pPacketsCounterOutputVideo = pCounterOutputVideo; s_pPacketsCounterOutputECVideo = pCounterOutputECVideo; - s_pPacketsCounterOutputRetrVideo = pCounterOutputRetrVideo; + s_pPacketsCounterOutputHighPriority = pCounterOutputHighPriority; s_pPacketsCounterOutputData = pCounterOutputData; s_pPacketsCounterOutputMissing = pCounterMissingPackets; s_pPacketsCounterOutputMissingMaxGap = pCounterMissingPacketsMaxGap; } +void radio_rx_set_air_gap_track_output(u8* pCounterRxAirgap) +{ + s_pRxAirGapTracking = pCounterRxAirgap; +} + int radio_rx_detect_firmware_type_from_packet(u8* pPacketBuffer, int nPacketLength) { if ( (NULL == pPacketBuffer) || (nPacketLength < 4) ) @@ -1218,83 +1386,3 @@ u32 radio_rx_get_and_reset_max_loop_time_queue() s_uRadioRxLastTimeQueue = 0; return u; } - - -u8* _radio_rx_wait_get_queue_packet(t_radio_rx_state_packets_queue* pQueue, u32 uTimeoutMicroSec, int* pLength, int* pIsShortPacket, int* pRadioInterfaceIndex) -{ - int iRes = -1; - - if ( 0 == uTimeoutMicroSec ) - { - iRes = sem_trywait(pQueue->pSemaphore); - } - else - { - struct timespec ts; - clock_gettime(CLOCK_REALTIME, &ts); - ts.tv_nsec += 1000*uTimeoutMicroSec; - iRes = sem_timedwait(pQueue->pSemaphore, &ts); - } - if ( 0 != iRes ) - return NULL; - - int iIndexToCopy = 0; - pthread_mutex_lock(&(pQueue->mutex)); - - iIndexToCopy = pQueue->iCurrentRxPacketToConsume; - if ( NULL != pLength ) - *pLength = pQueue->iPacketsLengths[pQueue->iCurrentRxPacketToConsume]; - if ( NULL != pIsShortPacket ) - *pIsShortPacket = pQueue->uPacketsAreShort[pQueue->iCurrentRxPacketToConsume]; - if ( NULL != pRadioInterfaceIndex ) - *pRadioInterfaceIndex = pQueue->uPacketsRxInterface[pQueue->iCurrentRxPacketToConsume]; - - // Defer copy after mutex unlock - //memcpy(s_tmpLastProcessedRadioRxPacket, pQueue->pPacketsBuffers[pQueue->iCurrentRxPacketToConsume], pQueue->iPacketsLengths[pQueue->iCurrentRxPacketToConsume]); - - pQueue->iCurrentRxPacketToConsume++; - if ( pQueue->iCurrentRxPacketToConsume >= MAX_RX_PACKETS_QUEUE ) - pQueue->iCurrentRxPacketToConsume = 0; - pQueue->iCurrentRxPacketsInQueue--; - pthread_mutex_unlock(&(pQueue->mutex)); - - memcpy(s_tmpLastProcessedRadioRxPacket, pQueue->pPacketsBuffers[iIndexToCopy], pQueue->iPacketsLengths[iIndexToCopy]); - - return s_tmpLastProcessedRadioRxPacket; -} - -u8* radio_rx_wait_get_next_received_high_prio_packet(u32 uTimeoutMicroSec, int* pLength, int* pIsShortPacket, int* pRadioInterfaceIndex) -{ - if ( NULL != pLength ) - *pLength = 0; - if ( NULL != pIsShortPacket ) - *pIsShortPacket = 0; - if ( NULL != pRadioInterfaceIndex ) - *pRadioInterfaceIndex = 0; - if ( 0 == s_iRadioRxInitialized ) - return NULL; - - if ( NULL == s_RadioRxState.queue_high_priority.pSemaphore ) - if ( s_RadioRxState.queue_high_priority.iCurrentRxPacketIndex == s_RadioRxState.queue_high_priority.iCurrentRxPacketToConsume ) - return 0; - - return _radio_rx_wait_get_queue_packet(&(s_RadioRxState.queue_high_priority), uTimeoutMicroSec, pLength, pIsShortPacket, pRadioInterfaceIndex); -} - -u8* radio_rx_wait_get_next_received_reg_prio_packet(u32 uTimeoutMicroSec, int* pLength, int* pIsShortPacket, int* pRadioInterfaceIndex) -{ - if ( NULL != pLength ) - *pLength = 0; - if ( NULL != pIsShortPacket ) - *pIsShortPacket = 0; - if ( NULL != pRadioInterfaceIndex ) - *pRadioInterfaceIndex = 0; - if ( 0 == s_iRadioRxInitialized ) - return NULL; - - if ( NULL == s_RadioRxState.queue_reg_priority.pSemaphore ) - if ( s_RadioRxState.queue_reg_priority.iCurrentRxPacketIndex == s_RadioRxState.queue_reg_priority.iCurrentRxPacketToConsume ) - return 0; - - return _radio_rx_wait_get_queue_packet(&(s_RadioRxState.queue_reg_priority), uTimeoutMicroSec, pLength, pIsShortPacket, pRadioInterfaceIndex); -} diff --git a/code/radio/radio_rx.h b/code/radio/radio_rx.h index 5ba45ff5..15cf563b 100644 --- a/code/radio/radio_rx.h +++ b/code/radio/radio_rx.h @@ -7,9 +7,9 @@ #include #if defined (HW_PLATFORM_RASPBERRY) || defined (HW_PLATFORM_RADXA_ZERO3) -#define MAX_RX_PACKETS_QUEUE 300 +#define MAX_RX_PACKETS_QUEUE 700 #else -#define MAX_RX_PACKETS_QUEUE 100 +#define MAX_RX_PACKETS_QUEUE 400 #endif typedef struct { @@ -33,14 +33,14 @@ typedef struct int iPacketsLengths[MAX_RX_PACKETS_QUEUE]; u8 uPacketsAreShort[MAX_RX_PACKETS_QUEUE]; u8 uPacketsRxInterface[MAX_RX_PACKETS_QUEUE]; - int iCurrentRxPacketIndex; // Where next packet will be added - int iCurrentRxPacketToConsume; // Where the first packet to read/consume is - int iCurrentRxPacketsInQueue; + int iQueueSize; + volatile int iCurrentPacketIndexToWrite; // Where next packet will be added + volatile int iCurrentPacketIndexToConsume; // Where the first packet to read/consume is int iStatsMaxPacketsInQueue; int iStatsMaxPacketsInQueueLastMinute; - pthread_mutex_t mutex; - sem_t* pSemaphore; + sem_t* pSemaphoreWrite; + sem_t* pSemaphoreRead; } ALIGN_STRUCT_SPEC_INFO t_radio_rx_state_packets_queue; typedef struct @@ -81,7 +81,8 @@ void radio_rx_pause_interface(int iInterfaceIndex, const char* szReason); void radio_rx_resume_interface(int iInterfaceIndex); void radio_rx_mark_quit(); void radio_rx_set_dev_mode(); -void radio_rx_set_packet_counter_output(u8* pCounterOutputVideo, u8* pCounterOutputECVideo, u8* pCounterOutputRetrVideo, u8* pCounterOutputData, u8* pCounterMissingPackets, u8* pCounterMissingPacketsMaxGap); +void radio_rx_set_packet_counter_output(u8* pCounterOutputVideo, u8* pCounterOutputECVideo, u8* pCounterOutputHighPriority, u8* pCounterOutputData, u8* pCounterMissingPackets, u8* pCounterMissingPacketsMaxGap); +void radio_rx_set_air_gap_track_output(u8* pCounterRxAirgap); int radio_rx_detect_firmware_type_from_packet(u8* pPacketBuffer, int nPacketLength); diff --git a/code/radio/radiolink.c b/code/radio/radiolink.c index a6781bc5..7c6b0beb 100644 --- a/code/radio/radiolink.c +++ b/code/radio/radiolink.c @@ -10,9 +10,9 @@ * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - * Copyright info and developer info must be preserved as is in the user + * Copyright info and developer info must be preserved as is in the user interface, additions could be made to that info. - * Neither the name of the organization nor the + * Neither the name of the organization nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. * Military use is not permited. @@ -1131,6 +1131,21 @@ int packet_process_and_check(int interfaceNb, u8* pPacketBuffer, int iBufferLeng return 0; } + t_packet_header* pPH = (t_packet_header*)pPacketBuffer; + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pPacketBuffer; + + if ( iBufferLength < (int)sizeof(t_packet_header_compressed) ) + { + s_iLastProcessingErrorCode = RADIO_PROCESSING_ERROR_CODE_PACKET_RECEIVED_TOO_SMALL; + + #ifdef DEBUG_PACKET_RECEIVED + printf("Received packet to small: packet length: %d bytes, header minimum: %d\n", iBufferLength, (int)sizeof(t_packet_header_compressed)); + log_line("Received packet to small: packet length: %d bytes, header minimum: %d", iBufferLength, (int)sizeof(t_packet_header_compressed)); + #endif + return 0; + } + + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) if ( iBufferLength < (int)sizeof(t_packet_header) ) { s_iLastProcessingErrorCode = RADIO_PROCESSING_ERROR_CODE_PACKET_RECEIVED_TOO_SMALL; @@ -1142,8 +1157,20 @@ int packet_process_and_check(int interfaceNb, u8* pPacketBuffer, int iBufferLeng return 0; } - t_packet_header* pPH = (t_packet_header*)pPacketBuffer; - int packetLength = pPH->total_length; + int packetLength = 0; + u8 uPacketFlags = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + packetLength = pPHC->total_length; + uPacketFlags = pPHC->packet_flags; + uPacketFlags &= ~(PACKET_FLAGS_MASK_MODULE); + uPacketFlags |= pPHC->uExtraBits & PACKET_FLAGS_MASK_MODULE; + } + else + { + packetLength = pPH->total_length; + uPacketFlags = pPH->packet_flags; + } if ( packetLength > iBufferLength ) { @@ -1156,7 +1183,8 @@ int packet_process_and_check(int interfaceNb, u8* pPacketBuffer, int iBufferLeng return 0; } - if ( pPH->packet_flags & PACKET_FLAGS_BIT_HAS_ENCRYPTION ) + if ( uPacketFlags & PACKET_FLAGS_BIT_HAS_ENCRYPTION ) + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) { #ifdef DEBUG_PACKET_RECEIVED log_line("enc detected"); @@ -1166,25 +1194,44 @@ int packet_process_and_check(int interfaceNb, u8* pPacketBuffer, int iBufferLeng dpp(pPacketBuffer + dx, l); } - u32 uCRC = 0; - if ( pPH->packet_flags & PACKET_FLAGS_BIT_HEADERS_ONLY_CRC ) - uCRC = base_compute_crc32(pPacketBuffer+sizeof(u32), sizeof(t_packet_header)-sizeof(u32)); - else - uCRC = base_compute_crc32(pPacketBuffer+sizeof(u32), pPH->total_length-sizeof(u32)); - - if ( (uCRC & 0x00FFFFFF) != (pPH->uCRC & 0x00FFFFFF) ) + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) { - s_iLastProcessingErrorCode = RADIO_PROCESSING_ERROR_CODE_INVALID_CRC_RECEIVED; - #ifdef DEBUG_PACKET_RECEIVED - log_line("Received packet bad headers, CRC headers: %u, computed CRC(%s): %u, packet length: %d bytes", pPH->uCRC, (pPH->packet_flags & PACKET_FLAGS_BIT_HEADERS_ONLY_CRC)?"headers only":"full", uCRC, packetLength); - if ( packetLength <= 48 ) - log_buffer(pPacketBuffer, packetLength); - #endif - if ( NULL != pbCRCOk ) - *pbCRCOk = 0; - return 0; + u8 uCRC = base_compute_crc8(pPacketBuffer+sizeof(u8), pPHC->total_length-sizeof(u8)); + + if ( uCRC != pPHC->uCRC ) + { + s_iLastProcessingErrorCode = RADIO_PROCESSING_ERROR_CODE_INVALID_CRC_RECEIVED; + #ifdef DEBUG_PACKET_RECEIVED + log_line("Received packet bad headers, CRC headers: %u, computed CRC(%s): %u, packet length: %d bytes", pPHC->uCRC, (pPHC->packet_flags & PACKET_FLAGS_BIT_HEADERS_ONLY_CRC)?"headers only":"full", uCRC, packetLength); + if ( packetLength <= 48 ) + log_buffer(pPacketBuffer, packetLength); + #endif + if ( NULL != pbCRCOk ) + *pbCRCOk = 0; + return 0; + } } + else + { + u32 uCRC = 0; + if ( pPH->packet_flags & PACKET_FLAGS_BIT_HEADERS_ONLY_CRC ) + uCRC = base_compute_crc32(pPacketBuffer+sizeof(u32), sizeof(t_packet_header)-sizeof(u32)); + else + uCRC = base_compute_crc32(pPacketBuffer+sizeof(u32), pPH->total_length-sizeof(u32)); + if ( (uCRC & 0x00FFFFFF) != (pPH->uCRC & 0x00FFFFFF) ) + { + s_iLastProcessingErrorCode = RADIO_PROCESSING_ERROR_CODE_INVALID_CRC_RECEIVED; + #ifdef DEBUG_PACKET_RECEIVED + log_line("Received packet bad headers, CRC headers: %u, computed CRC(%s): %u, packet length: %d bytes", pPH->uCRC, (pPH->packet_flags & PACKET_FLAGS_BIT_HEADERS_ONLY_CRC)?"headers only":"full", uCRC, packetLength); + if ( packetLength <= 48 ) + log_buffer(pPacketBuffer, packetLength); + #endif + if ( NULL != pbCRCOk ) + *pbCRCOk = 0; + return 0; + } + } if ( NULL != pbCRCOk ) *pbCRCOk = 1; @@ -1270,12 +1317,12 @@ int radio_build_new_raw_packet(int iLocalRadioLinkId, u8* pRawPacket, u8* pPacke memcpy(pRawPacket, pPacketData, nInputLength); totalRadioLength += nInputLength; - memset(s_uLastPacketBuilt, 0, MAX_PACKET_TOTAL_SIZE); - // To fix, only on debug - if ( 1 ) - //if ( s_bRadioDebugFlag ) + if ( s_bRadioDebugFlag ) + { + memset(s_uLastPacketBuilt, 0, MAX_PACKET_TOTAL_SIZE); memcpy(s_uLastPacketBuilt, pPacketData, nInputLength); - + } + #ifdef DEBUG_PACKET_SENT log_line("Building a composed packet of total size: %d, extra data: %d", nInputLength + iExtraData, iExtraData); #endif @@ -1294,29 +1341,43 @@ int radio_build_new_raw_packet(int iLocalRadioLinkId, u8* pRawPacket, u8* pPacke { nPCount++; t_packet_header* pPH = (t_packet_header*)pData; - int nPacketLength = pPH->total_length; - - pPH->radio_link_packet_index = uRadioLinkPacketIndex; - if ( bEncrypt ) - pPH->packet_flags |= PACKET_FLAGS_BIT_HAS_ENCRYPTION; - + t_packet_header_compressed* pPHC = (t_packet_header_compressed*)pData; + int nPacketLength = 0; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) == PACKET_FLAGS_MASK_COMPRESSED_HEADER ) + { + nPacketLength = pPHC->total_length; + if ( bEncrypt ) + pPHC->packet_flags |= PACKET_FLAGS_BIT_HAS_ENCRYPTION; - if ( pPH->packet_flags & PACKET_FLAGS_BIT_HEADERS_ONLY_CRC ) - radio_packet_compute_crc((u8*)pPH, sizeof(t_packet_header)); + radio_packet_compressed_compute_crc(pData, nPacketLength); + } else - radio_packet_compute_crc((u8*)pPH, pPH->total_length); + { + nPacketLength = pPH->total_length; + pPH->radio_link_packet_index = uRadioLinkPacketIndex; + if ( bEncrypt ) + pPH->packet_flags |= PACKET_FLAGS_BIT_HAS_ENCRYPTION; + + if ( pPH->packet_flags & PACKET_FLAGS_BIT_HEADERS_ONLY_CRC ) + radio_packet_compute_crc((u8*)pPH, sizeof(t_packet_header)); + else + radio_packet_compute_crc((u8*)pPH, pPH->total_length); + + if ( bEncrypt ) + { + int dx = sizeof(t_packet_header) - sizeof(u32) - sizeof(u32); + epp(pData+dx, pPH->total_length-dx); + } + } + #ifdef DEBUG_PACKET_SENT - log_line("Packet %d in composed packet: enc: %d, crc (%s): %u, len: %d", nPCount, bEncrypt, (pPH->packet_flags & PACKET_FLAGS_BIT_HEADERS_ONLY_CRC)?"headers only":"full", pPH->uCRC, pPH->total_length); - if ( pPH->total_length <= 125 ) - log_buffer3(pData, pPH->total_length, 10,6,8); + // Add compressed header support: + //log_line("Packet %d in composed packet: enc: %d, crc (%s): %u, len: %d", nPCount, bEncrypt, (pPH->packet_flags & PACKET_FLAGS_BIT_HEADERS_ONLY_CRC)?"headers only":"full", pPH->uCRC, pPH->total_length); + //if ( pPH->total_length <= 125 ) + // log_buffer3(pData, pPH->total_length, 10,6,8); #endif - if ( bEncrypt ) - { - int dx = sizeof(t_packet_header) - sizeof(u32) - sizeof(u32); - epp(pData+dx, pPH->total_length-dx); - } nLength -= nPacketLength; pData += nPacketLength; } @@ -1343,6 +1404,7 @@ int radio_write_raw_packet(int interfaceIndex, u8* pData, int dataLength) if ( s_bRadioDebugFlag ) { t_packet_header* pPH = (t_packet_header*)&s_uLastPacketBuilt[0]; + if ( (pPH->packet_flags & PACKET_FLAGS_MASK_MODULE) != PACKET_FLAGS_MASK_COMPRESSED_HEADER ) if ( pPH->packet_type == PACKET_TYPE_RUBY_PING_CLOCK ) { s_uLastRadioPingSentTime = get_current_timestamp_ms(); diff --git a/code/radio/radiolink.h b/code/radio/radiolink.h index bfe45c44..f79a9bce 100644 --- a/code/radio/radiolink.h +++ b/code/radio/radiolink.h @@ -1,12 +1,32 @@ /* -You can use this C/C++ code however you wish (for example, but not limited to: - as is, or by modifying it, or by adding new code, or by removing parts of the code; - in public or private projects, in new free or commercial products) - only if you get a priori written consent from Petru Soroaga (petrusoroaga@yahoo.com) for your specific use - and only if this copyright terms are preserved in the code. - This code is public for learning and academic purposes. -Also, check the licences folder for additional licences terms. -Code written by: Petru Soroaga, 2021-2023 + Ruby Licence + Copyright (c) 2024 Petru Soroaga + All rights reserved. + + Redistribution and use in source and/or binary forms, with or without + modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Copyright info and developer info must be preserved as is in the user + interface, additions could be made to that info. + * Neither the name of the organization nor the + names of its contributors may be used to endorse or promote products + derived from this software without specific prior written permission. + * Military use is not permited. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE AUTHOR (PETRU SOROAGA) BE LIABLE FOR ANY + DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ #pragma once diff --git a/code/radio/radiopackets2.c b/code/radio/radiopackets2.c index b2257072..ba098e90 100644 --- a/code/radio/radiopackets2.c +++ b/code/radio/radiopackets2.c @@ -10,9 +10,9 @@ * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - * Copyright info and developer info must be preserved as is in the user + * Copyright info and developer info must be preserved as is in the user interface, additions could be made to that info. - * Neither the name of the organization nor the + * Neither the name of the organization nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. * Military use is not permited. @@ -45,15 +45,29 @@ void radio_packet_init(t_packet_header* pPH, u8 component, u8 packet_type, u32 u pPH->vehicle_id_dest = 0; pPH->radio_link_packet_index = 0; pPH->stream_packet_idx = uStreamId << PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX; - pPH->packet_flags = component; + pPH->packet_flags = component & PACKET_FLAGS_MASK_MODULE; pPH->packet_type = packet_type; - + pPH->total_length = sizeof(t_packet_header); if ( SYSTEM_SW_VERSION_MINOR < 10 ) pPH->packet_flags_extended = 0xFF & ((SYSTEM_SW_VERSION_MAJOR << 4) | SYSTEM_SW_VERSION_MINOR); else pPH->packet_flags_extended = 0xFF & ((SYSTEM_SW_VERSION_MAJOR << 4) | (SYSTEM_SW_VERSION_MINOR/10)); } +void radio_packet_compressed_init(t_packet_header_compressed* pPHC, u8 component, u8 packet_type) +{ + if ( NULL == pPHC ) + return; + + pPHC->uCRC = 0; + pPHC->packet_flags = PACKET_FLAGS_MASK_COMPRESSED_HEADER; + pPHC->uExtraBits = component & PACKET_FLAGS_MASK_MODULE; + pPHC->packet_type = packet_type; + pPHC->vehicle_id_src = 0; + pPHC->vehicle_id_dest = 0; + pPHC->total_length = sizeof(t_packet_header_compressed); +} + void radio_packet_compute_crc(u8* pBuffer, int length) { u32 crc = base_compute_crc32(pBuffer + sizeof(u32), length-sizeof(u32)); @@ -61,6 +75,12 @@ void radio_packet_compute_crc(u8* pBuffer, int length) *p = crc; } +void radio_packet_compressed_compute_crc(u8* pBuffer, int length) +{ + u8 crc = base_compute_crc8(pBuffer + sizeof(u8), length-sizeof(u8)); + *pBuffer = crc; +} + int radio_packet_check_crc(u8* pBuffer, int length) { u32 crc = base_compute_crc32(pBuffer + sizeof(u32), length-sizeof(u32)); @@ -76,7 +96,8 @@ int radio_packet_type_is_high_priority(u8 uPacketType) { case PACKET_TYPE_RUBY_PING_CLOCK: case PACKET_TYPE_RUBY_PING_CLOCK_REPLY: - case PACKET_TYPE_VIDEO_DATA_98: + //case PACKET_TYPE_VIDEO_DATA_98: + case PACKET_TYPE_VIDEO_ACK: case PACKET_TYPE_VIDEO_REQ_MULTIPLE_PACKETS: case PACKET_TYPE_VIDEO_SWITCH_TO_ADAPTIVE_VIDEO_LEVEL: case PACKET_TYPE_VIDEO_SWITCH_TO_ADAPTIVE_VIDEO_LEVEL_ACK: diff --git a/code/radio/radiopackets2.h b/code/radio/radiopackets2.h index aeea87bb..817c80bc 100644 --- a/code/radio/radiopackets2.h +++ b/code/radio/radiopackets2.h @@ -1,12 +1,32 @@ /* -You can use this C/C++ code however you wish (for example, but not limited to: - as is, or by modifying it, or by adding new code, or by removing parts of the code; - in public or private projects, in new free or commercial products) - only if you get a priori written consent from Petru Soroaga (petrusoroaga@yahoo.com) for your specific use - and only if this copyright terms are preserved in the code. - This code is public for learning and academic purposes. -Also, check the licences folder for additional licences terms. -Code written by: Petru Soroaga, 2021-2023 + Ruby Licence + Copyright (c) 2024 Petru Soroaga + All rights reserved. + + Redistribution and use in source and/or binary forms, with or without + modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Copyright info and developer info must be preserved as is in the user + interface, additions could be made to that info. + * Neither the name of the organization nor the + names of its contributors may be used to endorse or promote products + derived from this software without specific prior written permission. + * Military use is not permited. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE AUTHOR (PETRU SOROAGA) BE LIABLE FOR ANY + DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ #pragma once @@ -42,10 +62,11 @@ Code written by: Petru Soroaga, 2021-2023 #define STREAM_ID_DATA ((u32)0) #define STREAM_ID_TELEMETRY ((u32)1) #define STREAM_ID_DATA2 ((u32)2) -#define STREAM_ID_VIDEO_1 ((u32)3) +#define STREAM_ID_COMPRESSED ((u32)3) +#define STREAM_ID_VIDEO_1 ((u32)4) // Packet flags is a byte and contains flags: -// bit 0..2 - target module type (video/telem/rc/comm) (3 bits) +// bit 0..2 - target module type (video/telem/rc/comm) (3 bits) or 0b111 for a compressed packet header // bit 3 - header only CRC // bit 4 - chained flag: has more radio packets in the same buffer, just after this packet // bit 5 - has extra data after the regular packet data @@ -53,6 +74,7 @@ Code written by: Petru Soroaga, 2021-2023 // bit 7 - can TX after this one (to be used by the controller when it receives this packet) #define PACKET_FLAGS_MASK_MODULE 0b0111 +#define PACKET_FLAGS_MASK_COMPRESSED_HEADER 0b0111 #define PACKET_FLAGS_MASK_STREAM_PACKET_IDX 0x0FFFFFFF #define PACKET_FLAGS_MASK_STREAM_INDEX (((u32)0x0F)<<28) #define PACKET_FLAGS_MASK_SHIFT_STREAM_INDEX (28) @@ -75,7 +97,7 @@ Code written by: Petru Soroaga, 2021-2023 #define PACKET_COMPONENT_RC 4 #define PACKET_COMPONENT_RUBY 5 // Used for control messages between vehicle and controller #define PACKET_COMPONENT_AUDIO 6 -#define PACKET_COMPONENT_DATA 7 + #define PACKET_TYPE_EMBEDED_FULL_PACKET 0xFF #define PACKET_TYPE_EMBEDED_SHORT_PACKET 0x00 @@ -113,140 +135,26 @@ typedef struct } __attribute__((packed)) t_packet_header; -// Deprecated in 9.8 -/* -#define PACKET_TYPE_VIDEO_DATA_FULL 2 - -//---------------------------------------------- -// packet_header_video_full -// - -typedef struct -{ - u8 video_link_profile; - // (video stream id: 0xF0 bits, current video link profile: 0x0F bits); added in v.5.6 - u8 video_stream_and_type; // bits 0...3: video stream index, bits 4...7: video stream type: H264, H265, IP, etc - u32 uProfileEncodingFlags; // same as video link profile's uProfileEncodingFlags; - // byte 0: - // bit 0..2 - scramble blocks count - // bit 3 - enables restransmission of missing packets - // bit 4 - enable adaptive video keyframe interval - // bit 5 - enable adaptive video link params - // bit 6 - use controller info too when adjusting video link params - // bit 7 - go lower adaptive video profile when controller link lost - - // byte 1: - max time to wait for retransmissions (in ms*5)// affects rx buffers size - // byte 2: - retransmission duplication percent (0-100%), 0xFF = auto, bit 0..3 - regular packets duplication, bit 4..7 - retransmitted packets duplication - // byte 3: - // bit 0 - use medium adaptive video - // bit 1 - enable video auto quantization - // bit 2 - video auto quantization strength - // bit 3 - one way video link - // bit 4 - video profile should use EC scheme as auto; - // bit 5,6 - EC scheme spreading factor (0...3) - // bit 7 - try to keep constant video bitrate when it fluctuates - - u32 uVideoStatusFlags2; - // byte 0: current h264 quantization value - // byte 1: - // bit 0 - 0/1: has debug timings info after the video data: - // u32 - delta ms between video packets - // u32 - local timestamp camera capture, - // u32 - local timestamp sent to radio processing; - // u32 - local timestamp sent to radio output; - // u32 - local timestamp received on radio; - // u32 - local timestamp sent to video processing; - // u32 - local timestamp sent to video output; - // bit 1 - 0/1: is this video packet part of a I-frame - // bit 2 - 1: is on lower video bitrate - - u16 video_width; - u16 video_height; - u8 video_fps; - u16 video_keyframe_interval_ms; - u8 block_packets; - u8 block_fecs; - - u16 video_data_length; - u32 video_block_index; - u8 video_block_packet_index; - u32 fec_time; // how long FEC took, in microseconds/second - u32 uLastRecvVideoRetransmissionId; // unique id of the last retransmission request received by vehicle - u16 uLastAckKeyframeInterval; // in milisec - u8 uLastAckLevelShift; - u32 uLastSetVideoBitrate; // in bps, highest bit: 1 - initial set, 0 - auto adjusted - u32 uExtraData; // not used, for future -} __attribute__((packed)) t_packet_header_video_full_77; -*/ - -#define PACKET_TYPE_VIDEO_DATA_98 22 - -#define VIDEO_STREAM_INFO_FLAG_NONE 0 -#define VIDEO_STREAM_INFO_FLAG_SIZE 1 -#define VIDEO_STREAM_INFO_FLAG_FPS 2 -#define VIDEO_STREAM_INFO_FLAG_FEC_TIME 3 -#define VIDEO_STREAM_INFO_FLAG_VIDEO_PROFILE_FLAGS 4 -#define VIDEO_STREAM_INFO_FLAG_RETRANSMISSION_ID 5 +// Compressed packets (t_packet_header_compressed) are sent only on high bandwidth radio links +// Short packets (t_packet_header_short) are sent only on low bandwidth radio links typedef struct { - u8 uVideoStreamIndexAndType; - // bits 0...3: video stream index - // bits 4...7: video stream type: H264, H265, IP, etc - u32 uVideoStatusFlags2; - // byte 0: current h264 quantization value - // byte 1: - // bit 0 - 0/1: has debug timings info after the video data: - // u32 - delta ms between video packets - // u32 - local timestamp camera capture, - // u32 - local timestamp sent to radio processing; - // u32 - local timestamp sent to radio output; - // u32 - local timestamp received on radio; - // u32 - local timestamp sent to video processing; - // u32 - local timestamp sent to video output; - // bit 1 - 0/1: is this video packet part of a I-frame - // bit 2 - 1: is on lower video bitrate - // bit 3 - 0/1: is end of current frame - - u8 uCurrentVideoLinkProfile; - - u8 uStreamInfoFlags; - // See enum above - // 0: none; - // 1: video width (low 16 bits) and video height (high 16 bits) - // 2: video fps - // 3: fec time: how long FEC took, in microseconds/second - // 4: contains uProfileEncodingFlags; same as video link profile's uProfileEncodingFlags; - // 5: retransmission id - - u32 uStreamInfo; // value dependent on uStreamInfoFlags; - - u16 uCurrentVideoKeyframeIntervalMs; - - u32 uCurrentBlockIndex; - u8 uCurrentBlockPacketIndex; - u16 uCurrentBlockPacketSize; - u8 uCurrentBlockDataPackets; - u8 uCurrentBlockECPackets; - - u32 uLastRecvVideoRetransmissionId; // unique id of the last retransmission request received by vehicle - u16 uLastAckKeyframeInterval; // in milisec - u8 uLastAckLevelShift; - u32 uLastSetVideoBitrate; // in bps, highest bit: 1 - initial set, 0 - auto adjusted - u32 uExtraData; // not used, for future - // After video header, first two bites are the size of actual video data, part of error reconstruction as video data -} __attribute__((packed)) t_packet_header_video_full_98; + u8 uCRC; // computed for the entire packet + u8 packet_type; // 1...150: components packets types, 150-200: local control controller packets, 200-250: local control vehicle packets + u8 total_length; // Total length, including all the header data, including CRC + u8 uExtraBits; + // bit 0,1,2: component id, as component id in packets_flags below is not valid for this header type + // bit 3-7: tbd + // packets_flags must be the 5th byte so we can differentiate it from a regular t_packet_header; + u8 packet_flags; // first 3 bits are 1 to differentiate it from a regular t_packet_header; + u32 stream_packet_idx; // high 4 bits: stream id (0..15), lower 28 bits: stream packet index + // monotonically increassing, to detect missing/lost packets on each stream + u32 vehicle_id_src; + u32 vehicle_id_dest; + u32 uExtraData; // Can be used as a fast short payload +} __attribute__((packed)) t_packet_header_compressed; -typedef struct -{ - u32 uTime1; - u32 uTime2; - u32 uTime3; - u32 uTime4; - u32 uTime5; - u32 uTime6; - u32 uVideoCRC; -} __attribute__((packed)) t_packet_header_video_full_98_debug_info; // PING packets do not increase stream packet index as they are sent on each radio link separatelly #define PACKET_TYPE_RUBY_PING_CLOCK 3 @@ -356,6 +264,82 @@ typedef struct // u8: number of video packets requested // (u32+u8)*n = each (video block index + video packet index) requested +#define PACKET_TYPE_VIDEO_ACK 21 +// Sent only as a compressed packet (t_packet_header_compressed) +// uExtraData in header contains the acknoledged video frame id + +#define PACKET_TYPE_VIDEO_DATA_98 22 + +#define VIDEO_STREAM_INFO_FLAG_NONE 0 +#define VIDEO_STREAM_INFO_FLAG_SIZE 1 +#define VIDEO_STREAM_INFO_FLAG_FPS 2 +#define VIDEO_STREAM_INFO_FLAG_FEC_TIME 3 +#define VIDEO_STREAM_INFO_FLAG_VIDEO_PROFILE_FLAGS 4 +#define VIDEO_STREAM_INFO_FLAG_RETRANSMISSION_ID 5 + +typedef struct +{ + u8 uVideoStreamIndexAndType; + // bits 0...3: video stream index + // bits 4...7: video stream type: H264, H265, IP, etc + u32 uVideoStatusFlags2; + // byte 0: current h264 quantization value + // byte 1: + // bit 0 - 0/1: has debug timings info after the video data: + // u32 - delta ms between video packets + // u32 - local timestamp camera capture, + // u32 - local timestamp sent to radio processing; + // u32 - local timestamp sent to radio output; + // u32 - local timestamp received on radio; + // u32 - local timestamp sent to video processing; + // u32 - local timestamp sent to video output; + // bit 1 - 0/1: is this video packet part of a I-frame + // bit 2 - 1: is on lower video bitrate + // bit 3 - 0/1: is end of current frame + + u8 uCurrentVideoLinkProfile; + + u8 uStreamInfoFlags; + // See enum above + // 0: none; + // 1: video width (low 16 bits) and video height (high 16 bits) + // 2: video fps + // 3: fec time: how long FEC took, in microseconds/second + // 4: contains uProfileEncodingFlags; same as video link profile's uProfileEncodingFlags; + // 5: retransmission id + + u32 uStreamInfo; // value dependent on uStreamInfoFlags; + + u16 uCurrentVideoKeyframeIntervalMs; + + u32 uCurrentBlockIndex; + u8 uCurrentBlockPacketIndex; + u16 uCurrentBlockPacketSize; + u8 uCurrentBlockDataPackets; + u8 uCurrentBlockECPackets; + + // Future + u16 uFrameId; // H264/H264 frame id (monotonically increasing) + u16 uDummy1; + u16 uDummy2; + u8 uDummy3; + u32 uDummy4; + u32 uExtraData; // not used, for future + // After video header, first two bites are the size of actual video data, part of error reconstruction as video data +} __attribute__((packed)) t_packet_header_video_full_98; + +typedef struct +{ + u32 uTime1; + u32 uTime2; + u32 uTime3; + u32 uTime4; + u32 uTime5; + u32 uTime6; + u32 uVideoCRC; +} __attribute__((packed)) t_packet_header_video_full_98_debug_info; + + //--------------------------------------- // COMPONENT RC PACKETS @@ -698,7 +682,7 @@ typedef struct #define PACKET_TYPE_AUX_DATA_LINK_DOWNLOAD 46 // upload data link packet from controller to vehicle // payload is a data link segment index and data -#define PACKET_TYPE_RUBY_TELEMETRY_VIDEO_INFO_STATS 47 // has a shared_mem_video_info_stats structure +#define PACKET_TYPE_RUBY_TELEMETRY_VIDEO_INFO_STATS 47 // has a shared_mem_video_frames_stats structure #define MAX_HISTORY_VEHICLE_TX_STATS_SLICES 40 typedef struct @@ -864,7 +848,9 @@ extern "C" { #endif void radio_packet_init(t_packet_header* pPH, u8 component, u8 packet_type, u32 uStreamId); +void radio_packet_compressed_init(t_packet_header_compressed* pPHC, u8 component, u8 packet_type); void radio_packet_compute_crc(u8* pBuffer, int length); +void radio_packet_compressed_compute_crc(u8* pBuffer, int length); int radio_packet_check_crc(u8* pBuffer, int length); int radio_packet_type_is_high_priority(u8 uPacketType); diff --git a/code/radio/radiopackets_rc.c b/code/radio/radiopackets_rc.c index 332bf7d1..766f6b6d 100644 --- a/code/radio/radiopackets_rc.c +++ b/code/radio/radiopackets_rc.c @@ -10,9 +10,9 @@ * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - * Copyright info and developer info must be preserved as is in the user + * Copyright info and developer info must be preserved as is in the user interface, additions could be made to that info. - * Neither the name of the organization nor the + * Neither the name of the organization nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. * Military use is not permited. diff --git a/code/radio/radiopackets_short.c b/code/radio/radiopackets_short.c index 539f9a6a..d1596baf 100644 --- a/code/radio/radiopackets_short.c +++ b/code/radio/radiopackets_short.c @@ -10,9 +10,9 @@ * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - * Copyright info and developer info must be preserved as is in the user + * Copyright info and developer info must be preserved as is in the user interface, additions could be made to that info. - * Neither the name of the organization nor the + * Neither the name of the organization nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. * Military use is not permited. diff --git a/code/radio/radiopackets_short.h b/code/radio/radiopackets_short.h index b0e106da..7d4f3d11 100644 --- a/code/radio/radiopackets_short.h +++ b/code/radio/radiopackets_short.h @@ -4,6 +4,9 @@ #define SHORT_PACKET_START_BYTE_START_PACKET 0x0F #define SHORT_PACKET_START_BYTE_END_PACKET 0x10 +// Compressed packets (t_packet_header_compressed) are sent only on high bandwidth radio links +// Short packets (t_packet_header_short) are sent only on low bandwidth radio links + // Short packets usually have 24 bytes usable payload typedef struct { diff --git a/code/renderer/cairo_mpp.txt b/code/renderer/cairo_mpp.txt index e78da667..5f6c6abd 100644 --- a/code/renderer/cairo_mpp.txt +++ b/code/renderer/cairo_mpp.txt @@ -9,3 +9,7 @@ cd mpp cmake -B build sudo cmake --build build --target install + + +* drivers Pi3: 'make' -j4 KVER=5.10.103-v7+ KSRC=/lib/modules/5.10.103-v7+/build +* drivers Pi4: 'make' -j4 KVER=5.10.103-v7l+ KSRC=/lib/modules/5.10.103-v7l+/build diff --git a/code/base/controller_utils.cpp b/code/utils/utils_controller.cpp similarity index 81% rename from code/base/controller_utils.cpp rename to code/utils/utils_controller.cpp index 7ff852ff..535c6d89 100644 --- a/code/base/controller_utils.cpp +++ b/code/utils/utils_controller.cpp @@ -29,13 +29,14 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -#include "base.h" -#include "config.h" -#include "hardware.h" -#include "hardware_radio.h" -#include "hw_procs.h" -#include "controller_utils.h" -#include "ctrl_interfaces.h" +#include "../base/base.h" +#include "../base/config.h" +#include "../base/hardware.h" +#include "../base/hardware_radio.h" +#include "../base/hw_procs.h" +#include "../base/tx_powers.h" +#include "../base/ctrl_interfaces.h" +#include "../utils/utils_controller.h" #if defined(HW_PLATFORM_RASPBERRY) || defined(HW_PLATFORM_RADXA_ZERO3) @@ -473,12 +474,120 @@ void propagate_video_profile_changes(type_video_link_profile* pOrgProfile, type_ pAllProfiles[VIDEO_PROFILE_MQ].h264refresh = pUpdatedProfile->h264refresh; pAllProfiles[VIDEO_PROFILE_LQ].h264refresh = pUpdatedProfile->h264refresh; } +} + +int tx_powers_get_max_usable_power_mw_for_controller() +{ + // Select the max mw power for any present card + int iMaxPowerMw = 10; + + for( int i=0; iisConfigurable) || (! pRadioHWInfo->isSupported) ) + continue; + + t_ControllerRadioInterfaceInfo* pCRII = controllerGetRadioCardInfo(pRadioHWInfo->szMAC); + if ( NULL == pCRII ) + continue; - if ( pOrgProfile->insertPPS != pUpdatedProfile->insertPPS ) + int iDriver = pRadioHWInfo->iRadioDriver; + int iCardModel = pCRII->cardModel; + + int iPowerMaxRaw = tx_powers_get_max_usable_power_raw_for_card(iDriver, iCardModel); + int iPowerMw = tx_powers_convert_raw_to_mw(iDriver, iCardModel, iPowerMaxRaw); + if ( iPowerMw > iMaxPowerMw ) + iMaxPowerMw = iPowerMw; + } + return iMaxPowerMw; +} + +int apply_controller_radio_tx_powers(Model* pModel, bool bFixedPower, bool bComputeOnly) +{ + load_ControllerInterfacesSettings(); + + int iMaxPowerMwSet = 0; + int iPowerMwToOverwrite = 0; + + if ( ! bFixedPower ) + if ( (NULL != pModel) && pModel->radioInterfacesParams.iAutoControllerTxPower ) { - pAllProfiles[VIDEO_PROFILE_MQ].insertPPS = pUpdatedProfile->insertPPS; - pAllProfiles[VIDEO_PROFILE_LQ].insertPPS = pUpdatedProfile->insertPPS; + int iMwPowers[MAX_RADIO_INTERFACES]; + tx_power_get_current_mw_powers_for_model(pModel, &iMwPowers[0]); + int iMaxPowerMwVehicle = 0; + for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) + { + log_line("Vehicle radio interface %d raw tx power: %d (%d mw)", i+1, pModel->radioInterfacesParams.interface_raw_power[i], iMwPowers[i]); + if ( iMwPowers[i] > iMaxPowerMwVehicle ) + iMaxPowerMwVehicle = iMwPowers[i]; + } + log_line("Vehicle max tx power (mw): %d", iMaxPowerMwVehicle); + iPowerMwToOverwrite = iMaxPowerMwVehicle * 2; } + + if ( 0 != iPowerMwToOverwrite ) + log_line("Applying all radio interfaces tx power overwrite (from model): %d mW", iPowerMwToOverwrite); + else + log_line("Applying all radio interfaces raw tx powers..."); + + for( int i=0; iisConfigurable) || (! pRadioHWInfo->isSupported) ) + continue; + + t_ControllerRadioInterfaceInfo* pCRII = controllerGetRadioCardInfo(pRadioHWInfo->szMAC); + if ( NULL == pCRII ) + continue; + + int iDriver = pRadioHWInfo->iRadioDriver; + int iCardModel = pCRII->cardModel; + int iPowerRawToSet = pCRII->iRawPowerLevel; + + if ( 0 != iPowerMwToOverwrite ) + { + int iCardMaxPowerMw = tx_powers_get_max_usable_power_mw_for_card(iDriver, iCardModel); + int iCardNewPowerMw = iPowerMwToOverwrite; + if ( iCardNewPowerMw > iCardMaxPowerMw ) + iCardNewPowerMw = iCardMaxPowerMw; + iPowerRawToSet = tx_powers_convert_mw_to_raw(iDriver, iCardModel, iCardNewPowerMw); + pCRII->iRawPowerLevel = iPowerRawToSet; + log_line("Set radio interface %d raw tx power to: %d (%d mw of %d mw max for this card)", i+1, iPowerRawToSet, iCardNewPowerMw, iCardMaxPowerMw); + } + log_line("Radio interface %d raw tx power: %d", i+1, pCRII->iRawPowerLevel); + + if ( ! bComputeOnly ) + { + if ( hardware_radio_driver_is_rtl8812au_card(pRadioHWInfo->iRadioDriver) ) + hardware_radio_set_txpower_raw_rtl8812au(i, iPowerRawToSet); + if ( hardware_radio_driver_is_rtl8812eu_card(pRadioHWInfo->iRadioDriver) ) + hardware_radio_set_txpower_raw_rtl8812eu(i, iPowerRawToSet); + if ( hardware_radio_driver_is_atheros_card(pRadioHWInfo->iRadioDriver) ) + hardware_radio_set_txpower_raw_atheros(i, iPowerRawToSet); + } + + int iPowerMwSet = tx_powers_convert_raw_to_mw(iDriver, iCardModel, iPowerRawToSet); + if ( iPowerMwSet > iMaxPowerMwSet ) + iMaxPowerMwSet = iPowerMwSet; + } + if ( 0 != iPowerMwToOverwrite ) + log_line("Applied all radio interfaces tx power overwrite (from model): %d mW", iPowerMwToOverwrite); + else + log_line("Applied all radio interfaces raw tx powers."); + + if ( bComputeOnly ) + log_line("Computed a max tx power of %d mw", iMaxPowerMwSet); + else + log_line("Applied a max tx power of %d mw", iMaxPowerMwSet); + return iMaxPowerMwSet; } #else @@ -489,4 +598,6 @@ bool controller_utils_usb_import_has_matching_controller_id_file() { return fals bool controller_utils_usb_import_has_any_controller_id_file() { return false; } int controller_count_asignable_radio_interfaces_to_vehicle_radio_link(Model* pModel, int iVehicleRadioLinkId) { return 0; } void propagate_video_profile_changes(type_video_link_profile* pOrg, type_video_link_profile* pUpdated, type_video_link_profile* pAllProfiles){} +int tx_powers_get_max_usable_power_mw_for_controller(){ return 0; } +int apply_controller_radio_tx_powers(Model* pModel, bool bFixedPower, bool bComputeOnl){ return 0; } #endif \ No newline at end of file diff --git a/code/base/controller_utils.h b/code/utils/utils_controller.h similarity index 79% rename from code/base/controller_utils.h rename to code/utils/utils_controller.h index 9a3be404..d8e3fe8c 100644 --- a/code/base/controller_utils.h +++ b/code/utils/utils_controller.h @@ -14,3 +14,7 @@ bool controller_utils_usb_import_has_any_controller_id_file(); int controller_count_asignable_radio_interfaces_to_vehicle_radio_link(Model* pModel, int iVehicleRadioLinkId); void propagate_video_profile_changes(type_video_link_profile* pOrgProfile, type_video_link_profile* pUpdatedProfile, type_video_link_profile* pAllProfiles); + +int tx_powers_get_max_usable_power_mw_for_controller(); +// Returns the max set value in mW +int apply_controller_radio_tx_powers(Model* pModel, bool bFixedPower, bool bComputeOnly); diff --git a/code/r_vehicle/utils_vehicle.cpp b/code/utils/utils_vehicle.cpp similarity index 83% rename from code/r_vehicle/utils_vehicle.cpp rename to code/utils/utils_vehicle.cpp index e2bac918..f0dbd824 100644 --- a/code/r_vehicle/utils_vehicle.cpp +++ b/code/utils/utils_vehicle.cpp @@ -35,10 +35,12 @@ #include "../base/config.h" #include "../base/models.h" #include "../base/radio_utils.h" +#include "../base/utils.h" +#include "../base/hardware_radio_txpower.h" #include "../common/string_utils.h" -#include "utils_vehicle.h" -#include "shared_vars.h" -#include "timers.h" +#include "../utils/utils_vehicle.h" +#include "../radio/radioflags.h" + bool videoLinkProfileIsOnlyVideoKeyframeChanged(type_video_link_profile* pOldProfile, type_video_link_profile* pNewProfile) { @@ -70,6 +72,23 @@ bool videoLinkProfileIsOnlyBitrateChanged(type_video_link_profile* pOldProfile, return false; } +bool videoLinkProfileIsOnlyIPQuantizationDeltaChanged(type_video_link_profile* pOldProfile, type_video_link_profile* pNewProfile) +{ + if ( NULL == pOldProfile || NULL == pNewProfile ) + return false; + + type_video_link_profile tmp; + memcpy(&tmp, pNewProfile, sizeof(type_video_link_profile) ); + tmp.iIPQuantizationDelta = pOldProfile->iIPQuantizationDelta; + + if ( 0 == memcmp(pOldProfile, &tmp, sizeof(type_video_link_profile)) ) + if ( pOldProfile->iIPQuantizationDelta != pNewProfile->iIPQuantizationDelta ) + return true; + + return false; +} + + bool videoLinkProfileIsOnlyECSchemeChanged(type_video_link_profile* pOldProfile, type_video_link_profile* pNewProfile) { if ( NULL == pOldProfile || NULL == pNewProfile ) @@ -96,7 +115,7 @@ bool videoLinkProfileIsOnlyAdaptiveVideoChanged(type_video_link_profile* pOldPro type_video_link_profile tmp; memcpy(&tmp, pNewProfile, sizeof(type_video_link_profile) ); - tmp.uProfileEncodingFlags = (tmp.uProfileEncodingFlags & (~(VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_LINK | VIDEO_PROFILE_ENCODING_FLAG_ADAPTIVE_VIDEO_LINK_USE_CONTROLLER_INFO_TOO))) | (pOldProfile->uProfileEncodingFlags & ( VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_LINK | VIDEO_PROFILE_ENCODING_FLAG_ADAPTIVE_VIDEO_LINK_USE_CONTROLLER_INFO_TOO)); + tmp.uProfileEncodingFlags = (tmp.uProfileEncodingFlags & (~(VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_LINK | VIDEO_PROFILE_ENCODING_FLAG_ADAPTIVE_VIDEO_LINK_USE_CONTROLLER_INFO_TOO | VIDEO_PROFILE_ENCODING_FLAG_USE_MEDIUM_ADAPTIVE_VIDEO))) | (pOldProfile->uProfileEncodingFlags & ( VIDEO_PROFILE_ENCODING_FLAG_ENABLE_ADAPTIVE_VIDEO_LINK | VIDEO_PROFILE_ENCODING_FLAG_ADAPTIVE_VIDEO_LINK_USE_CONTROLLER_INFO_TOO | VIDEO_PROFILE_ENCODING_FLAG_USE_MEDIUM_ADAPTIVE_VIDEO)); if ( 0 == memcmp(pOldProfile, &tmp, sizeof(type_video_link_profile)) ) { @@ -104,6 +123,8 @@ bool videoLinkProfileIsOnlyAdaptiveVideoChanged(type_video_link_profile* pOldPro return true; if ( (pOldProfile->uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ADAPTIVE_VIDEO_LINK_USE_CONTROLLER_INFO_TOO) != (pNewProfile->uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_ADAPTIVE_VIDEO_LINK_USE_CONTROLLER_INFO_TOO) ) return true; + if ( (pOldProfile->uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_USE_MEDIUM_ADAPTIVE_VIDEO) != (pNewProfile->uProfileEncodingFlags & VIDEO_PROFILE_ENCODING_FLAG_USE_MEDIUM_ADAPTIVE_VIDEO) ) + return true; } return false; } @@ -227,7 +248,7 @@ bool configure_radio_interfaces_for_current_model(Model* pModel, shared_mem_proc continue; } hardware_radio_sik_set_frequency_txpower_airspeed_lbt_ecc(pRadioHWInfo, - uRadioLinkFrequency, pModel->radioInterfacesParams.txPowerSiK, + uRadioLinkFrequency, pModel->radioInterfacesParams.interface_raw_power[iInterface], pModel->radioLinksParams.link_datarate_data_bps[iLink], (u32)((pModel->radioLinksParams.link_radio_flags[iLink] & RADIO_FLAGS_SIK_ECC)?1:0), (u32)((pModel->radioLinksParams.link_radio_flags[iLink] & RADIO_FLAGS_SIK_LBT)?1:0), @@ -272,32 +293,37 @@ bool configure_radio_interfaces_for_current_model(Model* pModel, shared_mem_proc hardware_save_radio_info(); hardware_sleep_ms(50); - if ( hardware_is_running_on_openipc() ) - { - char szComm[256]; - for( int i=0; iisConfigurable ) - { - log_line("Configuring radio interface %d (%s): radio interface is not configurable. Skipping it.", i+1, pRadioHWInfo->szName); - continue; - } - if ( (pRadioHWInfo->iRadioType == RADIO_TYPE_REALTEK) || - (pRadioHWInfo->iRadioType == RADIO_TYPE_RALINK) ) - { - sprintf(szComm, "iw dev %s set txpower fixed %d", pRadioHWInfo->szName, -100*pModel->radioInterfacesParams.txPowerRTL8812AU); - hw_execute_bash_command(szComm, NULL); - } - } - } + apply_vehicle_tx_power_levels(pModel); log_line("CONFIGURE RADIO END ---------------------------------------------------------"); return bMissmatch; } + +void apply_vehicle_tx_power_levels(Model* pModel) +{ + if ( NULL == pModel ) + { + log_softerror_and_alarm("Passing NULL model on applying model tx powers."); + return; + } + + log_line("Aplying all radio interfaces raw tx powers..."); + for( int i=0; iradioInterfacesParams.interfaces_count; i++ ) + { + if ( ! hardware_radio_is_index_wifi_radio(i) ) + continue; + if ( hardware_radio_index_is_sik_radio(i) ) + continue; + radio_hw_info_t* pRadioHWInfo = hardware_get_radio_info(i); + if ( ! pRadioHWInfo->isConfigurable ) + continue; + if ( hardware_radio_driver_is_rtl8812au_card(pRadioHWInfo->iRadioDriver) ) + hardware_radio_set_txpower_raw_rtl8812au(i, pModel->radioInterfacesParams.interface_raw_power[i]); + if ( hardware_radio_driver_is_rtl8812eu_card(pRadioHWInfo->iRadioDriver) ) + hardware_radio_set_txpower_raw_rtl8812eu(i, pModel->radioInterfacesParams.interface_raw_power[i]); + if ( hardware_radio_driver_is_atheros_card(pRadioHWInfo->iRadioDriver) ) + hardware_radio_set_txpower_raw_atheros(i, pModel->radioInterfacesParams.interface_raw_power[i]); + } + log_line("Aplied all radio interfaces raw tx powers."); +} \ No newline at end of file diff --git a/code/r_vehicle/utils_vehicle.h b/code/utils/utils_vehicle.h similarity index 81% rename from code/r_vehicle/utils_vehicle.h rename to code/utils/utils_vehicle.h index e5bba51a..74760c7d 100644 --- a/code/r_vehicle/utils_vehicle.h +++ b/code/utils/utils_vehicle.h @@ -7,9 +7,12 @@ bool videoLinkProfileIsOnlyVideoKeyframeChanged(type_video_link_profile* pOldProfile, type_video_link_profile* pNewProfile); bool videoLinkProfileIsOnlyBitrateChanged(type_video_link_profile* pOldProfile, type_video_link_profile* pNewProfile); +bool videoLinkProfileIsOnlyIPQuantizationDeltaChanged(type_video_link_profile* pOldProfile, type_video_link_profile* pNewProfile); bool videoLinkProfileIsOnlyECSchemeChanged(type_video_link_profile* pOldProfile, type_video_link_profile* pNewProfile); bool videoLinkProfileIsOnlyAdaptiveVideoChanged(type_video_link_profile* pOldProfile, type_video_link_profile* pNewProfile); // To fix //void video_overwrites_init(shared_mem_video_link_overwrites* pSMVLO, Model* pModel); bool configure_radio_interfaces_for_current_model(Model* pModel, shared_mem_process_stats* pProcessStats); + +void apply_vehicle_tx_power_levels(Model* pModel);