Path: blob/main/sys/contrib/dev/ath/ath_hal/ar9300/ar9300_attach.c
48525 views
/*1* Copyright (c) 2013 Qualcomm Atheros, Inc.2*3* Permission to use, copy, modify, and/or distribute this software for any4* purpose with or without fee is hereby granted, provided that the above5* copyright notice and this permission notice appear in all copies.6*7* THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES WITH8* REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF MERCHANTABILITY9* AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY SPECIAL, DIRECT,10* INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES WHATSOEVER RESULTING FROM11* LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR12* OTHER TORTIOUS ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR13* PERFORMANCE OF THIS SOFTWARE.14*/1516#include "opt_ah.h"1718#include "ah.h"19#include "ah_internal.h"20#include "ah_devid.h"2122#include "ar9300/ar9300desc.h"23#include "ar9300/ar9300.h"24#include "ar9300/ar9300reg.h"25#include "ar9300/ar9300phy.h"26#include "ar9300/ar9300paprd.h"2728#include "ar9300/ar9300_stub.h"29#include "ar9300/ar9300_stub_funcs.h"303132/* Add static register initialization vectors */33#include "ar9300/ar9300_osprey22.ini"34#include "ar9300/ar9330_11.ini"35#include "ar9300/ar9330_12.ini"36#include "ar9300/ar9340.ini"37#include "ar9300/ar9485.ini"38#include "ar9300/ar9485_1_1.ini"39#include "ar9300/ar9300_jupiter10.ini"40/* TODO: convert the 2.0 code to use the new initvals from ath9k */41#include "ar9300/ar9300_jupiter20.ini"42#include "ar9300/ar9462_2p0_initvals.h"43#include "ar9300/ar9462_2p1_initvals.h"44#include "ar9300/ar9580.ini"45#include "ar9300/ar955x.ini"46#include "ar9300/ar953x.ini"47#include "ar9300/ar9300_aphrodite10.ini"484950/* Include various freebsd specific HAL methods */51#include "ar9300/ar9300_freebsd.h"5253/* XXX duplicate in ar9300_radio.c ? */54static HAL_BOOL ar9300_get_chip_power_limits(struct ath_hal *ah,55struct ieee80211_channel *chan);5657static inline HAL_STATUS ar9300_init_mac_addr(struct ath_hal *ah);58static inline HAL_STATUS ar9300_hw_attach(struct ath_hal *ah);59static inline void ar9300_hw_detach(struct ath_hal *ah);60static int16_t ar9300_get_nf_adjust(struct ath_hal *ah,61const HAL_CHANNEL_INTERNAL *c);62#if 063int ar9300_get_cal_intervals(struct ath_hal *ah, HAL_CALIBRATION_TIMER **timerp,64HAL_CAL_QUERY query);65#endif6667#if ATH_TRAFFIC_FAST_RECOVER68unsigned long ar9300_get_pll3_sqsum_dvc(struct ath_hal *ah);69#endif70static int ar9300_init_offsets(struct ath_hal *ah, u_int16_t devid);717273static void74ar9300_disable_pcie_phy(struct ath_hal *ah);7576static const HAL_PERCAL_DATA iq_cal_single_sample =77{IQ_MISMATCH_CAL,78MIN_CAL_SAMPLES,79PER_MAX_LOG_COUNT,80ar9300_iq_cal_collect,81ar9300_iq_calibration};8283#if 084static HAL_CALIBRATION_TIMER ar9300_cals[] =85{ {IQ_MISMATCH_CAL, /* Cal type */861200000, /* Cal interval */870 /* Cal timestamp */88},89{TEMP_COMP_CAL,905000,91092},93};94#endif9596#if ATH_PCIE_ERROR_MONITOR9798int ar9300_start_pcie_error_monitor(struct ath_hal *ah, int b_auto_stop)99{100u_int32_t val;101102/* Clear the counters */103OS_REG_WRITE(ah, PCIE_CO_ERR_CTR_CTR0, 0);104OS_REG_WRITE(ah, PCIE_CO_ERR_CTR_CTR1, 0);105106/* Read the previous value */107val = OS_REG_READ(ah, PCIE_CO_ERR_CTR_CTRL);108109/* Set auto_stop */110if (b_auto_stop) {111val |=112RCVD_ERR_CTR_AUTO_STOP | BAD_TLP_ERR_CTR_AUTO_STOP |113BAD_DLLP_ERR_CTR_AUTO_STOP | RPLY_TO_ERR_CTR_AUTO_STOP |114RPLY_NUM_RO_ERR_CTR_AUTO_STOP;115} else {116val &= ~(117RCVD_ERR_CTR_AUTO_STOP | BAD_TLP_ERR_CTR_AUTO_STOP |118BAD_DLLP_ERR_CTR_AUTO_STOP | RPLY_TO_ERR_CTR_AUTO_STOP |119RPLY_NUM_RO_ERR_CTR_AUTO_STOP);120}121OS_REG_WRITE(ah, PCIE_CO_ERR_CTR_CTRL, val );122123/*124* Start to run.125* This has to be done separately from the above auto_stop flag setting,126* to avoid a HW race condition.127*/128val |=129RCVD_ERR_CTR_RUN | BAD_TLP_ERR_CTR_RUN | BAD_DLLP_ERR_CTR_RUN |130RPLY_TO_ERR_CTR_RUN | RPLY_NUM_RO_ERR_CTR_RUN;131OS_REG_WRITE(ah, PCIE_CO_ERR_CTR_CTRL, val);132133return 0;134}135136int ar9300_read_pcie_error_monitor(struct ath_hal *ah, void* p_read_counters)137{138u_int32_t val;139ar_pcie_error_moniter_counters *p_counters =140(ar_pcie_error_moniter_counters*) p_read_counters;141142val = OS_REG_READ(ah, PCIE_CO_ERR_CTR_CTR0);143144p_counters->uc_receiver_errors = MS(val, RCVD_ERR_MASK);145p_counters->uc_bad_tlp_errors = MS(val, BAD_TLP_ERR_MASK);146p_counters->uc_bad_dllp_errors = MS(val, BAD_DLLP_ERR_MASK);147148val = OS_REG_READ(ah, PCIE_CO_ERR_CTR_CTR1);149150p_counters->uc_replay_timeout_errors = MS(val, RPLY_TO_ERR_MASK);151p_counters->uc_replay_number_rollover_errors= MS(val, RPLY_NUM_RO_ERR_MASK);152153return 0;154}155156int ar9300_stop_pcie_error_monitor(struct ath_hal *ah)157{158u_int32_t val;159160/* Read the previous value */161val = OS_REG_READ(ah, PCIE_CO_ERR_CTR_CTRL);162163val &= ~(164RCVD_ERR_CTR_RUN |165BAD_TLP_ERR_CTR_RUN |166BAD_DLLP_ERR_CTR_RUN |167RPLY_TO_ERR_CTR_RUN |168RPLY_NUM_RO_ERR_CTR_RUN);169170/* Start to stop */171OS_REG_WRITE(ah, PCIE_CO_ERR_CTR_CTRL, val );172173return 0;174}175176#endif /* ATH_PCIE_ERROR_MONITOR */177178#if 0179/* WIN32 does not support C99 */180static const struct ath_hal_private ar9300hal = {181{182ar9300_get_rate_table, /* ah_get_rate_table */183ar9300_detach, /* ah_detach */184185/* Reset Functions */186ar9300_reset, /* ah_reset */187ar9300_phy_disable, /* ah_phy_disable */188ar9300_disable, /* ah_disable */189ar9300_config_pci_power_save, /* ah_config_pci_power_save */190ar9300_set_pcu_config, /* ah_set_pcu_config */191ar9300_calibration, /* ah_per_calibration */192ar9300_reset_cal_valid, /* ah_reset_cal_valid */193ar9300_set_tx_power_limit, /* ah_set_tx_power_limit */194195#if ATH_ANT_DIV_COMB196ar9300_ant_ctrl_set_lna_div_use_bt_ant, /* ah_ant_ctrl_set_lna_div_use_bt_ant */197#endif /* ATH_ANT_DIV_COMB */198#ifdef ATH_SUPPORT_DFS199ar9300_radar_wait, /* ah_radar_wait */200201/* New DFS functions */202ar9300_check_dfs, /* ah_ar_check_dfs */203ar9300_dfs_found, /* ah_ar_dfs_found */204ar9300_enable_dfs, /* ah_ar_enable_dfs */205ar9300_get_dfs_thresh, /* ah_ar_get_dfs_thresh */206ar9300_get_dfs_radars, /* ah_ar_get_dfs_radars */207ar9300_adjust_difs, /* ah_adjust_difs */208ar9300_dfs_config_fft, /* ah_dfs_config_fft */209ar9300_dfs_cac_war, /* ah_dfs_cac_war */210ar9300_cac_tx_quiet, /* ah_cac_tx_quiet */211#endif212ar9300_get_extension_channel, /* ah_get_extension_channel */213ar9300_is_fast_clock_enabled, /* ah_is_fast_clock_enabled */214215/* Transmit functions */216ar9300_update_tx_trig_level, /* ah_update_tx_trig_level */217ar9300_get_tx_trig_level, /* ah_get_tx_trig_level */218ar9300_setup_tx_queue, /* ah_setup_tx_queue */219ar9300_set_tx_queue_props, /* ah_set_tx_queue_props */220ar9300_get_tx_queue_props, /* ah_get_tx_queue_props */221ar9300_release_tx_queue, /* ah_release_tx_queue */222ar9300_reset_tx_queue, /* ah_reset_tx_queue */223ar9300_get_tx_dp, /* ah_get_tx_dp */224ar9300_set_tx_dp, /* ah_set_tx_dp */225ar9300_num_tx_pending, /* ah_num_tx_pending */226ar9300_start_tx_dma, /* ah_start_tx_dma */227ar9300_stop_tx_dma, /* ah_stop_tx_dma */228ar9300_stop_tx_dma_indv_que, /* ah_stop_tx_dma_indv_que */229ar9300_abort_tx_dma, /* ah_abort_tx_dma */230ar9300_fill_tx_desc, /* ah_fill_tx_desc */231ar9300_set_desc_link, /* ah_set_desc_link */232ar9300_get_desc_link_ptr, /* ah_get_desc_link_ptr */233ar9300_clear_tx_desc_status, /* ah_clear_tx_desc_status */234#ifdef ATH_SWRETRY235ar9300_clear_dest_mask, /* ah_clear_dest_mask */236#endif237ar9300_proc_tx_desc, /* ah_proc_tx_desc */238ar9300_get_raw_tx_desc, /* ah_get_raw_tx_desc */239ar9300_get_tx_rate_code, /* ah_get_tx_rate_code */240AH_NULL, /* ah_get_tx_intr_queue */241ar9300_tx_req_intr_desc, /* ah_req_tx_intr_desc */242ar9300_calc_tx_airtime, /* ah_calc_tx_airtime */243ar9300_setup_tx_status_ring, /* ah_setup_tx_status_ring */244245/* RX Functions */246ar9300_get_rx_dp, /* ah_get_rx_dp */247ar9300_set_rx_dp, /* ah_set_rx_dp */248ar9300_enable_receive, /* ah_enable_receive */249ar9300_stop_dma_receive, /* ah_stop_dma_receive */250ar9300_start_pcu_receive, /* ah_start_pcu_receive */251ar9300_stop_pcu_receive, /* ah_stop_pcu_receive */252ar9300_set_multicast_filter, /* ah_set_multicast_filter */253ar9300_get_rx_filter, /* ah_get_rx_filter */254ar9300_set_rx_filter, /* ah_set_rx_filter */255ar9300_set_rx_sel_evm, /* ah_set_rx_sel_evm */256ar9300_set_rx_abort, /* ah_set_rx_abort */257AH_NULL, /* ah_setup_rx_desc */258ar9300_proc_rx_desc, /* ah_proc_rx_desc */259ar9300_get_rx_key_idx, /* ah_get_rx_key_idx */260ar9300_proc_rx_desc_fast, /* ah_proc_rx_desc_fast */261ar9300_ani_ar_poll, /* ah_rx_monitor */262ar9300_process_mib_intr, /* ah_proc_mib_event */263264/* Misc Functions */265ar9300_get_capability, /* ah_get_capability */266ar9300_set_capability, /* ah_set_capability */267ar9300_get_diag_state, /* ah_get_diag_state */268ar9300_get_mac_address, /* ah_get_mac_address */269ar9300_set_mac_address, /* ah_set_mac_address */270ar9300_get_bss_id_mask, /* ah_get_bss_id_mask */271ar9300_set_bss_id_mask, /* ah_set_bss_id_mask */272ar9300_set_regulatory_domain, /* ah_set_regulatory_domain */273ar9300_set_led_state, /* ah_set_led_state */274ar9300_set_power_led_state, /* ah_setpowerledstate */275ar9300_set_network_led_state, /* ah_setnetworkledstate */276ar9300_write_associd, /* ah_write_associd */277ar9300_force_tsf_sync, /* ah_force_tsf_sync */278ar9300_gpio_cfg_input, /* ah_gpio_cfg_input */279ar9300_gpio_cfg_output, /* ah_gpio_cfg_output */280ar9300_gpio_cfg_output_led_off, /* ah_gpio_cfg_output_led_off */281ar9300_gpio_get, /* ah_gpio_get */282ar9300_gpio_set, /* ah_gpio_set */283ar9300_gpio_get_intr, /* ah_gpio_get_intr */284ar9300_gpio_set_intr, /* ah_gpio_set_intr */285ar9300_gpio_get_polarity, /* ah_gpio_get_polarity */286ar9300_gpio_set_polarity, /* ah_gpio_set_polarity */287ar9300_gpio_get_mask, /* ah_gpio_get_mask */288ar9300_gpio_set_mask, /* ah_gpio_set_mask */289ar9300_get_tsf32, /* ah_get_tsf32 */290ar9300_get_tsf64, /* ah_get_tsf64 */291ar9300_get_tsf2_32, /* ah_get_tsf2_32 */292ar9300_reset_tsf, /* ah_reset_tsf */293ar9300_detect_card_present, /* ah_detect_card_present */294ar9300_update_mib_mac_stats, /* ah_update_mib_mac_stats */295ar9300_get_mib_mac_stats, /* ah_get_mib_mac_stats */296ar9300_get_rfgain, /* ah_get_rf_gain */297ar9300_get_def_antenna, /* ah_get_def_antenna */298ar9300_set_def_antenna, /* ah_set_def_antenna */299ar9300_set_slot_time, /* ah_set_slot_time */300ar9300_set_ack_timeout, /* ah_set_ack_timeout */301ar9300_get_ack_timeout, /* ah_get_ack_timeout */302ar9300_set_coverage_class, /* ah_set_coverage_class */303ar9300_set_quiet, /* ah_set_quiet */304ar9300_set_antenna_switch, /* ah_set_antenna_switch */305ar9300_get_desc_info, /* ah_get_desc_info */306ar9300_select_ant_config, /* ah_select_ant_config */307ar9300_ant_ctrl_common_get, /* ah_ant_ctrl_common_get */308ar9300_ant_swcom_sel, /* ah_ant_swcom_sel */309ar9300_enable_tpc, /* ah_enable_tpc */310AH_NULL, /* ah_olpc_temp_compensation */311#if ATH_SUPPORT_CRDC312ar9300_chain_rssi_diff_compensation,/*ah_chain_rssi_diff_compensation*/313#endif314ar9300_disable_phy_restart, /* ah_disable_phy_restart */315ar9300_enable_keysearch_always,316ar9300_interference_is_present, /* ah_interference_is_present */317ar9300_disp_tpc_tables, /* ah_disp_tpc_tables */318ar9300_get_tpc_tables, /* ah_get_tpc_tables */319/* Key Cache Functions */320ar9300_get_key_cache_size, /* ah_get_key_cache_size */321ar9300_reset_key_cache_entry, /* ah_reset_key_cache_entry */322ar9300_is_key_cache_entry_valid, /* ah_is_key_cache_entry_valid */323ar9300_set_key_cache_entry, /* ah_set_key_cache_entry */324ar9300_set_key_cache_entry_mac, /* ah_set_key_cache_entry_mac */325ar9300_print_keycache, /* ah_print_key_cache */326#if ATH_SUPPORT_KEYPLUMB_WAR327ar9300_check_key_cache_entry, /* ah_check_key_cache_entry */328#endif329/* Power Management Functions */330ar9300_set_power_mode, /* ah_set_power_mode */331ar9300_set_sm_power_mode, /* ah_set_sm_ps_mode */332#if ATH_WOW333ar9300_wow_apply_pattern, /* ah_wow_apply_pattern */334ar9300_wow_enable, /* ah_wow_enable */335ar9300_wow_wake_up, /* ah_wow_wake_up */336#if ATH_WOW_OFFLOAD337ar9300_wowoffload_prep, /* ah_wow_offload_prep */338ar9300_wowoffload_post, /* ah_wow_offload_post */339ar9300_wowoffload_download_rekey_data, /* ah_wow_offload_download_rekey_data */340ar9300_wowoffload_retrieve_data, /* ah_wow_offload_retrieve_data */341ar9300_wowoffload_download_acer_magic, /* ah_wow_offload_download_acer_magic */342ar9300_wowoffload_download_acer_swka, /* ah_wow_offload_download_acer_swka */343ar9300_wowoffload_download_arp_info, /* ah_wow_offload_download_arp_info */344ar9300_wowoffload_download_ns_info, /* ah_wow_offload_download_ns_info */345#endif /* ATH_WOW_OFFLOAD */346#endif347348/* Get Channel Noise */349ath_hal_get_chan_noise, /* ah_get_chan_noise */350ar9300_chain_noise_floor, /* ah_get_chain_noise_floor */351ar9300_get_nf_from_reg, /* ah_get_nf_from_reg */352ar9300_get_rx_nf_offset, /* ah_get_rx_nf_offset */353354/* Beacon Functions */355ar9300_beacon_init, /* ah_beacon_init */356ar9300_set_sta_beacon_timers, /* ah_set_station_beacon_timers */357358/* Interrupt Functions */359ar9300_is_interrupt_pending, /* ah_is_interrupt_pending */360ar9300_get_pending_interrupts, /* ah_get_pending_interrupts */361ar9300_get_interrupts, /* ah_get_interrupts */362ar9300_set_interrupts, /* ah_set_interrupts */363ar9300_set_intr_mitigation_timer, /* ah_set_intr_mitigation_timer */364ar9300_get_intr_mitigation_timer, /* ah_get_intr_mitigation_timer */365ar9300ForceVCS,366ar9300SetDfs3StreamFix,367ar9300Get3StreamSignature,368369/* 11n specific functions (NOT applicable to ar9300) */370ar9300_set_11n_tx_desc, /* ah_set_11n_tx_desc */371/* Update rxchain */372ar9300_set_rx_chainmask, /*ah_set_rx_chainmask*/373/*Updating locationing register */374ar9300_update_loc_ctl_reg, /*ah_update_loc_ctl_reg*/375/* Start PAPRD functions */376ar9300_set_paprd_tx_desc, /* ah_set_paprd_tx_desc */377ar9300_paprd_init_table, /* ah_paprd_init_table */378ar9300_paprd_setup_gain_table, /* ah_paprd_setup_gain_table */379ar9300_paprd_create_curve, /* ah_paprd_create_curve */380ar9300_paprd_is_done, /* ah_paprd_is_done */381ar9300_enable_paprd, /* ah_PAPRDEnable */382ar9300_populate_paprd_single_table,/* ah_paprd_populate_table */383ar9300_is_tx_done, /* ah_is_tx_done */384ar9300_paprd_dec_tx_pwr, /* ah_paprd_dec_tx_pwr*/385ar9300_paprd_thermal_send, /* ah_paprd_thermal_send */386/* End PAPRD functions */387ar9300_set_11n_rate_scenario, /* ah_set_11n_rate_scenario */388ar9300_set_11n_aggr_first, /* ah_set_11n_aggr_first */389ar9300_set_11n_aggr_middle, /* ah_set_11n_aggr_middle */390ar9300_set_11n_aggr_last, /* ah_set_11n_aggr_last */391ar9300_clr_11n_aggr, /* ah_clr_11n_aggr */392ar9300_set_11n_rifs_burst_middle, /* ah_set_11n_rifs_burst_middle */393ar9300_set_11n_rifs_burst_last, /* ah_set_11n_rifs_burst_last */394ar9300_clr_11n_rifs_burst, /* ah_clr_11n_rifs_burst */395ar9300_set_11n_aggr_rifs_burst, /* ah_set_11n_aggr_rifs_burst */396ar9300_set_11n_rx_rifs, /* ah_set_11n_rx_rifs */397ar9300_set_smart_antenna, /* ah_setSmartAntenna */398ar9300_detect_bb_hang, /* ah_detect_bb_hang */399ar9300_detect_mac_hang, /* ah_detect_mac_hang */400ar9300_set_immunity, /* ah_immunity */401ar9300_get_hw_hangs, /* ah_get_hang_types */402ar9300_set_11n_burst_duration, /* ah_set_11n_burst_duration */403ar9300_set_11n_virtual_more_frag, /* ah_set_11n_virtual_more_frag */404ar9300_get_11n_ext_busy, /* ah_get_11n_ext_busy */405ar9300_set_11n_mac2040, /* ah_set_11n_mac2040 */406ar9300_get_11n_rx_clear, /* ah_get_11n_rx_clear */407ar9300_set_11n_rx_clear, /* ah_set_11n_rx_clear */408ar9300_get_mib_cycle_counts_pct, /* ah_get_mib_cycle_counts_pct */409ar9300_dma_reg_dump, /* ah_dma_reg_dump */410411/* force_ppm specific functions */412ar9300_ppm_get_rssi_dump, /* ah_ppm_get_rssi_dump */413ar9300_ppm_arm_trigger, /* ah_ppm_arm_trigger */414ar9300_ppm_get_trigger, /* ah_ppm_get_trigger */415ar9300_ppm_force, /* ah_ppm_force */416ar9300_ppm_un_force, /* ah_ppm_un_force */417ar9300_ppm_get_force_state, /* ah_ppm_get_force_state */418419ar9300_get_spur_info, /* ah_get_spur_info */420ar9300_set_spur_info, /* ah_get_spur_info */421422ar9300_get_min_cca_pwr, /* ah_ar_get_noise_floor_val */423424ar9300_green_ap_ps_on_off, /* ah_set_rx_green_ap_ps_on_off */425ar9300_is_single_ant_power_save_possible, /* ah_is_single_ant_power_save_possible */426427/* radio measurement specific functions */428ar9300_get_mib_cycle_counts, /* ah_get_mib_cycle_counts */429ar9300_get_vow_stats, /* ah_get_vow_stats */430ar9300_clear_mib_counters, /* ah_clear_mib_counters */431#if ATH_GEN_RANDOMNESS432ar9300_get_rssi_chain0, /* ah_get_rssi_chain0 */433#endif434#ifdef ATH_BT_COEX435/* Bluetooth Coexistence functions */436ar9300_set_bt_coex_info, /* ah_set_bt_coex_info */437ar9300_bt_coex_config, /* ah_bt_coex_config */438ar9300_bt_coex_set_qcu_thresh, /* ah_bt_coex_set_qcu_thresh */439ar9300_bt_coex_set_weights, /* ah_bt_coex_set_weights */440ar9300_bt_coex_setup_bmiss_thresh, /* ah_bt_coex_set_bmiss_thresh */441ar9300_bt_coex_set_parameter, /* ah_bt_coex_set_parameter */442ar9300_bt_coex_disable, /* ah_bt_coex_disable */443ar9300_bt_coex_enable, /* ah_bt_coex_enable */444ar9300_get_bt_active_gpio, /* ah_bt_coex_info*/445ar9300_get_wlan_active_gpio, /* ah__coex_wlan_info*/446#endif447/* Generic Timer functions */448ar9300_alloc_generic_timer, /* ah_gentimer_alloc */449ar9300_free_generic_timer, /* ah_gentimer_free */450ar9300_start_generic_timer, /* ah_gentimer_start */451ar9300_stop_generic_timer, /* ah_gentimer_stop */452ar9300_get_gen_timer_interrupts, /* ah_gentimer_get_intr */453454ar9300_set_dcs_mode, /* ah_set_dcs_mode */455ar9300_get_dcs_mode, /* ah_get_dcs_mode */456457#if ATH_ANT_DIV_COMB458ar9300_ant_div_comb_get_config, /* ah_get_ant_dvi_comb_conf */459ar9300_ant_div_comb_set_config, /* ah_set_ant_dvi_comb_conf */460#endif461462ar9300_get_bb_panic_info, /* ah_get_bb_panic_info */463ar9300_handle_radar_bb_panic, /* ah_handle_radar_bb_panic */464ar9300_set_hal_reset_reason, /* ah_set_hal_reset_reason */465466#if ATH_PCIE_ERROR_MONITOR467ar9300_start_pcie_error_monitor, /* ah_start_pcie_error_monitor */468ar9300_read_pcie_error_monitor, /* ah_read_pcie_error_monitor*/469ar9300_stop_pcie_error_monitor, /* ah_stop_pcie_error_monitor*/470#endif /* ATH_PCIE_ERROR_MONITOR */471472#if ATH_SUPPORT_SPECTRAL473/* Spectral scan */474ar9300_configure_spectral_scan, /* ah_ar_configure_spectral */475ar9300_get_spectral_params, /* ah_ar_get_spectral_config */476ar9300_start_spectral_scan, /* ah_ar_start_spectral_scan */477ar9300_stop_spectral_scan, /* ah_ar_stop_spectral_scan */478ar9300_is_spectral_enabled, /* ah_ar_is_spectral_enabled */479ar9300_is_spectral_active, /* ah_ar_is_spectral_active */480ar9300_get_ctl_chan_nf, /* ah_ar_get_ctl_nf */481ar9300_get_ext_chan_nf, /* ah_ar_get_ext_nf */482#endif /* ATH_SUPPORT_SPECTRAL */483484485ar9300_promisc_mode, /* ah_promisc_mode */486ar9300_read_pktlog_reg, /* ah_read_pktlog_reg */487ar9300_write_pktlog_reg, /* ah_write_pktlog_reg */488ar9300_set_proxy_sta, /* ah_set_proxy_sta */489ar9300_get_cal_intervals, /* ah_get_cal_intervals */490#if ATH_TRAFFIC_FAST_RECOVER491ar9300_get_pll3_sqsum_dvc, /* ah_get_pll3_sqsum_dvc */492#endif493#ifdef ATH_SUPPORT_HTC494AH_NULL,495#endif496497#ifdef ATH_TX99_DIAG498/* Tx99 functions */499#ifdef ATH_SUPPORT_HTC500AH_NULL,501AH_NULL,502AH_NULL,503AH_NULL,504AH_NULL,505AH_NULL,506AH_NULL,507#else508AH_NULL,509AH_NULL,510ar9300_tx99_channel_pwr_update, /* ah_tx99channelpwrupdate */511ar9300_tx99_start, /* ah_tx99start */512ar9300_tx99_stop, /* ah_tx99stop */513ar9300_tx99_chainmsk_setup, /* ah_tx99_chainmsk_setup */514ar9300_tx99_set_single_carrier, /* ah_tx99_set_single_carrier */515#endif516#endif517ar9300_chk_rssi_update_tx_pwr,518ar9300_is_skip_paprd_by_greentx, /* ah_is_skip_paprd_by_greentx */519ar9300_hwgreentx_set_pal_spare, /* ah_hwgreentx_set_pal_spare */520#if ATH_SUPPORT_MCI521/* MCI Coexistence Functions */522ar9300_mci_setup, /* ah_mci_setup */523ar9300_mci_send_message, /* ah_mci_send_message */524ar9300_mci_get_interrupt, /* ah_mci_get_interrupt */525ar9300_mci_state, /* ah_mci_state */526ar9300_mci_detach, /* ah_mci_detach */527#endif528ar9300_reset_hw_beacon_proc_crc, /* ah_reset_hw_beacon_proc_crc */529ar9300_get_hw_beacon_rssi, /* ah_get_hw_beacon_rssi */530ar9300_set_hw_beacon_rssi_threshold,/*ah_set_hw_beacon_rssi_threshold*/531ar9300_reset_hw_beacon_rssi, /* ah_reset_hw_beacon_rssi */532ar9300_mat_enable, /* ah_mat_enable */533ar9300_dump_keycache, /* ah_dump_keycache */534ar9300_is_ani_noise_spur, /* ah_is_ani_noise_spur */535ar9300_set_hw_beacon_proc, /* ah_set_hw_beacon_proc */536ar9300_set_ctl_pwr, /* ah_set_ctl_pwr */537ar9300_set_txchainmaskopt, /* ah_set_txchainmaskopt */538},539540ar9300_get_channel_edges, /* ah_get_channel_edges */541ar9300_get_wireless_modes, /* ah_get_wireless_modes */542ar9300_eeprom_read_word, /* ah_eeprom_read */543AH_NULL,544ar9300_eeprom_dump_support, /* ah_eeprom_dump */545ar9300_get_chip_power_limits, /* ah_get_chip_power_limits */546547ar9300_get_nf_adjust, /* ah_get_nf_adjust */548/* rest is zero'd by compiler */549};550#endif551552/*553* Read MAC version/revision information from Chip registers and initialize554* local data structures.555*/556void557ar9300_read_revisions(struct ath_hal *ah)558{559u_int32_t val;560561/* XXX verify if this is the correct way to read revision on Osprey */562/* new SREV format for Sowl and later */563val = OS_REG_READ(ah, AR_HOSTIF_REG(ah, AR_SREV));564565if (AH_PRIVATE(ah)->ah_devid == AR9300_DEVID_AR9340) {566/* XXX: AR_SREV register in Wasp reads 0 */567AH_PRIVATE(ah)->ah_macVersion = AR_SREV_VERSION_WASP;568} else if(AH_PRIVATE(ah)->ah_devid == AR9300_DEVID_QCA955X) {569/* XXX: AR_SREV register in Scorpion reads 0 */570AH_PRIVATE(ah)->ah_macVersion = AR_SREV_VERSION_SCORPION;571} else if(AH_PRIVATE(ah)->ah_devid == AR9300_DEVID_QCA953X) {572/* XXX: AR_SREV register in HoneyBEE reads 0 */573AH_PRIVATE(ah)->ah_macVersion = AR_SREV_VERSION_HONEYBEE;574} else {575/*576* Include 6-bit Chip Type (masked to 0)577* to differentiate from pre-Sowl versions578*/579AH_PRIVATE(ah)->ah_macVersion =580(val & AR_SREV_VERSION2) >> AR_SREV_TYPE2_S;581}582583584585586587#ifdef AH_SUPPORT_HORNET588/*589* EV74984, due to Hornet 1.1 didn't update WMAC revision,590* so that have to read SoC's revision ID instead591*/592if (AH_PRIVATE(ah)->ah_macVersion == AR_SREV_VERSION_HORNET) {593#define AR_SOC_RST_REVISION_ID 0xB8060090594#define REG_READ(_reg) *((volatile u_int32_t *)(_reg))595if ((REG_READ(AR_SOC_RST_REVISION_ID) & AR_SREV_REVISION_HORNET_11_MASK)596== AR_SREV_REVISION_HORNET_11)597{598AH_PRIVATE(ah)->ah_macRev = AR_SREV_REVISION_HORNET_11;599} else {600AH_PRIVATE(ah)->ah_macRev = MS(val, AR_SREV_REVISION2);601}602#undef REG_READ603#undef AR_SOC_RST_REVISION_ID604} else605#endif606if (AH_PRIVATE(ah)->ah_macVersion == AR_SREV_VERSION_WASP)607{608#define AR_SOC_RST_REVISION_ID 0xB8060090609#define REG_READ(_reg) *((volatile u_int32_t *)(_reg))610611AH_PRIVATE(ah)->ah_macRev =612REG_READ(AR_SOC_RST_REVISION_ID) & AR_SREV_REVISION_WASP_MASK;613#undef REG_READ614#undef AR_SOC_RST_REVISION_ID615}616else617AH_PRIVATE(ah)->ah_macRev = MS(val, AR_SREV_REVISION2);618619if (AR_SREV_JUPITER(ah) || AR_SREV_APHRODITE(ah)) {620AH_PRIVATE(ah)->ah_ispcie = AH_TRUE;621}622else {623AH_PRIVATE(ah)->ah_ispcie =624(val & AR_SREV_TYPE2_HOST_MODE) ? 0 : 1;625}626627}628629/*630* Attach for an AR9300 part.631*/632struct ath_hal *633ar9300_attach(u_int16_t devid, HAL_SOFTC sc, HAL_BUS_TAG st,634HAL_BUS_HANDLE sh, uint16_t *eepromdata, HAL_OPS_CONFIG *ah_config,635HAL_STATUS *status)636{637struct ath_hal_9300 *ahp;638struct ath_hal *ah;639struct ath_hal_private *ahpriv;640HAL_STATUS ecode;641642HAL_NO_INTERSPERSED_READS;643644/* NB: memory is returned zero'd */645ahp = ar9300_new_state(devid, sc, st, sh, eepromdata, ah_config, status);646if (ahp == AH_NULL) {647return AH_NULL;648}649ah = &ahp->ah_priv.h;650ar9300_init_offsets(ah, devid);651ahpriv = AH_PRIVATE(ah);652// AH_PRIVATE(ah)->ah_bustype = bustype;653654/* FreeBSD: to make OTP work for now, provide this.. */655AH9300(ah)->ah_cal_mem = ath_hal_malloc(HOST_CALDATA_SIZE);656if (AH9300(ah)->ah_cal_mem == NULL) {657ath_hal_printf(ah, "%s: caldata malloc failed!\n", __func__);658ecode = HAL_EIO;659goto bad;660}661662/*663* If eepromdata is not NULL, copy it it into ah_cal_mem.664*/665if (eepromdata != NULL)666OS_MEMCPY(AH9300(ah)->ah_cal_mem, eepromdata, HOST_CALDATA_SIZE);667668/* XXX FreeBSD: enable RX mitigation */669ah->ah_config.ath_hal_intr_mitigation_rx = 1;670671/* interrupt mitigation */672#ifdef AR5416_INT_MITIGATION673if (ah->ah_config.ath_hal_intr_mitigation_rx != 0) {674ahp->ah_intr_mitigation_rx = AH_TRUE;675}676#else677/* Enable Rx mitigation (default) */678ahp->ah_intr_mitigation_rx = AH_TRUE;679ah->ah_config.ath_hal_intr_mitigation_rx = 1;680681#endif682#ifdef HOST_OFFLOAD683/* Reset default Rx mitigation values for Hornet */684if (AR_SREV_HORNET(ah)) {685ahp->ah_intr_mitigation_rx = AH_FALSE;686#ifdef AR5416_INT_MITIGATION687ah->ah_config.ath_hal_intr_mitigation_rx = 0;688#endif689}690#endif691692if (ah->ah_config.ath_hal_intr_mitigation_tx != 0) {693ahp->ah_intr_mitigation_tx = AH_TRUE;694}695696/*697* Read back AR_WA into a permanent copy and set bits 14 and 17.698* We need to do this to avoid RMW of this register.699* Do this before calling ar9300_set_reset_reg.700* If not, the AR_WA register which was inited via EEPROM701* will get wiped out.702*/703ahp->ah_wa_reg_val = OS_REG_READ(ah, AR_HOSTIF_REG(ah, AR_WA));704/* Set Bits 14 and 17 in the AR_WA register. */705ahp->ah_wa_reg_val |=706AR_WA_D3_TO_L1_DISABLE | AR_WA_ASPM_TIMER_BASED_DISABLE;707708if (!ar9300_set_reset_reg(ah, HAL_RESET_POWER_ON)) { /* reset chip */709HALDEBUG(ah, HAL_DEBUG_RESET, "%s: couldn't reset chip\n", __func__);710ecode = HAL_EIO;711goto bad;712}713714if (AR_SREV_JUPITER(ah)715#if ATH_WOW_OFFLOAD716&& !HAL_WOW_CTRL(ah, HAL_WOW_OFFLOAD_SET_4004_BIT14)717#endif718)719{720/* Jupiter doesn't need bit 14 to be set. */721ahp->ah_wa_reg_val &= ~AR_WA_D3_TO_L1_DISABLE;722OS_REG_WRITE(ah, AR_HOSTIF_REG(ah, AR_WA), ahp->ah_wa_reg_val);723}724725#if ATH_SUPPORT_MCI726if (AR_SREV_JUPITER(ah) || AR_SREV_APHRODITE(ah)) {727#if 1728ah->ah_btCoexSetWeights = ar9300_mci_bt_coex_set_weights;729ah->ah_btCoexDisable = ar9300_mci_bt_coex_disable;730ah->ah_btCoexEnable = ar9300_mci_bt_coex_enable;731#endif732ahp->ah_mci_ready = AH_FALSE;733ahp->ah_mci_bt_state = MCI_BT_SLEEP;734ahp->ah_mci_coex_major_version_wlan = MCI_GPM_COEX_MAJOR_VERSION_WLAN;735ahp->ah_mci_coex_minor_version_wlan = MCI_GPM_COEX_MINOR_VERSION_WLAN;736ahp->ah_mci_coex_major_version_bt = MCI_GPM_COEX_MAJOR_VERSION_DEFAULT;737ahp->ah_mci_coex_minor_version_bt = MCI_GPM_COEX_MINOR_VERSION_DEFAULT;738ahp->ah_mci_coex_bt_version_known = AH_FALSE;739ahp->ah_mci_coex_2g5g_update = AH_TRUE; /* track if 2g5g status sent */740/* will be updated before boot up sequence */741ahp->ah_mci_coex_is_2g = AH_TRUE;742ahp->ah_mci_coex_wlan_channels_update = AH_FALSE;743ahp->ah_mci_coex_wlan_channels[0] = 0x00000000;744ahp->ah_mci_coex_wlan_channels[1] = 0xffffffff;745ahp->ah_mci_coex_wlan_channels[2] = 0xffffffff;746ahp->ah_mci_coex_wlan_channels[3] = 0x7fffffff;747ahp->ah_mci_query_bt = AH_TRUE; /* In case WLAN start after BT */748ahp->ah_mci_unhalt_bt_gpm = AH_TRUE; /* Send UNHALT at beginning */749ahp->ah_mci_halted_bt_gpm = AH_FALSE; /* Allow first HALT */750ahp->ah_mci_need_flush_btinfo = AH_FALSE;751ahp->ah_mci_wlan_cal_seq = 0;752ahp->ah_mci_wlan_cal_done = 0;753}754#endif /* ATH_SUPPORT_MCI */755756#if ATH_WOW_OFFLOAD757ahp->ah_mcast_filter_l32_set = 0;758ahp->ah_mcast_filter_u32_set = 0;759#endif760761if (AR_SREV_HORNET(ah)) {762#ifdef AH_SUPPORT_HORNET763if (!AR_SREV_HORNET_11(ah)) {764/*765* Do not check bootstrap register, which cannot be trusted766* due to s26 switch issue on CUS164/AP121.767*/768ahp->clk_25mhz = 1;769HALDEBUG(AH_NULL, HAL_DEBUG_UNMASKABLE, "Bootstrap clock 25MHz\n");770} else {771/* check bootstrap clock setting */772#define AR_SOC_SEL_25M_40M 0xB80600AC773#define REG_WRITE(_reg, _val) *((volatile u_int32_t *)(_reg)) = (_val);774#define REG_READ(_reg) (*((volatile u_int32_t *)(_reg)))775if (REG_READ(AR_SOC_SEL_25M_40M) & 0x1) {776ahp->clk_25mhz = 0;777HALDEBUG(AH_NULL, HAL_DEBUG_UNMASKABLE,778"Bootstrap clock 40MHz\n");779} else {780ahp->clk_25mhz = 1;781HALDEBUG(AH_NULL, HAL_DEBUG_UNMASKABLE,782"Bootstrap clock 25MHz\n");783}784#undef REG_READ785#undef REG_WRITE786#undef AR_SOC_SEL_25M_40M787}788#endif /* AH_SUPPORT_HORNET */789}790791if (AR_SREV_WASP(ah) || AR_SREV_SCORPION(ah)) {792/* check bootstrap clock setting */793#define AR9340_SOC_SEL_25M_40M 0xB80600B0794#define AR9340_REF_CLK_40 (1 << 4) /* 0 - 25MHz 1 - 40 MHz */795#define REG_READ(_reg) (*((volatile u_int32_t *)(_reg)))796if (REG_READ(AR9340_SOC_SEL_25M_40M) & AR9340_REF_CLK_40) {797ahp->clk_25mhz = 0;798HALDEBUG(AH_NULL, HAL_DEBUG_UNMASKABLE, "Bootstrap clock 40MHz\n");799} else {800ahp->clk_25mhz = 1;801HALDEBUG(AH_NULL, HAL_DEBUG_UNMASKABLE, "Bootstrap clock 25MHz\n");802}803#undef REG_READ804#undef AR9340_SOC_SEL_25M_40M805#undef AR9340_REF_CLK_40806}807808if (AR_SREV_HONEYBEE(ah)) {809ahp->clk_25mhz = 1;810}811812ar9300_init_pll(ah, AH_NULL);813814if (!ar9300_set_power_mode(ah, HAL_PM_AWAKE, AH_TRUE)) {815HALDEBUG(ah, HAL_DEBUG_RESET, "%s: couldn't wakeup chip\n", __func__);816ecode = HAL_EIO;817goto bad;818}819820/* No serialization of Register Accesses needed. */821ah->ah_config.ah_serialise_reg_war = SER_REG_MODE_OFF;822HALDEBUG(ah, HAL_DEBUG_RESET, "%s: ah_serialise_reg_war is %d\n",823__func__, ah->ah_config.ah_serialise_reg_war);824825/*826* Add mac revision check when needed.827* - Osprey 1.0 and 2.0 no longer supported.828*/829if (((ahpriv->ah_macVersion == AR_SREV_VERSION_OSPREY) &&830(ahpriv->ah_macRev <= AR_SREV_REVISION_OSPREY_20)) ||831(ahpriv->ah_macVersion != AR_SREV_VERSION_OSPREY &&832ahpriv->ah_macVersion != AR_SREV_VERSION_WASP &&833ahpriv->ah_macVersion != AR_SREV_VERSION_HORNET &&834ahpriv->ah_macVersion != AR_SREV_VERSION_POSEIDON &&835ahpriv->ah_macVersion != AR_SREV_VERSION_SCORPION &&836ahpriv->ah_macVersion != AR_SREV_VERSION_HONEYBEE &&837ahpriv->ah_macVersion != AR_SREV_VERSION_JUPITER &&838ahpriv->ah_macVersion != AR_SREV_VERSION_APHRODITE) ) {839HALDEBUG(ah, HAL_DEBUG_RESET,840"%s: Mac Chip Rev 0x%02x.%x is not supported by this driver\n",841__func__,842ahpriv->ah_macVersion,843ahpriv->ah_macRev);844ecode = HAL_ENOTSUPP;845goto bad;846}847848AH_PRIVATE(ah)->ah_phyRev = OS_REG_READ(ah, AR_PHY_CHIP_ID);849850/* Setup supported calibrations */851ahp->ah_iq_cal_data.cal_data = &iq_cal_single_sample;852ahp->ah_supp_cals = IQ_MISMATCH_CAL;853854/* Enable ANI */855ahp->ah_ani_function = HAL_ANI_ALL;856857/* Enable RIFS */858ahp->ah_rifs_enabled = AH_TRUE;859860/* by default, stop RX also in abort txdma, due to861"Unable to stop TxDMA" msg observed */862ahp->ah_abort_txdma_norx = AH_TRUE;863864/* do not use optional tx chainmask by default */865ahp->ah_tx_chainmaskopt = 0;866867ahp->ah_skip_rx_iq_cal = AH_FALSE;868ahp->ah_rx_cal_complete = AH_FALSE;869ahp->ah_rx_cal_chan = 0;870ahp->ah_rx_cal_chan_flag = 0;871872HALDEBUG(ah, HAL_DEBUG_RESET,873"%s: This Mac Chip Rev 0x%02x.%x is \n", __func__,874ahpriv->ah_macVersion,875ahpriv->ah_macRev);876877if (AR_SREV_HORNET_12(ah)) {878/* mac */879INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_PRE], NULL, 0, 0);880INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_CORE],881ar9331_hornet1_2_mac_core,882ARRAY_LENGTH(ar9331_hornet1_2_mac_core), 2);883INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_POST],884ar9331_hornet1_2_mac_postamble,885ARRAY_LENGTH(ar9331_hornet1_2_mac_postamble), 5);886887/* bb */888INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_PRE], NULL, 0, 0);889INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_CORE],890ar9331_hornet1_2_baseband_core,891ARRAY_LENGTH(ar9331_hornet1_2_baseband_core), 2);892INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_POST],893ar9331_hornet1_2_baseband_postamble,894ARRAY_LENGTH(ar9331_hornet1_2_baseband_postamble), 5);895896/* radio */897INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_PRE], NULL, 0, 0);898INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_CORE],899ar9331_hornet1_2_radio_core,900ARRAY_LENGTH(ar9331_hornet1_2_radio_core), 2);901INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_POST], NULL, 0, 0);902903/* soc */904INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_PRE],905ar9331_hornet1_2_soc_preamble,906ARRAY_LENGTH(ar9331_hornet1_2_soc_preamble), 2);907INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_CORE], NULL, 0, 0);908INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_POST],909ar9331_hornet1_2_soc_postamble,910ARRAY_LENGTH(ar9331_hornet1_2_soc_postamble), 2);911912/* rx/tx gain */913INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,914ar9331_common_rx_gain_hornet1_2,915ARRAY_LENGTH(ar9331_common_rx_gain_hornet1_2), 2);916INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,917ar9331_modes_lowest_ob_db_tx_gain_hornet1_2,918ARRAY_LENGTH(ar9331_modes_lowest_ob_db_tx_gain_hornet1_2), 5);919920ah->ah_config.ath_hal_pcie_power_save_enable = 0;921922/* Japan 2484Mhz CCK settings */923INIT_INI_ARRAY(&ahp->ah_ini_japan2484,924ar9331_hornet1_2_baseband_core_txfir_coeff_japan_2484,925ARRAY_LENGTH(926ar9331_hornet1_2_baseband_core_txfir_coeff_japan_2484), 2);927928#if 0 /* ATH_WOW */929/* SerDes values during WOW sleep */930INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_wow, ar9300_pcie_phy_awow,931ARRAY_LENGTH(ar9300_pcie_phy_awow), 2);932#endif933934/* additional clock settings */935if (AH9300(ah)->clk_25mhz) {936INIT_INI_ARRAY(&ahp->ah_ini_modes_additional,937ar9331_hornet1_2_xtal_25M,938ARRAY_LENGTH(ar9331_hornet1_2_xtal_25M), 2);939} else {940INIT_INI_ARRAY(&ahp->ah_ini_modes_additional,941ar9331_hornet1_2_xtal_40M,942ARRAY_LENGTH(ar9331_hornet1_2_xtal_40M), 2);943}944945} else if (AR_SREV_HORNET_11(ah)) {946/* mac */947INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_PRE], NULL, 0, 0);948INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_CORE],949ar9331_hornet1_1_mac_core,950ARRAY_LENGTH(ar9331_hornet1_1_mac_core), 2);951INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_POST],952ar9331_hornet1_1_mac_postamble,953ARRAY_LENGTH(ar9331_hornet1_1_mac_postamble), 5);954955/* bb */956INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_PRE], NULL, 0, 0);957INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_CORE],958ar9331_hornet1_1_baseband_core,959ARRAY_LENGTH(ar9331_hornet1_1_baseband_core), 2);960INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_POST],961ar9331_hornet1_1_baseband_postamble,962ARRAY_LENGTH(ar9331_hornet1_1_baseband_postamble), 5);963964/* radio */965INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_PRE], NULL, 0, 0);966INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_CORE],967ar9331_hornet1_1_radio_core,968ARRAY_LENGTH(ar9331_hornet1_1_radio_core), 2);969INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_POST], NULL, 0, 0);970971/* soc */972INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_PRE],973ar9331_hornet1_1_soc_preamble,974ARRAY_LENGTH(ar9331_hornet1_1_soc_preamble), 2);975INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_CORE], NULL, 0, 0);976INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_POST],977ar9331_hornet1_1_soc_postamble,978ARRAY_LENGTH(ar9331_hornet1_1_soc_postamble), 2);979980/* rx/tx gain */981INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,982ar9331_common_rx_gain_hornet1_1,983ARRAY_LENGTH(ar9331_common_rx_gain_hornet1_1), 2);984INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,985ar9331_modes_lowest_ob_db_tx_gain_hornet1_1,986ARRAY_LENGTH(ar9331_modes_lowest_ob_db_tx_gain_hornet1_1), 5);987988ah->ah_config.ath_hal_pcie_power_save_enable = 0;989990/* Japan 2484Mhz CCK settings */991INIT_INI_ARRAY(&ahp->ah_ini_japan2484,992ar9331_hornet1_1_baseband_core_txfir_coeff_japan_2484,993ARRAY_LENGTH(994ar9331_hornet1_1_baseband_core_txfir_coeff_japan_2484), 2);995996#if 0 /* ATH_WOW */997/* SerDes values during WOW sleep */998INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_wow, ar9300_pcie_phy_awow,999N(ar9300_pcie_phy_awow), 2);1000#endif10011002/* additional clock settings */1003if (AH9300(ah)->clk_25mhz) {1004INIT_INI_ARRAY(&ahp->ah_ini_modes_additional,1005ar9331_hornet1_1_xtal_25M,1006ARRAY_LENGTH(ar9331_hornet1_1_xtal_25M), 2);1007} else {1008INIT_INI_ARRAY(&ahp->ah_ini_modes_additional,1009ar9331_hornet1_1_xtal_40M,1010ARRAY_LENGTH(ar9331_hornet1_1_xtal_40M), 2);1011}10121013} else if (AR_SREV_POSEIDON_11_OR_LATER(ah)) {1014/* mac */1015INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_PRE], NULL, 0, 0);1016INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_CORE],1017ar9485_poseidon1_1_mac_core,1018ARRAY_LENGTH( ar9485_poseidon1_1_mac_core), 2);1019INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_POST],1020ar9485_poseidon1_1_mac_postamble,1021ARRAY_LENGTH(ar9485_poseidon1_1_mac_postamble), 5);10221023/* bb */1024INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_PRE],1025ar9485_poseidon1_1, ARRAY_LENGTH(ar9485_poseidon1_1), 2);1026INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_CORE],1027ar9485_poseidon1_1_baseband_core,1028ARRAY_LENGTH(ar9485_poseidon1_1_baseband_core), 2);1029INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_POST],1030ar9485_poseidon1_1_baseband_postamble,1031ARRAY_LENGTH(ar9485_poseidon1_1_baseband_postamble), 5);10321033/* radio */1034INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_PRE], NULL, 0, 0);1035INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_CORE],1036ar9485_poseidon1_1_radio_core,1037ARRAY_LENGTH(ar9485_poseidon1_1_radio_core), 2);1038INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_POST],1039ar9485_poseidon1_1_radio_postamble,1040ARRAY_LENGTH(ar9485_poseidon1_1_radio_postamble), 2);10411042/* soc */1043INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_PRE],1044ar9485_poseidon1_1_soc_preamble,1045ARRAY_LENGTH(ar9485_poseidon1_1_soc_preamble), 2);10461047INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_CORE], NULL, 0, 0);1048INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_POST], NULL, 0, 0);10491050/* rx/tx gain */1051INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,1052ar9485_common_wo_xlna_rx_gain_poseidon1_1,1053ARRAY_LENGTH(ar9485_common_wo_xlna_rx_gain_poseidon1_1), 2);1054INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,1055ar9485_modes_lowest_ob_db_tx_gain_poseidon1_1,1056ARRAY_LENGTH(ar9485_modes_lowest_ob_db_tx_gain_poseidon1_1), 5);10571058/* Japan 2484Mhz CCK settings */1059INIT_INI_ARRAY(&ahp->ah_ini_japan2484,1060ar9485_poseidon1_1_baseband_core_txfir_coeff_japan_2484,1061ARRAY_LENGTH(1062ar9485_poseidon1_1_baseband_core_txfir_coeff_japan_2484), 2);10631064/* Load PCIE SERDES settings from INI */1065if (ah->ah_config.ath_hal_pcie_clock_req) {1066/* Pci-e Clock Request = 1 */1067if (ah->ah_config.ath_hal_pll_pwr_save1068& AR_PCIE_PLL_PWRSAVE_CONTROL)1069{1070/* Sleep Setting */1071if (ah->ah_config.ath_hal_pll_pwr_save &1072AR_PCIE_PLL_PWRSAVE_ON_D3)1073{1074INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1075ar9485_poseidon1_1_pcie_phy_clkreq_enable_L1,1076ARRAY_LENGTH(1077ar9485_poseidon1_1_pcie_phy_clkreq_enable_L1),10782);1079} else {1080INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1081ar9485_poseidon1_1_pcie_phy_pll_on_clkreq_enable_L1,1082ARRAY_LENGTH(1083ar9485_poseidon1_1_pcie_phy_pll_on_clkreq_enable_L1),10842);1085}1086/* Awake Setting */1087if (ah->ah_config.ath_hal_pll_pwr_save &1088AR_PCIE_PLL_PWRSAVE_ON_D0)1089{1090INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1091ar9485_poseidon1_1_pcie_phy_clkreq_enable_L1,1092ARRAY_LENGTH(1093ar9485_poseidon1_1_pcie_phy_clkreq_enable_L1),10942);1095} else {1096INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1097ar9485_poseidon1_1_pcie_phy_pll_on_clkreq_enable_L1,1098ARRAY_LENGTH(1099ar9485_poseidon1_1_pcie_phy_pll_on_clkreq_enable_L1),11002);1101}11021103} else {1104/*Use driver default setting*/1105/* Sleep Setting */1106INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1107ar9485_poseidon1_1_pcie_phy_clkreq_enable_L1,1108ARRAY_LENGTH(ar9485_poseidon1_1_pcie_phy_clkreq_enable_L1),11092);1110/* Awake Setting */1111INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1112ar9485_poseidon1_1_pcie_phy_clkreq_enable_L1,1113ARRAY_LENGTH(ar9485_poseidon1_1_pcie_phy_clkreq_enable_L1),11142);1115}1116} else {1117/* Pci-e Clock Request = 0 */1118if (ah->ah_config.ath_hal_pll_pwr_save1119& AR_PCIE_PLL_PWRSAVE_CONTROL)1120{1121/* Sleep Setting */1122if (ah->ah_config.ath_hal_pll_pwr_save &1123AR_PCIE_PLL_PWRSAVE_ON_D3)1124{1125INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1126ar9485_poseidon1_1_pcie_phy_clkreq_disable_L1,1127ARRAY_LENGTH(1128ar9485_poseidon1_1_pcie_phy_clkreq_disable_L1),11292);1130} else {1131INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1132ar9485_poseidon1_1_pcie_phy_pll_on_clkreq_disable_L1,1133ARRAY_LENGTH(1134ar9485_poseidon1_1_pcie_phy_pll_on_clkreq_disable_L1),11352);1136}1137/* Awake Setting */1138if (ah->ah_config.ath_hal_pll_pwr_save &1139AR_PCIE_PLL_PWRSAVE_ON_D0)1140{1141INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1142ar9485_poseidon1_1_pcie_phy_clkreq_disable_L1,1143ARRAY_LENGTH(1144ar9485_poseidon1_1_pcie_phy_clkreq_disable_L1),11452);1146} else {1147INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1148ar9485_poseidon1_1_pcie_phy_pll_on_clkreq_disable_L1,1149ARRAY_LENGTH(1150ar9485_poseidon1_1_pcie_phy_pll_on_clkreq_disable_L1),11512);1152}11531154} else {1155/*Use driver default setting*/1156/* Sleep Setting */1157INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1158ar9485_poseidon1_1_pcie_phy_clkreq_disable_L1,1159ARRAY_LENGTH(ar9485_poseidon1_1_pcie_phy_clkreq_disable_L1),11602);1161/* Awake Setting */1162INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1163ar9485_poseidon1_1_pcie_phy_clkreq_disable_L1,1164ARRAY_LENGTH(ar9485_poseidon1_1_pcie_phy_clkreq_disable_L1),11652);1166}1167}1168/* pcie ps setting will honor registry setting, default is 0 */1169//ah->ah_config.ath_hal_pciePowerSaveEnable = 0;1170} else if (AR_SREV_POSEIDON(ah)) {1171/* mac */1172INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_PRE], NULL, 0, 0);1173INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_CORE],1174ar9485_poseidon1_0_mac_core,1175ARRAY_LENGTH(ar9485_poseidon1_0_mac_core), 2);1176INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_POST],1177ar9485_poseidon1_0_mac_postamble,1178ARRAY_LENGTH(ar9485_poseidon1_0_mac_postamble), 5);11791180/* bb */1181INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_PRE],1182ar9485_poseidon1_0,1183ARRAY_LENGTH(ar9485_poseidon1_0), 2);1184INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_CORE],1185ar9485_poseidon1_0_baseband_core,1186ARRAY_LENGTH(ar9485_poseidon1_0_baseband_core), 2);1187INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_POST],1188ar9485_poseidon1_0_baseband_postamble,1189ARRAY_LENGTH(ar9485_poseidon1_0_baseband_postamble), 5);11901191/* radio */1192INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_PRE], NULL, 0, 0);1193INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_CORE],1194ar9485_poseidon1_0_radio_core,1195ARRAY_LENGTH(ar9485_poseidon1_0_radio_core), 2);1196INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_POST],1197ar9485_poseidon1_0_radio_postamble,1198ARRAY_LENGTH(ar9485_poseidon1_0_radio_postamble), 2);11991200/* soc */1201INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_PRE],1202ar9485_poseidon1_0_soc_preamble,1203ARRAY_LENGTH(ar9485_poseidon1_0_soc_preamble), 2);1204INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_CORE], NULL, 0, 0);1205INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_POST], NULL, 0, 0);12061207/* rx/tx gain */1208INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,1209ar9485Common_wo_xlna_rx_gain_poseidon1_0,1210ARRAY_LENGTH(ar9485Common_wo_xlna_rx_gain_poseidon1_0), 2);1211INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,1212ar9485Modes_lowest_ob_db_tx_gain_poseidon1_0,1213ARRAY_LENGTH(ar9485Modes_lowest_ob_db_tx_gain_poseidon1_0), 5);12141215/* Japan 2484Mhz CCK settings */1216INIT_INI_ARRAY(&ahp->ah_ini_japan2484,1217ar9485_poseidon1_0_baseband_core_txfir_coeff_japan_2484,1218ARRAY_LENGTH(1219ar9485_poseidon1_0_baseband_core_txfir_coeff_japan_2484), 2);12201221/* Load PCIE SERDES settings from INI */1222if (ah->ah_config.ath_hal_pcie_clock_req) {1223/* Pci-e Clock Request = 1 */1224if (ah->ah_config.ath_hal_pll_pwr_save1225& AR_PCIE_PLL_PWRSAVE_CONTROL)1226{1227/* Sleep Setting */1228if (ah->ah_config.ath_hal_pll_pwr_save &1229AR_PCIE_PLL_PWRSAVE_ON_D3)1230{1231INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1232ar9485_poseidon1_0_pcie_phy_clkreq_enable_L1,1233ARRAY_LENGTH(1234ar9485_poseidon1_0_pcie_phy_clkreq_enable_L1),12352);1236} else {1237INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1238ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_enable_L1,1239ARRAY_LENGTH(1240ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_enable_L1),12412);1242}1243/* Awake Setting */1244if (ah->ah_config.ath_hal_pll_pwr_save &1245AR_PCIE_PLL_PWRSAVE_ON_D0)1246{1247INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1248ar9485_poseidon1_0_pcie_phy_clkreq_enable_L1,1249ARRAY_LENGTH(1250ar9485_poseidon1_0_pcie_phy_clkreq_enable_L1),12512);1252} else {1253INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1254ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_enable_L1,1255ARRAY_LENGTH(1256ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_enable_L1),12572);1258}12591260} else {1261/*Use driver default setting*/1262/* Sleep Setting */1263INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1264ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_enable_L1,1265ARRAY_LENGTH(1266ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_enable_L1),12672);1268/* Awake Setting */1269INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1270ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_enable_L1,1271ARRAY_LENGTH(1272ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_enable_L1),12732);1274}1275} else {1276/* Pci-e Clock Request = 0 */1277if (ah->ah_config.ath_hal_pll_pwr_save1278& AR_PCIE_PLL_PWRSAVE_CONTROL)1279{1280/* Sleep Setting */1281if (ah->ah_config.ath_hal_pll_pwr_save &1282AR_PCIE_PLL_PWRSAVE_ON_D3)1283{1284INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1285ar9485_poseidon1_0_pcie_phy_clkreq_disable_L1,1286ARRAY_LENGTH(1287ar9485_poseidon1_0_pcie_phy_clkreq_disable_L1),12882);1289} else {1290INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1291ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_disable_L1,1292ARRAY_LENGTH(1293ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_disable_L1),12942);1295}1296/* Awake Setting */1297if (ah->ah_config.ath_hal_pll_pwr_save &1298AR_PCIE_PLL_PWRSAVE_ON_D0)1299{1300INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1301ar9485_poseidon1_0_pcie_phy_clkreq_disable_L1,1302ARRAY_LENGTH(1303ar9485_poseidon1_0_pcie_phy_clkreq_disable_L1),13042);1305} else {1306INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1307ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_disable_L1,1308ARRAY_LENGTH(1309ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_disable_L1),13102);1311}13121313} else {1314/*Use driver default setting*/1315/* Sleep Setting */1316INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1317ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_disable_L1,1318ARRAY_LENGTH(1319ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_disable_L1),13202);1321/* Awake Setting */1322INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1323ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_disable_L1,1324ARRAY_LENGTH(1325ar9485_poseidon1_0_pcie_phy_pll_on_clkreq_disable_L1),13262);1327}1328}1329/* pcie ps setting will honor registry setting, default is 0 */1330/*ah->ah_config.ath_hal_pcie_power_save_enable = 0;*/13311332#if 0 /* ATH_WOW */1333/* SerDes values during WOW sleep */1334INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_wow, ar9300_pcie_phy_awow,1335ARRAY_LENGTH(ar9300_pcie_phy_awow), 2);1336#endif13371338} else if (AR_SREV_WASP(ah)) {1339/* mac */1340INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_PRE], NULL, 0, 0);1341INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_CORE],1342ar9340_wasp_1p0_mac_core,1343ARRAY_LENGTH(ar9340_wasp_1p0_mac_core), 2);1344INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_POST],1345ar9340_wasp_1p0_mac_postamble,1346ARRAY_LENGTH(ar9340_wasp_1p0_mac_postamble), 5);13471348/* bb */1349INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_PRE], NULL, 0, 0);1350INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_CORE],1351ar9340_wasp_1p0_baseband_core,1352ARRAY_LENGTH(ar9340_wasp_1p0_baseband_core), 2);1353INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_POST],1354ar9340_wasp_1p0_baseband_postamble,1355ARRAY_LENGTH(ar9340_wasp_1p0_baseband_postamble), 5);13561357/* radio */1358INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_PRE], NULL, 0, 0);1359INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_CORE],1360ar9340_wasp_1p0_radio_core,1361ARRAY_LENGTH(ar9340_wasp_1p0_radio_core), 2);1362INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_POST],1363ar9340_wasp_1p0_radio_postamble,1364ARRAY_LENGTH(ar9340_wasp_1p0_radio_postamble), 5);13651366/* soc */1367INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_PRE],1368ar9340_wasp_1p0_soc_preamble,1369ARRAY_LENGTH(ar9340_wasp_1p0_soc_preamble), 2);1370INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_CORE], NULL, 0, 0);1371INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_POST],1372ar9340_wasp_1p0_soc_postamble,1373ARRAY_LENGTH(ar9340_wasp_1p0_soc_postamble), 5);13741375/* rx/tx gain */1376INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,1377ar9340Common_wo_xlna_rx_gain_table_wasp_1p0,1378ARRAY_LENGTH(ar9340Common_wo_xlna_rx_gain_table_wasp_1p0), 2);1379INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,1380ar9340Modes_high_ob_db_tx_gain_table_wasp_1p0,1381ARRAY_LENGTH(ar9340Modes_high_ob_db_tx_gain_table_wasp_1p0), 5);13821383ah->ah_config.ath_hal_pcie_power_save_enable = 0;13841385/* Fast clock modal settings */1386INIT_INI_ARRAY(&ahp->ah_ini_modes_additional,1387ar9340Modes_fast_clock_wasp_1p0,1388ARRAY_LENGTH(ar9340Modes_fast_clock_wasp_1p0), 3);13891390/* XXX TODO: need to add this for freebsd; it's missing from the current .ini files */1391#if 01392/* Japan 2484Mhz CCK settings */1393INIT_INI_ARRAY(&ahp->ah_ini_japan2484,1394ar9340_wasp_1p0_baseband_core_txfir_coeff_japan_2484,1395ARRAY_LENGTH(1396ar9340_wasp_1p0_baseband_core_txfir_coeff_japan_2484), 2);1397#endif13981399/* Additional setttings for 40Mhz */1400INIT_INI_ARRAY(&ahp->ah_ini_modes_additional_40mhz,1401ar9340_wasp_1p0_radio_core_40M,1402ARRAY_LENGTH(ar9340_wasp_1p0_radio_core_40M), 2);14031404/* DFS */1405INIT_INI_ARRAY(&ahp->ah_ini_dfs,1406ar9340_wasp_1p0_baseband_postamble_dfs_channel,1407ARRAY_LENGTH(ar9340_wasp_1p0_baseband_postamble_dfs_channel), 3);1408} else if (AR_SREV_SCORPION(ah)) {1409/* mac */1410INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_PRE], NULL, 0, 0);1411INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_CORE],1412ar955x_scorpion_1p0_mac_core,1413ARRAY_LENGTH(ar955x_scorpion_1p0_mac_core), 2);1414INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_POST],1415ar955x_scorpion_1p0_mac_postamble,1416ARRAY_LENGTH(ar955x_scorpion_1p0_mac_postamble), 5);14171418/* bb */1419INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_PRE], NULL, 0, 0);1420INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_CORE],1421ar955x_scorpion_1p0_baseband_core,1422ARRAY_LENGTH(ar955x_scorpion_1p0_baseband_core), 2);1423INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_POST],1424ar955x_scorpion_1p0_baseband_postamble,1425ARRAY_LENGTH(ar955x_scorpion_1p0_baseband_postamble), 5);14261427/* radio */1428INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_PRE], NULL, 0, 0);1429INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_CORE],1430ar955x_scorpion_1p0_radio_core,1431ARRAY_LENGTH(ar955x_scorpion_1p0_radio_core), 2);1432INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_POST],1433ar955x_scorpion_1p0_radio_postamble,1434ARRAY_LENGTH(ar955x_scorpion_1p0_radio_postamble), 5);14351436/* soc */1437INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_PRE],1438ar955x_scorpion_1p0_soc_preamble,1439ARRAY_LENGTH(ar955x_scorpion_1p0_soc_preamble), 2);1440INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_CORE], NULL, 0, 0);1441INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_POST],1442ar955x_scorpion_1p0_soc_postamble,1443ARRAY_LENGTH(ar955x_scorpion_1p0_soc_postamble), 5);14441445/* rx/tx gain */1446INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,1447ar955xCommon_wo_xlna_rx_gain_table_scorpion_1p0,1448ARRAY_LENGTH(ar955xCommon_wo_xlna_rx_gain_table_scorpion_1p0), 2);1449INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain_bounds,1450ar955xCommon_wo_xlna_rx_gain_bounds_scorpion_1p0,1451ARRAY_LENGTH(ar955xCommon_wo_xlna_rx_gain_bounds_scorpion_1p0), 5);1452INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,1453ar955xModes_no_xpa_tx_gain_table_scorpion_1p0,1454ARRAY_LENGTH(ar955xModes_no_xpa_tx_gain_table_scorpion_1p0), 5);14551456/*ath_hal_pciePowerSaveEnable should be 2 for OWL/Condor and 0 for merlin */1457ah->ah_config.ath_hal_pcie_power_save_enable = 0;14581459/* Fast clock modal settings */1460INIT_INI_ARRAY(&ahp->ah_ini_modes_additional,1461ar955xModes_fast_clock_scorpion_1p0,1462ARRAY_LENGTH(ar955xModes_fast_clock_scorpion_1p0), 3);14631464/* Additional setttings for 40Mhz */1465//INIT_INI_ARRAY(&ahp->ah_ini_modes_additional_40M,1466// ar955x_scorpion_1p0_radio_core_40M,1467// ARRAY_LENGTH(ar955x_scorpion_1p0_radio_core_40M), 2);1468} else if (AR_SREV_HONEYBEE(ah)) {1469/* mac */1470INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_PRE], NULL, 0, 0);1471INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_CORE],1472qca953x_honeybee_1p0_mac_core,1473ARRAY_LENGTH(qca953x_honeybee_1p0_mac_core), 2);1474INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_POST],1475qca953x_honeybee_1p0_mac_postamble,1476ARRAY_LENGTH(qca953x_honeybee_1p0_mac_postamble), 5);14771478/* bb */1479INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_PRE], NULL, 0, 0);1480INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_CORE],1481qca953x_honeybee_1p0_baseband_core,1482ARRAY_LENGTH(qca953x_honeybee_1p0_baseband_core), 2);1483INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_POST],1484qca953x_honeybee_1p0_baseband_postamble,1485ARRAY_LENGTH(qca953x_honeybee_1p0_baseband_postamble), 5);14861487/* radio */1488INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_PRE], NULL, 0, 0);1489INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_CORE],1490qca953x_honeybee_1p0_radio_core,1491ARRAY_LENGTH(qca953x_honeybee_1p0_radio_core), 2);1492INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_POST],1493qca953x_honeybee_1p0_radio_postamble,1494ARRAY_LENGTH(qca953x_honeybee_1p0_radio_postamble), 5);14951496/* soc */1497INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_PRE],1498qca953x_honeybee_1p0_soc_preamble,1499ARRAY_LENGTH(qca953x_honeybee_1p0_soc_preamble), 2);1500INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_CORE], NULL, 0, 0);1501INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_POST],1502qca953x_honeybee_1p0_soc_postamble,1503ARRAY_LENGTH(qca953x_honeybee_1p0_soc_postamble), 5);15041505/* rx/tx gain */1506INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,1507qca953xCommon_wo_xlna_rx_gain_table_honeybee_1p0,1508ARRAY_LENGTH(qca953xCommon_wo_xlna_rx_gain_table_honeybee_1p0), 2);1509INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain_bounds,1510qca953xCommon_wo_xlna_rx_gain_bounds_honeybee_1p0,1511ARRAY_LENGTH(qca953xCommon_wo_xlna_rx_gain_bounds_honeybee_1p0), 5);1512INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,1513qca953xModes_no_xpa_tx_gain_table_honeybee_1p0,1514ARRAY_LENGTH(qca953xModes_no_xpa_tx_gain_table_honeybee_1p0), 2);15151516/*ath_hal_pciePowerSaveEnable should be 2 for OWL/Condor and 0 for merlin */1517ah->ah_config.ath_hal_pcie_power_save_enable = 0;15181519/* Fast clock modal settings */1520INIT_INI_ARRAY(&ahp->ah_ini_modes_additional,1521qca953xModes_fast_clock_honeybee_1p0,1522ARRAY_LENGTH(qca953xModes_fast_clock_honeybee_1p0), 3);15231524/* Additional setttings for 40Mhz */1525//INIT_INI_ARRAY(&ahp->ah_ini_modes_additional_40M,1526// qca953x_honeybee_1p0_radio_core_40M,1527// ARRAY_LENGTH(qca953x_honeybee_1p0_radio_core_40M), 2);15281529} else if (AR_SREV_JUPITER_10(ah)) {1530/* Jupiter: new INI format (pre, core, post arrays per subsystem) */15311532/* mac */1533INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_PRE], NULL, 0, 0);1534INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_CORE],1535ar9300_jupiter_1p0_mac_core,1536ARRAY_LENGTH(ar9300_jupiter_1p0_mac_core), 2);1537INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_POST],1538ar9300_jupiter_1p0_mac_postamble,1539ARRAY_LENGTH(ar9300_jupiter_1p0_mac_postamble), 5);15401541/* bb */1542INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_PRE], NULL, 0, 0);1543INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_CORE],1544ar9300_jupiter_1p0_baseband_core,1545ARRAY_LENGTH(ar9300_jupiter_1p0_baseband_core), 2);1546INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_POST],1547ar9300_jupiter_1p0_baseband_postamble,1548ARRAY_LENGTH(ar9300_jupiter_1p0_baseband_postamble), 5);15491550/* radio */1551INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_PRE], NULL, 0, 0);1552INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_CORE],1553ar9300_jupiter_1p0_radio_core,1554ARRAY_LENGTH(ar9300_jupiter_1p0_radio_core), 2);1555INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_POST],1556ar9300_jupiter_1p0_radio_postamble,1557ARRAY_LENGTH(ar9300_jupiter_1p0_radio_postamble), 5);15581559/* soc */1560INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_PRE],1561ar9300_jupiter_1p0_soc_preamble,1562ARRAY_LENGTH(ar9300_jupiter_1p0_soc_preamble), 2);1563INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_CORE], NULL, 0, 0);1564INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_POST],1565ar9300_jupiter_1p0_soc_postamble,1566ARRAY_LENGTH(ar9300_jupiter_1p0_soc_postamble), 5);15671568/* rx/tx gain */1569INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,1570ar9300_common_rx_gain_table_jupiter_1p0,1571ARRAY_LENGTH(ar9300_common_rx_gain_table_jupiter_1p0), 2);15721573/* Load PCIE SERDES settings from INI */1574if (ah->ah_config.ath_hal_pcie_clock_req) {1575/* Pci-e Clock Request = 1 */1576/*1577* PLL ON + clkreq enable is not a valid combination,1578* thus to ignore ath_hal_pll_pwr_save, use PLL OFF.1579*/1580{1581/*Use driver default setting*/1582/* Awake -> Sleep Setting */1583INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1584ar9300_pcie_phy_clkreq_enable_L1_jupiter_1p0,1585ARRAY_LENGTH(ar9300_pcie_phy_clkreq_enable_L1_jupiter_1p0),15862);1587/* Sleep -> Awake Setting */1588INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1589ar9300_pcie_phy_clkreq_enable_L1_jupiter_1p0,1590ARRAY_LENGTH(ar9300_pcie_phy_clkreq_enable_L1_jupiter_1p0),15912);1592}1593}1594else {1595/*1596* Since Jupiter 1.0 and 2.0 share the same device id and will be1597* installed with same INF, but Jupiter 1.0 has issue with PLL OFF.1598*1599* Force Jupiter 1.0 to use ON/ON setting.1600*/1601ah->ah_config.ath_hal_pll_pwr_save = 0;1602/* Pci-e Clock Request = 0 */1603if (ah->ah_config.ath_hal_pll_pwr_save &1604AR_PCIE_PLL_PWRSAVE_CONTROL)1605{1606/* Awake -> Sleep Setting */1607if (ah->ah_config.ath_hal_pll_pwr_save &1608AR_PCIE_PLL_PWRSAVE_ON_D3)1609{1610INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1611ar9300_pcie_phy_clkreq_disable_L1_jupiter_1p0,1612ARRAY_LENGTH(1613ar9300_pcie_phy_clkreq_disable_L1_jupiter_1p0),16142);1615}1616else {1617INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1618ar9300_pcie_phy_pll_on_clkreq_disable_L1_jupiter_1p0,1619ARRAY_LENGTH(1620ar9300_pcie_phy_pll_on_clkreq_disable_L1_jupiter_1p0),16212);1622}1623/* Sleep -> Awake Setting */1624if (ah->ah_config.ath_hal_pll_pwr_save &1625AR_PCIE_PLL_PWRSAVE_ON_D0)1626{1627INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1628ar9300_pcie_phy_clkreq_disable_L1_jupiter_1p0,1629ARRAY_LENGTH(1630ar9300_pcie_phy_clkreq_disable_L1_jupiter_1p0),16312);1632}1633else {1634INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1635ar9300_pcie_phy_pll_on_clkreq_disable_L1_jupiter_1p0,1636ARRAY_LENGTH(1637ar9300_pcie_phy_pll_on_clkreq_disable_L1_jupiter_1p0),16382);1639}16401641}1642else {1643/*Use driver default setting*/1644/* Awake -> Sleep Setting */1645INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1646ar9300_pcie_phy_pll_on_clkreq_disable_L1_jupiter_1p0,1647ARRAY_LENGTH(1648ar9300_pcie_phy_pll_on_clkreq_disable_L1_jupiter_1p0),16492);1650/* Sleep -> Awake Setting */1651INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1652ar9300_pcie_phy_pll_on_clkreq_disable_L1_jupiter_1p0,1653ARRAY_LENGTH(1654ar9300_pcie_phy_pll_on_clkreq_disable_L1_jupiter_1p0),16552);1656}1657}1658/*1659* ath_hal_pcie_power_save_enable should be 2 for OWL/Condor and1660* 0 for merlin1661*/1662ah->ah_config.ath_hal_pcie_power_save_enable = 0;16631664#if 0 // ATH_WOW1665/* SerDes values during WOW sleep */1666INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_wow, ar9300_pcie_phy_AWOW,1667ARRAY_LENGTH(ar9300_pcie_phy_AWOW), 2);1668#endif16691670/* Fast clock modal settings */1671INIT_INI_ARRAY(&ahp->ah_ini_modes_additional,1672ar9300_modes_fast_clock_jupiter_1p0,1673ARRAY_LENGTH(ar9300_modes_fast_clock_jupiter_1p0), 3);1674INIT_INI_ARRAY(&ahp->ah_ini_japan2484,1675ar9300_jupiter_1p0_baseband_core_txfir_coeff_japan_2484,1676ARRAY_LENGTH(1677ar9300_jupiter_1p0_baseband_core_txfir_coeff_japan_2484), 2);16781679}1680else if (AR_SREV_JUPITER_20_OR_LATER(ah)) {1681/* Jupiter: new INI format (pre, core, post arrays per subsystem) */16821683/* FreeBSD: just override the registers for jupiter 2.1 */1684/* XXX TODO: refactor this stuff out; reinit all the 2.1 registers */16851686/* mac */1687INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_PRE], NULL, 0, 0);16881689if (AR_SREV_JUPITER_21(ah)) {1690INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_CORE],1691ar9462_2p1_mac_core,1692ARRAY_LENGTH(ar9462_2p1_mac_core), 2);1693} else {1694INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_CORE],1695ar9300_jupiter_2p0_mac_core,1696ARRAY_LENGTH(ar9300_jupiter_2p0_mac_core), 2);1697}16981699INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_POST],1700ar9300_jupiter_2p0_mac_postamble,1701ARRAY_LENGTH(ar9300_jupiter_2p0_mac_postamble), 5);17021703/* bb */1704INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_PRE], NULL, 0, 0);1705INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_CORE],1706ar9300_jupiter_2p0_baseband_core,1707ARRAY_LENGTH(ar9300_jupiter_2p0_baseband_core), 2);17081709if (AR_SREV_JUPITER_21(ah)) {1710INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_POST],1711ar9462_2p1_baseband_postamble,1712ARRAY_LENGTH(ar9462_2p1_baseband_postamble), 5);1713} else {1714INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_POST],1715ar9300_jupiter_2p0_baseband_postamble,1716ARRAY_LENGTH(ar9300_jupiter_2p0_baseband_postamble), 5);1717}17181719/* radio */1720INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_PRE], NULL, 0, 0);1721INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_CORE],1722ar9300_jupiter_2p0_radio_core,1723ARRAY_LENGTH(ar9300_jupiter_2p0_radio_core), 2);1724INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_POST],1725ar9300_jupiter_2p0_radio_postamble,1726ARRAY_LENGTH(ar9300_jupiter_2p0_radio_postamble), 5);1727INIT_INI_ARRAY(&ahp->ah_ini_radio_post_sys2ant,1728ar9300_jupiter_2p0_radio_postamble_sys2ant,1729ARRAY_LENGTH(ar9300_jupiter_2p0_radio_postamble_sys2ant), 5);17301731/* soc */1732if (AR_SREV_JUPITER_21(ah)) {1733INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_PRE],1734ar9462_2p1_soc_preamble,1735ARRAY_LENGTH(ar9462_2p1_soc_preamble), 2);1736} else {1737INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_PRE],1738ar9300_jupiter_2p0_soc_preamble,1739ARRAY_LENGTH(ar9300_jupiter_2p0_soc_preamble), 2);1740}1741INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_CORE], NULL, 0, 0);1742INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_POST],1743ar9300_jupiter_2p0_soc_postamble,1744ARRAY_LENGTH(ar9300_jupiter_2p0_soc_postamble), 5);17451746/* rx/tx gain */1747INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,1748ar9300Common_rx_gain_table_jupiter_2p0,1749ARRAY_LENGTH(ar9300Common_rx_gain_table_jupiter_2p0), 2);17501751/* BTCOEX */1752INIT_INI_ARRAY(&ahp->ah_ini_BTCOEX_MAX_TXPWR,1753ar9300_jupiter_2p0_BTCOEX_MAX_TXPWR_table,1754ARRAY_LENGTH(ar9300_jupiter_2p0_BTCOEX_MAX_TXPWR_table), 2);17551756/* Load PCIE SERDES settings from INI */1757if (ah->ah_config.ath_hal_pcie_clock_req) {1758/* Pci-e Clock Request = 1 */1759/*1760* PLL ON + clkreq enable is not a valid combination,1761* thus to ignore ath_hal_pll_pwr_save, use PLL OFF.1762*/1763{1764/*Use driver default setting*/1765/* Awake -> Sleep Setting */1766INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1767ar9300_PciePhy_clkreq_enable_L1_jupiter_2p0,1768ARRAY_LENGTH(ar9300_PciePhy_clkreq_enable_L1_jupiter_2p0),17692);1770/* Sleep -> Awake Setting */1771INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1772ar9300_PciePhy_clkreq_enable_L1_jupiter_2p0,1773ARRAY_LENGTH(ar9300_PciePhy_clkreq_enable_L1_jupiter_2p0),17742);1775}1776}1777else {1778/* Pci-e Clock Request = 0 */1779if (ah->ah_config.ath_hal_pll_pwr_save &1780AR_PCIE_PLL_PWRSAVE_CONTROL)1781{1782/* Awake -> Sleep Setting */1783if (ah->ah_config.ath_hal_pll_pwr_save &1784AR_PCIE_PLL_PWRSAVE_ON_D3)1785{1786INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1787ar9300_PciePhy_clkreq_disable_L1_jupiter_2p0,1788ARRAY_LENGTH(1789ar9300_PciePhy_clkreq_disable_L1_jupiter_2p0),17902);1791}1792else {1793INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1794ar9300_PciePhy_pll_on_clkreq_disable_L1_jupiter_2p0,1795ARRAY_LENGTH(1796ar9300_PciePhy_pll_on_clkreq_disable_L1_jupiter_2p0),17972);1798}1799/* Sleep -> Awake Setting */1800if (ah->ah_config.ath_hal_pll_pwr_save &1801AR_PCIE_PLL_PWRSAVE_ON_D0)1802{1803INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1804ar9300_PciePhy_clkreq_disable_L1_jupiter_2p0,1805ARRAY_LENGTH(1806ar9300_PciePhy_clkreq_disable_L1_jupiter_2p0),18072);1808}1809else {1810INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1811ar9300_PciePhy_pll_on_clkreq_disable_L1_jupiter_2p0,1812ARRAY_LENGTH(1813ar9300_PciePhy_pll_on_clkreq_disable_L1_jupiter_2p0),18142);1815}18161817}1818else {1819/*Use driver default setting*/1820/* Awake -> Sleep Setting */1821INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1822ar9300_PciePhy_pll_on_clkreq_disable_L1_jupiter_2p0,1823ARRAY_LENGTH(1824ar9300_PciePhy_pll_on_clkreq_disable_L1_jupiter_2p0),18252);1826/* Sleep -> Awake Setting */1827INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,1828ar9300_PciePhy_pll_on_clkreq_disable_L1_jupiter_2p0,1829ARRAY_LENGTH(1830ar9300_PciePhy_pll_on_clkreq_disable_L1_jupiter_2p0),18312);1832}1833}18341835/*1836* ath_hal_pcie_power_save_enable should be 2 for OWL/Condor and1837* 0 for merlin1838*/1839ah->ah_config.ath_hal_pcie_power_save_enable = 0;18401841#if 0 // ATH_WOW1842/* SerDes values during WOW sleep */1843INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_wow, ar9300_pcie_phy_AWOW,1844ARRAY_LENGTH(ar9300_pcie_phy_AWOW), 2);1845#endif18461847/* Fast clock modal settings */1848INIT_INI_ARRAY(&ahp->ah_ini_modes_additional,1849ar9300Modes_fast_clock_jupiter_2p0,1850ARRAY_LENGTH(ar9300Modes_fast_clock_jupiter_2p0), 3);1851INIT_INI_ARRAY(&ahp->ah_ini_japan2484,1852ar9300_jupiter_2p0_baseband_core_txfir_coeff_japan_2484,1853ARRAY_LENGTH(1854ar9300_jupiter_2p0_baseband_core_txfir_coeff_japan_2484), 2);18551856} else if (AR_SREV_APHRODITE(ah)) {1857/* Aphrodite: new INI format (pre, core, post arrays per subsystem) */18581859/* mac */1860INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_PRE], NULL, 0, 0);1861INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_CORE],1862ar956X_aphrodite_1p0_mac_core,1863ARRAY_LENGTH(ar956X_aphrodite_1p0_mac_core), 2);1864INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_POST],1865ar956X_aphrodite_1p0_mac_postamble,1866ARRAY_LENGTH(ar956X_aphrodite_1p0_mac_postamble), 5);18671868/* bb */1869INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_PRE], NULL, 0, 0);1870INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_CORE],1871ar956X_aphrodite_1p0_baseband_core,1872ARRAY_LENGTH(ar956X_aphrodite_1p0_baseband_core), 2);1873INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_POST],1874ar956X_aphrodite_1p0_baseband_postamble,1875ARRAY_LENGTH(ar956X_aphrodite_1p0_baseband_postamble), 5);18761877//mark jupiter have but aphrodite don't have1878// /* radio */1879// INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_PRE], NULL, 0, 0);1880// INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_CORE],1881// ar9300_aphrodite_1p0_radio_core,1882// ARRAY_LENGTH(ar9300_aphrodite_1p0_radio_core), 2);1883// INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_POST],1884// ar9300_aphrodite_1p0_radio_postamble,1885// ARRAY_LENGTH(ar9300_aphrodite_1p0_radio_postamble), 5);18861887/* soc */1888INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_PRE],1889ar956X_aphrodite_1p0_soc_preamble,1890ARRAY_LENGTH(ar956X_aphrodite_1p0_soc_preamble), 2);1891INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_CORE], NULL, 0, 0);1892INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_POST],1893ar956X_aphrodite_1p0_soc_postamble,1894ARRAY_LENGTH(ar956X_aphrodite_1p0_soc_postamble), 5);18951896/* rx/tx gain */1897INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,1898ar956XCommon_rx_gain_table_aphrodite_1p0,1899ARRAY_LENGTH(ar956XCommon_rx_gain_table_aphrodite_1p0), 2);1900//INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,1901// ar956XModes_lowest_ob_db_tx_gain_table_aphrodite_1p0,1902// ARRAY_LENGTH(ar956XModes_lowest_ob_db_tx_gain_table_aphrodite_1p0),1903// 5);190419051906/*1907* ath_hal_pcie_power_save_enable should be 2 for OWL/Condor and1908* 0 for merlin1909*/1910ah->ah_config.ath_hal_pcie_power_save_enable = 0;19111912#if 0 // ATH_WOW1913/* SerDes values during WOW sleep */1914INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_wow, ar9300_pcie_phy_AWOW,1915ARRAY_LENGTH(ar9300_pcie_phy_AWOW), 2);1916#endif1917/* Fast clock modal settings */1918INIT_INI_ARRAY(&ahp->ah_ini_modes_additional,1919ar956XModes_fast_clock_aphrodite_1p0,1920ARRAY_LENGTH(ar956XModes_fast_clock_aphrodite_1p0), 3);19211922} else if (AR_SREV_AR9580(ah)) {1923/*1924* AR9580/Peacock -1925* new INI format (pre, core, post arrays per subsystem)1926*/19271928/* mac */1929INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_PRE], NULL, 0, 0);1930INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_CORE],1931ar9300_ar9580_1p0_mac_core,1932ARRAY_LENGTH(ar9300_ar9580_1p0_mac_core), 2);1933INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_POST],1934ar9300_ar9580_1p0_mac_postamble,1935ARRAY_LENGTH(ar9300_ar9580_1p0_mac_postamble), 5);19361937/* bb */1938INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_PRE], NULL, 0, 0);1939INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_CORE],1940ar9300_ar9580_1p0_baseband_core,1941ARRAY_LENGTH(ar9300_ar9580_1p0_baseband_core), 2);1942INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_POST],1943ar9300_ar9580_1p0_baseband_postamble,1944ARRAY_LENGTH(ar9300_ar9580_1p0_baseband_postamble), 5);19451946/* radio */1947INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_PRE], NULL, 0, 0);1948INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_CORE],1949ar9300_ar9580_1p0_radio_core,1950ARRAY_LENGTH(ar9300_ar9580_1p0_radio_core), 2);1951INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_POST],1952ar9300_ar9580_1p0_radio_postamble,1953ARRAY_LENGTH(ar9300_ar9580_1p0_radio_postamble), 5);19541955/* soc */1956INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_PRE],1957ar9300_ar9580_1p0_soc_preamble,1958ARRAY_LENGTH(ar9300_ar9580_1p0_soc_preamble), 2);1959INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_CORE], NULL, 0, 0);1960INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_POST],1961ar9300_ar9580_1p0_soc_postamble,1962ARRAY_LENGTH(ar9300_ar9580_1p0_soc_postamble), 5);19631964/* rx/tx gain */1965INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,1966ar9300_common_rx_gain_table_ar9580_1p0,1967ARRAY_LENGTH(ar9300_common_rx_gain_table_ar9580_1p0), 2);1968INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,1969ar9300Modes_lowest_ob_db_tx_gain_table_ar9580_1p0,1970ARRAY_LENGTH(ar9300Modes_lowest_ob_db_tx_gain_table_ar9580_1p0), 5);19711972/* DFS */1973INIT_INI_ARRAY(&ahp->ah_ini_dfs,1974ar9300_ar9580_1p0_baseband_postamble_dfs_channel,1975ARRAY_LENGTH(ar9300_ar9580_1p0_baseband_postamble_dfs_channel), 3);197619771978/* Load PCIE SERDES settings from INI */19791980/*D3 Setting */1981if (ah->ah_config.ath_hal_pcie_clock_req) {1982if (ah->ah_config.ath_hal_pll_pwr_save &1983AR_PCIE_PLL_PWRSAVE_CONTROL)1984{ //registry control1985if (ah->ah_config.ath_hal_pll_pwr_save &1986AR_PCIE_PLL_PWRSAVE_ON_D3)1987{ //bit1, in to D31988INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1989ar9300PciePhy_clkreq_enable_L1_ar9580_1p0,1990ARRAY_LENGTH(ar9300PciePhy_clkreq_enable_L1_ar9580_1p0),19912);1992} else {1993INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,1994ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0,1995ARRAY_LENGTH(1996ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0),19972);1998}1999} else {//no registry control, default is pll on2000INIT_INI_ARRAY(2001&ahp->ah_ini_pcie_serdes,2002ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0,2003ARRAY_LENGTH(2004ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0),20052);2006}2007} else {2008if (ah->ah_config.ath_hal_pll_pwr_save &2009AR_PCIE_PLL_PWRSAVE_CONTROL)2010{ //registry control2011if (ah->ah_config.ath_hal_pll_pwr_save &2012AR_PCIE_PLL_PWRSAVE_ON_D3)2013{ //bit1, in to D32014INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,2015ar9300PciePhy_clkreq_disable_L1_ar9580_1p0,2016ARRAY_LENGTH(2017ar9300PciePhy_clkreq_disable_L1_ar9580_1p0),20182);2019} else {2020INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,2021ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0,2022ARRAY_LENGTH(2023ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0),20242);2025}2026} else {//no registry control, default is pll on2027INIT_INI_ARRAY(2028&ahp->ah_ini_pcie_serdes,2029ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0,2030ARRAY_LENGTH(2031ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0),20322);2033}2034}20352036/*D0 Setting */2037if (ah->ah_config.ath_hal_pcie_clock_req) {2038if (ah->ah_config.ath_hal_pll_pwr_save &2039AR_PCIE_PLL_PWRSAVE_CONTROL)2040{ //registry control2041if (ah->ah_config.ath_hal_pll_pwr_save &2042AR_PCIE_PLL_PWRSAVE_ON_D0)2043{ //bit2, out of D32044INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,2045ar9300PciePhy_clkreq_enable_L1_ar9580_1p0,2046ARRAY_LENGTH(ar9300PciePhy_clkreq_enable_L1_ar9580_1p0),20472);20482049} else {2050INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,2051ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0,2052ARRAY_LENGTH(2053ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0),20542);2055}2056} else { //no registry control, default is pll on2057INIT_INI_ARRAY(2058&ahp->ah_ini_pcie_serdes_low_power,2059ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0,2060ARRAY_LENGTH(2061ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0),20622);2063}2064} else {2065if (ah->ah_config.ath_hal_pll_pwr_save &2066AR_PCIE_PLL_PWRSAVE_CONTROL)2067{//registry control2068if (ah->ah_config.ath_hal_pll_pwr_save &2069AR_PCIE_PLL_PWRSAVE_ON_D0)2070{//bit2, out of D32071INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,2072ar9300PciePhy_clkreq_disable_L1_ar9580_1p0,2073ARRAY_LENGTH(ar9300PciePhy_clkreq_disable_L1_ar9580_1p0),20742);2075} else {2076INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,2077ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0,2078ARRAY_LENGTH(2079ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0),20802);2081}2082} else { //no registry control, default is pll on2083INIT_INI_ARRAY(2084&ahp->ah_ini_pcie_serdes_low_power,2085ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0,2086ARRAY_LENGTH(2087ar9300PciePhy_pll_on_clkreq_disable_L1_ar9580_1p0),20882);2089}2090}20912092ah->ah_config.ath_hal_pcie_power_save_enable = 0;20932094#if 0 /* ATH_WOW */2095/* SerDes values during WOW sleep */2096INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_wow, ar9300_pcie_phy_awow,2097ARRAY_LENGTH(ar9300_pcie_phy_awow), 2);2098#endif20992100/* Fast clock modal settings */2101INIT_INI_ARRAY(&ahp->ah_ini_modes_additional,2102ar9300Modes_fast_clock_ar9580_1p0,2103ARRAY_LENGTH(ar9300Modes_fast_clock_ar9580_1p0), 3);2104INIT_INI_ARRAY(&ahp->ah_ini_japan2484,2105ar9300_ar9580_1p0_baseband_core_txfir_coeff_japan_2484,2106ARRAY_LENGTH(2107ar9300_ar9580_1p0_baseband_core_txfir_coeff_japan_2484), 2);21082109} else {2110/*2111* Osprey 2.2 - new INI format (pre, core, post arrays per subsystem)2112*/21132114/* mac */2115INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_PRE], NULL, 0, 0);2116INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_CORE],2117ar9300_osprey_2p2_mac_core,2118ARRAY_LENGTH(ar9300_osprey_2p2_mac_core), 2);2119INIT_INI_ARRAY(&ahp->ah_ini_mac[ATH_INI_POST],2120ar9300_osprey_2p2_mac_postamble,2121ARRAY_LENGTH(ar9300_osprey_2p2_mac_postamble), 5);21222123/* bb */2124INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_PRE], NULL, 0, 0);2125INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_CORE],2126ar9300_osprey_2p2_baseband_core,2127ARRAY_LENGTH(ar9300_osprey_2p2_baseband_core), 2);2128INIT_INI_ARRAY(&ahp->ah_ini_bb[ATH_INI_POST],2129ar9300_osprey_2p2_baseband_postamble,2130ARRAY_LENGTH(ar9300_osprey_2p2_baseband_postamble), 5);21312132/* radio */2133INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_PRE], NULL, 0, 0);2134INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_CORE],2135ar9300_osprey_2p2_radio_core,2136ARRAY_LENGTH(ar9300_osprey_2p2_radio_core), 2);2137INIT_INI_ARRAY(&ahp->ah_ini_radio[ATH_INI_POST],2138ar9300_osprey_2p2_radio_postamble,2139ARRAY_LENGTH(ar9300_osprey_2p2_radio_postamble), 5);21402141/* soc */2142INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_PRE],2143ar9300_osprey_2p2_soc_preamble,2144ARRAY_LENGTH(ar9300_osprey_2p2_soc_preamble), 2);2145INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_CORE], NULL, 0, 0);2146INIT_INI_ARRAY(&ahp->ah_ini_soc[ATH_INI_POST],2147ar9300_osprey_2p2_soc_postamble,2148ARRAY_LENGTH(ar9300_osprey_2p2_soc_postamble), 5);21492150/* rx/tx gain */2151INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,2152ar9300_common_rx_gain_table_osprey_2p2,2153ARRAY_LENGTH(ar9300_common_rx_gain_table_osprey_2p2), 2);2154INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,2155ar9300_modes_lowest_ob_db_tx_gain_table_osprey_2p2,2156ARRAY_LENGTH(ar9300_modes_lowest_ob_db_tx_gain_table_osprey_2p2), 5);21572158/* DFS */2159INIT_INI_ARRAY(&ahp->ah_ini_dfs,2160ar9300_osprey_2p2_baseband_postamble_dfs_channel,2161ARRAY_LENGTH(ar9300_osprey_2p2_baseband_postamble_dfs_channel), 3);21622163/* Load PCIE SERDES settings from INI */21642165/*D3 Setting */2166if (ah->ah_config.ath_hal_pcie_clock_req) {2167if (ah->ah_config.ath_hal_pll_pwr_save &2168AR_PCIE_PLL_PWRSAVE_CONTROL)2169{ //registry control2170if (ah->ah_config.ath_hal_pll_pwr_save &2171AR_PCIE_PLL_PWRSAVE_ON_D3)2172{ //bit1, in to D32173INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,2174ar9300PciePhy_clkreq_enable_L1_osprey_2p2,2175ARRAY_LENGTH(ar9300PciePhy_clkreq_enable_L1_osprey_2p2),21762);2177} else {2178INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,2179ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2,2180ARRAY_LENGTH(2181ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2),21822);2183}2184} else {//no registry control, default is pll on2185#ifndef ATH_BUS_PM2186INIT_INI_ARRAY(2187&ahp->ah_ini_pcie_serdes,2188ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2,2189ARRAY_LENGTH(2190ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2),21912);2192#else2193//no registry control, default is pll off2194INIT_INI_ARRAY(2195&ahp->ah_ini_pcie_serdes,2196ar9300PciePhy_clkreq_disable_L1_osprey_2p2,2197ARRAY_LENGTH(2198ar9300PciePhy_clkreq_disable_L1_osprey_2p2),21992);2200#endif22012202}2203} else {2204if (ah->ah_config.ath_hal_pll_pwr_save &2205AR_PCIE_PLL_PWRSAVE_CONTROL)2206{ //registry control2207if (ah->ah_config.ath_hal_pll_pwr_save &2208AR_PCIE_PLL_PWRSAVE_ON_D3)2209{ //bit1, in to D32210INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,2211ar9300PciePhy_clkreq_disable_L1_osprey_2p2,2212ARRAY_LENGTH(2213ar9300PciePhy_clkreq_disable_L1_osprey_2p2),22142);2215} else {2216INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes,2217ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2,2218ARRAY_LENGTH(2219ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2),22202);2221}2222} else {2223#ifndef ATH_BUS_PM2224//no registry control, default is pll on2225INIT_INI_ARRAY(2226&ahp->ah_ini_pcie_serdes,2227ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2,2228ARRAY_LENGTH(2229ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2),22302);2231#else2232//no registry control, default is pll off2233INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes, ar9300PciePhy_clkreq_disable_L1_osprey_2p2,2234ARRAY_LENGTH(ar9300PciePhy_clkreq_disable_L1_osprey_2p2), 2);2235#endif2236}2237}22382239/*D0 Setting */2240if (ah->ah_config.ath_hal_pcie_clock_req) {2241if (ah->ah_config.ath_hal_pll_pwr_save &2242AR_PCIE_PLL_PWRSAVE_CONTROL)2243{ //registry control2244if (ah->ah_config.ath_hal_pll_pwr_save &2245AR_PCIE_PLL_PWRSAVE_ON_D0)2246{ //bit2, out of D32247INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,2248ar9300PciePhy_clkreq_enable_L1_osprey_2p2,2249ARRAY_LENGTH(ar9300PciePhy_clkreq_enable_L1_osprey_2p2),22502);22512252} else {2253INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,2254ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2,2255ARRAY_LENGTH(2256ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2),22572);2258}2259} else { //no registry control, default is pll on2260INIT_INI_ARRAY(2261&ahp->ah_ini_pcie_serdes_low_power,2262ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2,2263ARRAY_LENGTH(2264ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2),22652);2266}2267} else {2268if (ah->ah_config.ath_hal_pll_pwr_save &2269AR_PCIE_PLL_PWRSAVE_CONTROL)2270{//registry control2271if (ah->ah_config.ath_hal_pll_pwr_save &2272AR_PCIE_PLL_PWRSAVE_ON_D0)2273{//bit2, out of D32274INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,2275ar9300PciePhy_clkreq_disable_L1_osprey_2p2,2276ARRAY_LENGTH(ar9300PciePhy_clkreq_disable_L1_osprey_2p2),22772);2278} else {2279INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_low_power,2280ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2,2281ARRAY_LENGTH(2282ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2),22832);2284}2285} else { //no registry control, default is pll on2286INIT_INI_ARRAY(2287&ahp->ah_ini_pcie_serdes_low_power,2288ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2,2289ARRAY_LENGTH(2290ar9300PciePhy_pll_on_clkreq_disable_L1_osprey_2p2),22912);2292}2293}22942295ah->ah_config.ath_hal_pcie_power_save_enable = 0;22962297#ifdef ATH_BUS_PM2298/*Use HAL to config PCI powersave by writing into the SerDes Registers */2299ah->ah_config.ath_hal_pcie_ser_des_write = 1;2300#endif23012302#if 0 /* ATH_WOW */2303/* SerDes values during WOW sleep */2304INIT_INI_ARRAY(&ahp->ah_ini_pcie_serdes_wow, ar9300_pcie_phy_awow,2305ARRAY_LENGTH(ar9300_pcie_phy_awow), 2);2306#endif23072308/* Fast clock modal settings */2309INIT_INI_ARRAY(&ahp->ah_ini_modes_additional,2310ar9300Modes_fast_clock_osprey_2p2,2311ARRAY_LENGTH(ar9300Modes_fast_clock_osprey_2p2), 3);2312INIT_INI_ARRAY(&ahp->ah_ini_japan2484,2313ar9300_osprey_2p2_baseband_core_txfir_coeff_japan_2484,2314ARRAY_LENGTH(2315ar9300_osprey_2p2_baseband_core_txfir_coeff_japan_2484), 2);23162317}23182319if(AR_SREV_WASP(ah) || AR_SREV_SCORPION(ah))2320{2321#define AR_SOC_RST_OTP_INTF 0xB80600B42322#define REG_READ(_reg) *((volatile u_int32_t *)(_reg))23232324ahp->ah_enterprise_mode = REG_READ(AR_SOC_RST_OTP_INTF);2325if (AR_SREV_SCORPION(ah)) {2326ahp->ah_enterprise_mode = ahp->ah_enterprise_mode << 12;2327}2328ath_hal_printf (ah, "Enterprise mode: 0x%08x\n", ahp->ah_enterprise_mode);2329#undef REG_READ2330#undef AR_SOC_RST_OTP_INTF2331} else {2332ahp->ah_enterprise_mode = OS_REG_READ(ah, AR_ENT_OTP);2333}233423352336if (ahpriv->ah_ispcie) {2337ar9300_config_pci_power_save(ah, 0, 0);2338} else {2339ar9300_disable_pcie_phy(ah);2340}2341#if 02342ath_hal_printf(ah, "%s: calling ar9300_hw_attach\n", __func__);2343#endif2344ecode = ar9300_hw_attach(ah);2345if (ecode != HAL_OK) {2346goto bad;2347}23482349/* set gain table pointers according to values read from the eeprom */2350ar9300_tx_gain_table_apply(ah);2351ar9300_rx_gain_table_apply(ah);23522353/*2354**2355** Got everything we need now to setup the capabilities.2356*/23572358if (!ar9300_fill_capability_info(ah)) {2359HALDEBUG(ah, HAL_DEBUG_RESET,2360"%s:failed ar9300_fill_capability_info\n", __func__);2361ecode = HAL_EEREAD;2362goto bad;2363}2364ecode = ar9300_init_mac_addr(ah);2365if (ecode != HAL_OK) {2366HALDEBUG(ah, HAL_DEBUG_RESET,2367"%s: failed initializing mac address\n", __func__);2368goto bad;2369}23702371/*2372* Initialize receive buffer size to MAC default2373*/2374ahp->rx_buf_size = HAL_RXBUFSIZE_DEFAULT;23752376#if ATH_WOW2377#if 02378/*2379* Needs to be removed once we stop using XB92 XXX2380* FIXME: Check with latest boards too - SriniK2381*/2382ar9300_wow_set_gpio_reset_low(ah);2383#endif23842385/*2386* Clear the Wow Status.2387*/2388OS_REG_WRITE(ah, AR_HOSTIF_REG(ah, AR_PCIE_PM_CTRL),2389OS_REG_READ(ah, AR_HOSTIF_REG(ah, AR_PCIE_PM_CTRL)) |2390AR_PMCTRL_WOW_PME_CLR);2391OS_REG_WRITE(ah, AR_WOW_PATTERN_REG,2392AR_WOW_CLEAR_EVENTS(OS_REG_READ(ah, AR_WOW_PATTERN_REG)));2393#endif23942395/*2396* Set the cur_trig_level to a value that works all modes - 11a/b/g or 11n2397* with aggregation enabled or disabled.2398*/2399ahp->ah_tx_trig_level = (AR_FTRIG_512B >> AR_FTRIG_S);24002401if (AR_SREV_HORNET(ah)) {2402ahp->nf_2GHz.nominal = AR_PHY_CCA_NOM_VAL_HORNET_2GHZ;2403ahp->nf_2GHz.max = AR_PHY_CCA_MAX_GOOD_VAL_OSPREY_2GHZ;2404ahp->nf_2GHz.min = AR_PHY_CCA_MIN_GOOD_VAL_OSPREY_2GHZ;2405ahp->nf_5GHz.nominal = AR_PHY_CCA_NOM_VAL_OSPREY_5GHZ;2406ahp->nf_5GHz.max = AR_PHY_CCA_MAX_GOOD_VAL_OSPREY_5GHZ;2407ahp->nf_5GHz.min = AR_PHY_CCA_MIN_GOOD_VAL_OSPREY_5GHZ;2408ahp->nf_cw_int_delta = AR_PHY_CCA_CW_INT_DELTA;2409} else if(AR_SREV_JUPITER(ah) || AR_SREV_APHRODITE(ah)){2410ahp->nf_2GHz.nominal = AR_PHY_CCA_NOM_VAL_JUPITER_2GHZ;2411ahp->nf_2GHz.max = AR_PHY_CCA_MAX_GOOD_VAL_OSPREY_2GHZ;2412ahp->nf_2GHz.min = AR_PHY_CCA_MIN_GOOD_VAL_JUPITER_2GHZ;2413ahp->nf_5GHz.nominal = AR_PHY_CCA_NOM_VAL_JUPITER_5GHZ;2414ahp->nf_5GHz.max = AR_PHY_CCA_MAX_GOOD_VAL_OSPREY_5GHZ;2415ahp->nf_5GHz.min = AR_PHY_CCA_MIN_GOOD_VAL_JUPITER_5GHZ;2416ahp->nf_cw_int_delta = AR_PHY_CCA_CW_INT_DELTA;2417} else {2418ahp->nf_2GHz.nominal = AR_PHY_CCA_NOM_VAL_OSPREY_2GHZ;2419ahp->nf_2GHz.max = AR_PHY_CCA_MAX_GOOD_VAL_OSPREY_2GHZ;2420ahp->nf_2GHz.min = AR_PHY_CCA_MIN_GOOD_VAL_OSPREY_2GHZ;2421if (AR_SREV_AR9580(ah) || AR_SREV_WASP(ah) || AR_SREV_SCORPION(ah)) {2422ahp->nf_5GHz.nominal = AR_PHY_CCA_NOM_VAL_PEACOCK_5GHZ;2423} else {2424ahp->nf_5GHz.nominal = AR_PHY_CCA_NOM_VAL_OSPREY_5GHZ;2425}2426ahp->nf_5GHz.max = AR_PHY_CCA_MAX_GOOD_VAL_OSPREY_5GHZ;2427ahp->nf_5GHz.min = AR_PHY_CCA_MIN_GOOD_VAL_OSPREY_5GHZ;2428ahp->nf_cw_int_delta = AR_PHY_CCA_CW_INT_DELTA;2429}24302431243224332434/* init BB Panic Watchdog timeout */2435if (AR_SREV_HORNET(ah)) {2436ahp->ah_bb_panic_timeout_ms = HAL_BB_PANIC_WD_TMO_HORNET;2437} else {2438ahp->ah_bb_panic_timeout_ms = HAL_BB_PANIC_WD_TMO;2439}244024412442/*2443* Determine whether tx IQ calibration HW should be enabled,2444* and whether tx IQ calibration should be performed during2445* AGC calibration, or separately.2446*/2447if (AR_SREV_JUPITER(ah) || AR_SREV_APHRODITE(ah)) {2448/*2449* Register not initialized yet. This flag will be re-initialized2450* after INI loading following each reset.2451*/2452ahp->tx_iq_cal_enable = 1;2453/* if tx IQ cal is enabled, do it together with AGC cal */2454ahp->tx_iq_cal_during_agc_cal = 1;2455} else if (AR_SREV_POSEIDON_OR_LATER(ah) && !AR_SREV_WASP(ah)) {2456ahp->tx_iq_cal_enable = 1;2457ahp->tx_iq_cal_during_agc_cal = 1;2458} else {2459/* osprey, hornet, wasp */2460ahp->tx_iq_cal_enable = 1;2461ahp->tx_iq_cal_during_agc_cal = 0;2462}2463return ah;24642465bad:2466if (ahp) {2467ar9300_detach((struct ath_hal *) ahp);2468}2469if (status) {2470*status = ecode;2471}2472return AH_NULL;2473}24742475void2476ar9300_detach(struct ath_hal *ah)2477{2478HALASSERT(ah != AH_NULL);2479HALASSERT(ah->ah_magic == AR9300_MAGIC);24802481/* Make sure that chip is awake before writing to it */2482if (!ar9300_set_power_mode(ah, HAL_PM_AWAKE, AH_TRUE)) {2483HALDEBUG(ah, HAL_DEBUG_UNMASKABLE,2484"%s: failed to wake up chip\n",2485__func__);2486}24872488ar9300_hw_detach(ah);2489ar9300_set_power_mode(ah, HAL_PM_FULL_SLEEP, AH_TRUE);24902491// ath_hal_hdprintf_deregister(ah);24922493if (AH9300(ah)->ah_cal_mem)2494ath_hal_free(AH9300(ah)->ah_cal_mem);2495AH9300(ah)->ah_cal_mem = AH_NULL;24962497ath_hal_free(ah);2498}24992500struct ath_hal_9300 *2501ar9300_new_state(u_int16_t devid, HAL_SOFTC sc,2502HAL_BUS_TAG st, HAL_BUS_HANDLE sh,2503uint16_t *eepromdata,2504HAL_OPS_CONFIG *ah_config,2505HAL_STATUS *status)2506{2507static const u_int8_t defbssidmask[IEEE80211_ADDR_LEN] =2508{ 0xff, 0xff, 0xff, 0xff, 0xff, 0xff };2509struct ath_hal_9300 *ahp;2510struct ath_hal *ah;25112512/* NB: memory is returned zero'd */2513ahp = ath_hal_malloc(sizeof(struct ath_hal_9300));2514if (ahp == AH_NULL) {2515HALDEBUG(AH_NULL, HAL_DEBUG_UNMASKABLE,2516"%s: cannot allocate memory for state block\n",2517__func__);2518*status = HAL_ENOMEM;2519return AH_NULL;2520}25212522ah = &ahp->ah_priv.h;2523/* set initial values */25242525/* stub everything first */2526ar9300_set_stub_functions(ah);25272528/* setup the FreeBSD HAL methods */2529ar9300_attach_freebsd_ops(ah);25302531/* These are private to this particular file, so .. */2532ah->ah_disablePCIE = ar9300_disable_pcie_phy;2533AH_PRIVATE(ah)->ah_getNfAdjust = ar9300_get_nf_adjust;2534AH_PRIVATE(ah)->ah_getChipPowerLimits = ar9300_get_chip_power_limits;25352536#if 02537/* Attach Osprey structure as default hal structure */2538OS_MEMCPY(&ahp->ah_priv.priv, &ar9300hal, sizeof(ahp->ah_priv.priv));2539#endif25402541#if 02542AH_PRIVATE(ah)->amem_handle = amem_handle;2543AH_PRIVATE(ah)->ah_osdev = osdev;2544#endif2545ah->ah_sc = sc;2546ah->ah_st = st;2547ah->ah_sh = sh;2548ah->ah_magic = AR9300_MAGIC;2549AH_PRIVATE(ah)->ah_devid = devid;25502551AH_PRIVATE(ah)->ah_flags = 0;25522553/*2554** Initialize factory defaults in the private space2555*/2556// ath_hal_factory_defaults(AH_PRIVATE(ah), hal_conf_parm);2557ar9300_config_defaults_freebsd(ah, ah_config);25582559/* XXX FreeBSD: cal is always in EEPROM */2560#if 02561if (!hal_conf_parm->calInFlash) {2562AH_PRIVATE(ah)->ah_flags |= AH_USE_EEPROM;2563}2564#endif2565AH_PRIVATE(ah)->ah_flags |= AH_USE_EEPROM;25662567#if 02568if (ar9300_eep_data_in_flash(ah)) {2569ahp->ah_priv.priv.ah_eeprom_read = ar9300_flash_read;2570ahp->ah_priv.priv.ah_eeprom_dump = AH_NULL;2571} else {2572ahp->ah_priv.priv.ah_eeprom_read = ar9300_eeprom_read_word;2573}2574#endif25752576/* XXX FreeBSD - for now, just supports EEPROM reading */2577ahp->ah_priv.ah_eepromRead = ar9300_eeprom_read_word;25782579AH_PRIVATE(ah)->ah_powerLimit = MAX_RATE_POWER;2580AH_PRIVATE(ah)->ah_tpScale = HAL_TP_SCALE_MAX; /* no scaling */25812582ahp->ah_atim_window = 0; /* [0..1000] */25832584ahp->ah_diversity_control =2585ah->ah_config.ath_hal_diversity_control;2586ahp->ah_antenna_switch_swap =2587ah->ah_config.ath_hal_antenna_switch_swap;25882589/*2590* Enable MIC handling.2591*/2592ahp->ah_sta_id1_defaults = AR_STA_ID1_CRPT_MIC_ENABLE;2593ahp->ah_enable32k_hz_clock = DONT_USE_32KHZ;/* XXX */2594ahp->ah_slot_time = (u_int) -1;2595ahp->ah_ack_timeout = (u_int) -1;2596OS_MEMCPY(&ahp->ah_bssid_mask, defbssidmask, IEEE80211_ADDR_LEN);25972598/*2599* 11g-specific stuff2600*/2601ahp->ah_g_beacon_rate = 0; /* adhoc beacon fixed rate */26022603/* SM power mode: Attach time, disable any setting */2604ahp->ah_sm_power_mode = HAL_SMPS_DEFAULT;26052606return ahp;2607}26082609HAL_BOOL2610ar9300_chip_test(struct ath_hal *ah)2611{2612/*u_int32_t reg_addr[2] = { AR_STA_ID0, AR_PHY_BASE+(8 << 2) };*/2613u_int32_t reg_addr[2] = { AR_STA_ID0 };2614u_int32_t reg_hold[2];2615u_int32_t pattern_data[4] =2616{ 0x55555555, 0xaaaaaaaa, 0x66666666, 0x99999999 };2617int i, j;26182619/* Test PHY & MAC registers */2620for (i = 0; i < 1; i++) {2621u_int32_t addr = reg_addr[i];2622u_int32_t wr_data, rd_data;26232624reg_hold[i] = OS_REG_READ(ah, addr);2625for (j = 0; j < 0x100; j++) {2626wr_data = (j << 16) | j;2627OS_REG_WRITE(ah, addr, wr_data);2628rd_data = OS_REG_READ(ah, addr);2629if (rd_data != wr_data) {2630HALDEBUG(ah, HAL_DEBUG_REGIO,2631"%s: address test failed addr: "2632"0x%08x - wr:0x%08x != rd:0x%08x\n",2633__func__, addr, wr_data, rd_data);2634return AH_FALSE;2635}2636}2637for (j = 0; j < 4; j++) {2638wr_data = pattern_data[j];2639OS_REG_WRITE(ah, addr, wr_data);2640rd_data = OS_REG_READ(ah, addr);2641if (wr_data != rd_data) {2642HALDEBUG(ah, HAL_DEBUG_REGIO,2643"%s: address test failed addr: "2644"0x%08x - wr:0x%08x != rd:0x%08x\n",2645__func__, addr, wr_data, rd_data);2646return AH_FALSE;2647}2648}2649OS_REG_WRITE(ah, reg_addr[i], reg_hold[i]);2650}2651OS_DELAY(100);2652return AH_TRUE;2653}26542655/*2656* Store the channel edges for the requested operational mode2657*/2658HAL_BOOL2659ar9300_get_channel_edges(struct ath_hal *ah,2660u_int16_t flags, u_int16_t *low, u_int16_t *high)2661{2662struct ath_hal_private *ahpriv = AH_PRIVATE(ah);2663HAL_CAPABILITIES *p_cap = &ahpriv->ah_caps;26642665if (flags & IEEE80211_CHAN_5GHZ) {2666*low = p_cap->halLow5GhzChan;2667*high = p_cap->halHigh5GhzChan;2668return AH_TRUE;2669}2670if ((flags & IEEE80211_CHAN_2GHZ)) {2671*low = p_cap->halLow2GhzChan;2672*high = p_cap->halHigh2GhzChan;26732674return AH_TRUE;2675}2676return AH_FALSE;2677}26782679HAL_BOOL2680ar9300_regulatory_domain_override(struct ath_hal *ah, u_int16_t regdmn)2681{2682AH_PRIVATE(ah)->ah_currentRD = regdmn;2683return AH_TRUE;2684}26852686/*2687* Fill all software cached or static hardware state information.2688* Return failure if capabilities are to come from EEPROM and2689* cannot be read.2690*/2691HAL_BOOL2692ar9300_fill_capability_info(struct ath_hal *ah)2693{2694#define AR_KEYTABLE_SIZE 1282695struct ath_hal_9300 *ahp = AH9300(ah);2696struct ath_hal_private *ahpriv = AH_PRIVATE(ah);2697HAL_CAPABILITIES *p_cap = &ahpriv->ah_caps;2698u_int16_t cap_field = 0, eeval;26992700ahpriv->ah_devType = (u_int16_t)ar9300_eeprom_get(ahp, EEP_DEV_TYPE);2701eeval = ar9300_eeprom_get(ahp, EEP_REG_0);27022703/* XXX record serial number */2704AH_PRIVATE(ah)->ah_currentRD = eeval;27052706/* Always enable fast clock; leave it up to EEPROM and channel */2707p_cap->halSupportsFastClock5GHz = AH_TRUE;27082709p_cap->halIntrMitigation = AH_TRUE;2710eeval = ar9300_eeprom_get(ahp, EEP_REG_1);2711AH_PRIVATE(ah)->ah_currentRDext = eeval | AR9300_RDEXT_DEFAULT;27122713/* Read the capability EEPROM location */2714cap_field = ar9300_eeprom_get(ahp, EEP_OP_CAP);27152716/* Construct wireless mode from EEPROM */2717p_cap->halWirelessModes = 0;2718eeval = ar9300_eeprom_get(ahp, EEP_OP_MODE);27192720/*2721* XXX FreeBSD specific: for now, set ath_hal_ht_enable to 1,2722* or we won't have 11n support.2723*/2724ah->ah_config.ath_hal_ht_enable = 1;27252726if (eeval & AR9300_OPFLAGS_11A) {2727p_cap->halWirelessModes |= HAL_MODE_11A |2728((!ah->ah_config.ath_hal_ht_enable ||2729(eeval & AR9300_OPFLAGS_N_5G_HT20)) ? 0 :2730(HAL_MODE_11NA_HT20 | ((eeval & AR9300_OPFLAGS_N_5G_HT40) ? 0 :2731(HAL_MODE_11NA_HT40PLUS | HAL_MODE_11NA_HT40MINUS))));2732}2733if (eeval & AR9300_OPFLAGS_11G) {2734p_cap->halWirelessModes |= HAL_MODE_11B | HAL_MODE_11G |2735((!ah->ah_config.ath_hal_ht_enable ||2736(eeval & AR9300_OPFLAGS_N_2G_HT20)) ? 0 :2737(HAL_MODE_11NG_HT20 | ((eeval & AR9300_OPFLAGS_N_2G_HT40) ? 0 :2738(HAL_MODE_11NG_HT40PLUS | HAL_MODE_11NG_HT40MINUS))));2739}27402741/* Get chainamsks from eeprom */2742p_cap->halTxChainMask = ar9300_eeprom_get(ahp, EEP_TX_MASK);2743p_cap->halRxChainMask = ar9300_eeprom_get(ahp, EEP_RX_MASK);2744274527462747#define owl_get_ntxchains(_txchainmask) \2748(((_txchainmask >> 2) & 1) + ((_txchainmask >> 1) & 1) + (_txchainmask & 1))27492750/* FreeBSD: Update number of TX/RX streams */2751p_cap->halTxStreams = owl_get_ntxchains(p_cap->halTxChainMask);2752p_cap->halRxStreams = owl_get_ntxchains(p_cap->halRxChainMask);2753#undef owl_get_ntxchains27542755/*2756* This being a newer chip supports TKIP non-splitmic mode.2757*2758*/2759ahp->ah_misc_mode |= AR_PCU_MIC_NEW_LOC_ENA;2760p_cap->halTkipMicTxRxKeySupport = AH_TRUE;27612762p_cap->halLow2GhzChan = 2312;2763p_cap->halHigh2GhzChan = 2732;27642765p_cap->halLow5GhzChan = 4920;2766p_cap->halHigh5GhzChan = 6100;27672768p_cap->halCipherCkipSupport = AH_FALSE;2769p_cap->halCipherTkipSupport = AH_TRUE;2770p_cap->halCipherAesCcmSupport = AH_TRUE;27712772p_cap->halMicCkipSupport = AH_FALSE;2773p_cap->halMicTkipSupport = AH_TRUE;2774p_cap->halMicAesCcmSupport = AH_TRUE;27752776p_cap->halChanSpreadSupport = AH_TRUE;2777p_cap->halSleepAfterBeaconBroken = AH_TRUE;27782779p_cap->halBurstSupport = AH_TRUE;2780p_cap->halChapTuningSupport = AH_TRUE;2781p_cap->halTurboPrimeSupport = AH_TRUE;2782p_cap->halFastFramesSupport = AH_TRUE;27832784p_cap->halTurboGSupport = p_cap->halWirelessModes & HAL_MODE_108G;27852786// p_cap->hal_xr_support = AH_FALSE;27872788p_cap->halHTSupport =2789ah->ah_config.ath_hal_ht_enable ? AH_TRUE : AH_FALSE;27902791p_cap->halGTTSupport = AH_TRUE;2792p_cap->halPSPollBroken = AH_TRUE; /* XXX fixed in later revs? */2793p_cap->halNumMRRetries = 4; /* Hardware supports 4 MRR */2794p_cap->halHTSGI20Support = AH_TRUE;2795p_cap->halVEOLSupport = AH_TRUE;2796p_cap->halBssIdMaskSupport = AH_TRUE;2797/* Bug 26802, fixed in later revs? */2798p_cap->halMcastKeySrchSupport = AH_TRUE;2799p_cap->halTsfAddSupport = AH_TRUE;28002801if (cap_field & AR_EEPROM_EEPCAP_MAXQCU) {2802p_cap->halTotalQueues = MS(cap_field, AR_EEPROM_EEPCAP_MAXQCU);2803} else {2804p_cap->halTotalQueues = HAL_NUM_TX_QUEUES;2805}28062807if (cap_field & AR_EEPROM_EEPCAP_KC_ENTRIES) {2808p_cap->halKeyCacheSize =28091 << MS(cap_field, AR_EEPROM_EEPCAP_KC_ENTRIES);2810} else {2811p_cap->halKeyCacheSize = AR_KEYTABLE_SIZE;2812}2813p_cap->halFastCCSupport = AH_TRUE;2814// p_cap->hal_num_mr_retries = 4;2815// ahp->hal_tx_trig_level_max = MAX_TX_FIFO_THRESHOLD;28162817p_cap->halNumGpioPins = AR9382_MAX_GPIO_PIN_NUM;28182819#if 02820/* XXX Verify support in Osprey */2821if (AR_SREV_MERLIN_10_OR_LATER(ah)) {2822p_cap->halWowSupport = AH_TRUE;2823p_cap->hal_wow_match_pattern_exact = AH_TRUE;2824if (AR_SREV_MERLIN(ah)) {2825p_cap->hal_wow_pattern_match_dword = AH_TRUE;2826}2827} else {2828p_cap->halWowSupport = AH_FALSE;2829p_cap->hal_wow_match_pattern_exact = AH_FALSE;2830}2831#endif2832p_cap->halWowSupport = AH_TRUE;2833p_cap->halWowMatchPatternExact = AH_TRUE;2834if (AR_SREV_POSEIDON(ah)) {2835p_cap->halWowMatchPatternExact = AH_TRUE;2836}28372838p_cap->halCSTSupport = AH_TRUE;28392840p_cap->halRifsRxSupport = AH_TRUE;2841p_cap->halRifsTxSupport = AH_TRUE;28422843#define IEEE80211_AMPDU_LIMIT_MAX (65536)2844p_cap->halRtsAggrLimit = IEEE80211_AMPDU_LIMIT_MAX;2845#undef IEEE80211_AMPDU_LIMIT_MAX28462847p_cap->halMfpSupport = ah->ah_config.ath_hal_mfp_support;28482849p_cap->halForcePpmSupport = AH_TRUE;2850p_cap->halHwBeaconProcSupport = AH_TRUE;28512852/* ar9300 - has the HW UAPSD trigger support,2853* but it has the following limitations2854* The power state change from the following2855* frames are not put in High priority queue.2856* i) Mgmt frames2857* ii) NoN QoS frames2858* iii) QoS frames form the access categories for which2859* UAPSD is not enabled.2860* so we can not enable this feature currently.2861* could be enabled, if these limitations are fixed2862* in later versions of ar9300 chips2863*/2864p_cap->halHasUapsdSupport = AH_FALSE;28652866/* Number of buffers that can be help in a single TxD */2867p_cap->halNumTxMaps = 4;28682869p_cap->halTxDescLen = sizeof(struct ar9300_txc);2870p_cap->halTxStatusLen = sizeof(struct ar9300_txs);2871p_cap->halRxStatusLen = sizeof(struct ar9300_rxs);28722873p_cap->halRxHpFifoDepth = HAL_HP_RXFIFO_DEPTH;2874p_cap->halRxLpFifoDepth = HAL_LP_RXFIFO_DEPTH;28752876/* Enable extension channel DFS support */2877p_cap->halUseCombinedRadarRssi = AH_TRUE;2878p_cap->halExtChanDfsSupport = AH_TRUE;2879#if ATH_SUPPORT_SPECTRAL2880p_cap->halSpectralScanSupport = AH_TRUE;2881#endif2882ahpriv->ah_rfsilent = ar9300_eeprom_get(ahp, EEP_RF_SILENT);2883if (ahpriv->ah_rfsilent & EEP_RFSILENT_ENABLED) {2884ahp->ah_gpio_select = MS(ahpriv->ah_rfsilent, EEP_RFSILENT_GPIO_SEL);2885ahp->ah_polarity = MS(ahpriv->ah_rfsilent, EEP_RFSILENT_POLARITY);28862887ath_hal_enable_rfkill(ah, AH_TRUE);2888p_cap->halRfSilentSupport = AH_TRUE;2889}28902891/* XXX */2892p_cap->halWpsPushButtonSupport = AH_FALSE;28932894#ifdef ATH_BT_COEX2895p_cap->halBtCoexSupport = AH_TRUE;2896p_cap->halBtCoexApsmWar = AH_FALSE;2897#endif28982899p_cap->halGenTimerSupport = AH_TRUE;2900ahp->ah_avail_gen_timers = ~((1 << AR_FIRST_NDP_TIMER) - 1);2901ahp->ah_avail_gen_timers &= (1 << AR_NUM_GEN_TIMERS) - 1;2902/*2903* According to Kyungwan, generic timer 0 and 8 are special2904* timers. Remove timer 8 from the available gen timer list.2905* Jupiter testing shows timer won't trigger with timer 8.2906*/2907ahp->ah_avail_gen_timers &= ~(1 << AR_GEN_TIMER_RESERVED);29082909if (AR_SREV_JUPITER(ah) || AR_SREV_APHRODITE(ah)) {2910#if ATH_SUPPORT_MCI2911if (ah->ah_config.ath_hal_mci_config & ATH_MCI_CONFIG_DISABLE_MCI)2912{2913p_cap->halMciSupport = AH_FALSE;2914}2915else2916#endif2917{2918p_cap->halMciSupport = (ahp->ah_enterprise_mode &2919AR_ENT_OTP_49GHZ_DISABLE) ? AH_FALSE: AH_TRUE;2920}2921HALDEBUG(AH_NULL, HAL_DEBUG_UNMASKABLE,2922"%s: (MCI) MCI support = %d\n",2923__func__, p_cap->halMciSupport);2924}2925else {2926p_cap->halMciSupport = AH_FALSE;2927}29282929/* XXX TODO: jupiter 2.1? */2930if (AR_SREV_JUPITER_20(ah)) {2931p_cap->halRadioRetentionSupport = AH_TRUE;2932} else {2933p_cap->halRadioRetentionSupport = AH_FALSE;2934}29352936p_cap->halAutoSleepSupport = AH_TRUE;29372938p_cap->halMbssidAggrSupport = AH_TRUE;2939// p_cap->hal_proxy_sta_support = AH_TRUE;29402941/* XXX Mark it true after it is verfied as fixed */2942p_cap->hal4kbSplitTransSupport = AH_FALSE;29432944/* Read regulatory domain flag */2945if (AH_PRIVATE(ah)->ah_currentRDext & (1 << REG_EXT_JAPAN_MIDBAND)) {2946/*2947* If REG_EXT_JAPAN_MIDBAND is set, turn on U1 EVEN, U2, and MIDBAND.2948*/2949p_cap->halRegCap =2950AR_EEPROM_EEREGCAP_EN_KK_NEW_11A |2951AR_EEPROM_EEREGCAP_EN_KK_U1_EVEN |2952AR_EEPROM_EEREGCAP_EN_KK_U2 |2953AR_EEPROM_EEREGCAP_EN_KK_MIDBAND;2954} else {2955p_cap->halRegCap =2956AR_EEPROM_EEREGCAP_EN_KK_NEW_11A | AR_EEPROM_EEREGCAP_EN_KK_U1_EVEN;2957}29582959/* For AR9300 and above, midband channels are always supported */2960p_cap->halRegCap |= AR_EEPROM_EEREGCAP_EN_FCC_MIDBAND;29612962p_cap->halNumAntCfg5GHz =2963ar9300_eeprom_get_num_ant_config(ahp, HAL_FREQ_BAND_5GHZ);2964p_cap->halNumAntCfg2GHz =2965ar9300_eeprom_get_num_ant_config(ahp, HAL_FREQ_BAND_2GHZ);29662967/* STBC supported */2968p_cap->halRxStbcSupport = 1; /* number of streams for STBC recieve. */2969if (AR_SREV_HORNET(ah) || AR_SREV_POSEIDON(ah) || AR_SREV_APHRODITE(ah)) {2970p_cap->halTxStbcSupport = 0;2971} else {2972p_cap->halTxStbcSupport = 1;2973}29742975p_cap->halEnhancedDmaSupport = AH_TRUE;2976p_cap->halEnhancedDfsSupport = AH_TRUE;29772978/*2979* EV61133 (missing interrupts due to AR_ISR_RAC).2980* Fixed in Osprey 2.0.2981*/2982p_cap->halIsrRacSupport = AH_TRUE;29832984/* XXX FreeBSD won't support TKIP and WEP aggregation */2985#if 02986p_cap->hal_wep_tkip_aggr_support = AH_TRUE;2987p_cap->hal_wep_tkip_aggr_num_tx_delim = 10; /* TBD */2988p_cap->hal_wep_tkip_aggr_num_rx_delim = 10; /* TBD */2989p_cap->hal_wep_tkip_max_ht_rate = 15; /* TBD */2990#endif29912992/*2993* XXX FreeBSD won't need these; but eventually add them2994* and add the WARs - AGGR extra delim WAR is useful to know2995* about.2996*/2997#if 02998p_cap->hal_cfend_fix_support = AH_FALSE;2999p_cap->hal_aggr_extra_delim_war = AH_FALSE;3000#endif3001p_cap->halTxTstampPrecision = 32;3002p_cap->halRxTstampPrecision = 32;3003p_cap->halRxTxAbortSupport = AH_TRUE;3004p_cap->hal_ani_poll_interval = AR9300_ANI_POLLINTERVAL;3005p_cap->hal_channel_switch_time_usec = AR9300_CHANNEL_SWITCH_TIME_USEC;30063007/* Transmit Beamforming supported, fill capabilities */3008p_cap->halPaprdEnabled = ar9300_eeprom_get(ahp, EEP_PAPRD_ENABLED);3009p_cap->halChanHalfRate =3010!(ahp->ah_enterprise_mode & AR_ENT_OTP_10MHZ_DISABLE);3011p_cap->halChanQuarterRate =3012!(ahp->ah_enterprise_mode & AR_ENT_OTP_5MHZ_DISABLE);30133014if(AR_SREV_JUPITER(ah) || AR_SREV_APHRODITE(ah)){3015/* There is no AR_ENT_OTP_49GHZ_DISABLE feature in Jupiter, now the bit is used to disable BT. */3016p_cap->hal49GhzSupport = 1;3017} else {3018p_cap->hal49GhzSupport = !(ahp->ah_enterprise_mode & AR_ENT_OTP_49GHZ_DISABLE);3019}30203021if (AR_SREV_POSEIDON(ah) || AR_SREV_HORNET(ah) || AR_SREV_APHRODITE(ah)) {3022/* LDPC supported */3023/* Poseidon doesn't support LDPC, or it will cause receiver CRC Error */3024p_cap->halLDPCSupport = AH_FALSE;3025/* PCI_E LCR offset */3026if (AR_SREV_POSEIDON(ah)) {3027p_cap->hal_pcie_lcr_offset = 0x80; /*for Poseidon*/3028}3029/*WAR method for APSM L0s with Poseidon 1.0*/3030if (AR_SREV_POSEIDON_10(ah)) {3031p_cap->hal_pcie_lcr_extsync_en = AH_TRUE;3032}3033} else {3034p_cap->halLDPCSupport = AH_TRUE;3035}30363037/* XXX is this a flag, or a chainmask number? */3038p_cap->halApmEnable = !! ar9300_eeprom_get(ahp, EEP_CHAIN_MASK_REDUCE);3039#if ATH_ANT_DIV_COMB3040if (AR_SREV_HORNET(ah) || AR_SREV_POSEIDON_11_OR_LATER(ah) || AR_SREV_APHRODITE(ah)) {3041if (ahp->ah_diversity_control == HAL_ANT_VARIABLE) {3042u_int8_t ant_div_control1 =3043ar9300_eeprom_get(ahp, EEP_ANTDIV_control);3044/* if enable_lnadiv is 0x1 and enable_fast_div is 0x1,3045* we enable the diversity-combining algorithm.3046*/3047if ((ant_div_control1 >> 0x6) == 0x3) {3048p_cap->halAntDivCombSupport = AH_TRUE;3049}3050p_cap->halAntDivCombSupportOrg = p_cap->halAntDivCombSupport;3051}3052}3053#endif /* ATH_ANT_DIV_COMB */30543055/*3056* FreeBSD: enable LNA mixing if the chip is Hornet or Poseidon.3057*/3058if (AR_SREV_HORNET(ah) || AR_SREV_POSEIDON_11_OR_LATER(ah)) {3059p_cap->halRxUsingLnaMixing = AH_TRUE;3060}30613062/*3063* AR5416 and later NICs support MYBEACON filtering.3064*/3065p_cap->halRxDoMyBeacon = AH_TRUE;30663067#if ATH_WOW_OFFLOAD3068if (AR_SREV_JUPITER_20_OR_LATER(ah) || AR_SREV_APHRODITE(ah)) {3069p_cap->hal_wow_gtk_offload_support = AH_TRUE;3070p_cap->hal_wow_arp_offload_support = AH_TRUE;3071p_cap->hal_wow_ns_offload_support = AH_TRUE;3072p_cap->hal_wow_4way_hs_wakeup_support = AH_TRUE;3073p_cap->hal_wow_acer_magic_support = AH_TRUE;3074p_cap->hal_wow_acer_swka_support = AH_TRUE;3075} else {3076p_cap->hal_wow_gtk_offload_support = AH_FALSE;3077p_cap->hal_wow_arp_offload_support = AH_FALSE;3078p_cap->hal_wow_ns_offload_support = AH_FALSE;3079p_cap->hal_wow_4way_hs_wakeup_support = AH_FALSE;3080p_cap->hal_wow_acer_magic_support = AH_FALSE;3081p_cap->hal_wow_acer_swka_support = AH_FALSE;3082}3083#endif /* ATH_WOW_OFFLOAD */308430853086return AH_TRUE;3087#undef AR_KEYTABLE_SIZE3088}30893090#if 03091static HAL_BOOL3092ar9300_get_chip_power_limits(struct ath_hal *ah, HAL_CHANNEL *chans,3093u_int32_t nchans)3094{3095struct ath_hal_9300 *ahp = AH9300(ah);30963097return ahp->ah_rf_hal.get_chip_power_lim(ah, chans, nchans);3098}3099#endif3100/* XXX FreeBSD */31013102static HAL_BOOL3103ar9300_get_chip_power_limits(struct ath_hal *ah,3104struct ieee80211_channel *chan)3105{31063107chan->ic_maxpower = AR9300_MAX_RATE_POWER;3108chan->ic_minpower = 0;31093110return AH_TRUE;3111}31123113/*3114* Disable PLL when in L0s as well as receiver clock when in L1.3115* This power saving option must be enabled through the Serdes.3116*3117* Programming the Serdes must go through the same 288 bit serial shift3118* register as the other analog registers. Hence the 9 writes.3119*3120* XXX Clean up the magic numbers.3121*/3122void3123ar9300_config_pci_power_save(struct ath_hal *ah, int restore, int power_off)3124{3125struct ath_hal_9300 *ahp = AH9300(ah);3126int i;31273128if (AH_PRIVATE(ah)->ah_ispcie != AH_TRUE) {3129return;3130}31313132/*3133* Increase L1 Entry Latency. Some WB222 boards don't have3134* this change in eeprom/OTP.3135*/3136if (AR_SREV_JUPITER(ah)) {3137u_int32_t val = ah->ah_config.ath_hal_war70c;3138if ((val & 0xff000000) == 0x17000000) {3139val &= 0x00ffffff;3140val |= 0x27000000;3141OS_REG_WRITE(ah, 0x570c, val);3142}3143}31443145/* Do not touch SERDES registers */3146if (ah->ah_config.ath_hal_pcie_power_save_enable == 2) {3147return;3148}31493150/* Nothing to do on restore for 11N */3151if (!restore) {3152/* set bit 19 to allow forcing of pcie core into L1 state */3153OS_REG_SET_BIT(ah,3154AR_HOSTIF_REG(ah, AR_PCIE_PM_CTRL), AR_PCIE_PM_CTRL_ENA);31553156/*3157* Set PCIE workaround config only if requested, else use the reset3158* value of this register.3159*/3160if (ah->ah_config.ath_hal_pcie_waen) {3161OS_REG_WRITE(ah,3162AR_HOSTIF_REG(ah, AR_WA),3163ah->ah_config.ath_hal_pcie_waen);3164} else {3165/* Set Bits 17 and 14 in the AR_WA register. */3166OS_REG_WRITE(ah, AR_HOSTIF_REG(ah, AR_WA), ahp->ah_wa_reg_val);3167}3168}31693170/* Configure PCIE after Ini init. SERDES values now come from ini file */3171if (ah->ah_config.ath_hal_pcie_ser_des_write) {3172if (power_off) {3173for (i = 0; i < ahp->ah_ini_pcie_serdes.ia_rows; i++) {3174OS_REG_WRITE(ah,3175INI_RA(&ahp->ah_ini_pcie_serdes, i, 0),3176INI_RA(&ahp->ah_ini_pcie_serdes, i, 1));3177}3178} else {3179for (i = 0; i < ahp->ah_ini_pcie_serdes_low_power.ia_rows; i++) {3180OS_REG_WRITE(ah,3181INI_RA(&ahp->ah_ini_pcie_serdes_low_power, i, 0),3182INI_RA(&ahp->ah_ini_pcie_serdes_low_power, i, 1));3183}3184}3185}31863187}31883189/*3190* Recipe from charles to turn off PCIe PHY in PCI mode for power savings3191*/3192void3193ar9300_disable_pcie_phy(struct ath_hal *ah)3194{3195/* Osprey does not support PCI mode */3196}31973198static inline HAL_STATUS3199ar9300_init_mac_addr(struct ath_hal *ah)3200{3201u_int32_t sum;3202int i;3203u_int16_t eeval;3204struct ath_hal_9300 *ahp = AH9300(ah);3205u_int32_t EEP_MAC [] = { EEP_MAC_LSW, EEP_MAC_MID, EEP_MAC_MSW };32063207sum = 0;3208for (i = 0; i < 3; i++) {3209eeval = ar9300_eeprom_get(ahp, EEP_MAC[i]);3210sum += eeval;3211ahp->ah_macaddr[2*i] = eeval >> 8;3212ahp->ah_macaddr[2*i + 1] = eeval & 0xff;3213}3214if (sum == 0 || sum == 0xffff*3) {3215HALDEBUG(ah, HAL_DEBUG_EEPROM, "%s: mac address read failed: %s\n",3216__func__, ath_hal_ether_sprintf(ahp->ah_macaddr));3217return HAL_EEBADMAC;3218}32193220return HAL_OK;3221}32223223/*3224* Code for the "real" chip i.e. non-emulation. Review and revisit3225* when actual hardware is at hand.3226*/3227static inline HAL_STATUS3228ar9300_hw_attach(struct ath_hal *ah)3229{3230HAL_STATUS ecode;32313232if (!ar9300_chip_test(ah)) {3233HALDEBUG(ah, HAL_DEBUG_REGIO,3234"%s: hardware self-test failed\n", __func__);3235return HAL_ESELFTEST;3236}32373238#if 03239ath_hal_printf(ah, "%s: calling ar9300_eeprom_attach\n", __func__);3240#endif3241ecode = ar9300_eeprom_attach(ah);3242ath_hal_printf(ah, "%s: ar9300_eeprom_attach returned %d\n", __func__, ecode);3243if (ecode != HAL_OK) {3244return ecode;3245}3246if (!ar9300_rf_attach(ah, &ecode)) {3247HALDEBUG(ah, HAL_DEBUG_RESET, "%s: RF setup failed, status %u\n",3248__func__, ecode);3249}32503251if (ecode != HAL_OK) {3252return ecode;3253}3254ar9300_ani_attach(ah);32553256return HAL_OK;3257}32583259static inline void3260ar9300_hw_detach(struct ath_hal *ah)3261{3262/* XXX EEPROM allocated state */3263ar9300_ani_detach(ah);3264}32653266static int16_t3267ar9300_get_nf_adjust(struct ath_hal *ah, const HAL_CHANNEL_INTERNAL *c)3268{3269return 0;3270}32713272void3273ar9300_set_immunity(struct ath_hal *ah, HAL_BOOL enable)3274{3275struct ath_hal_9300 *ahp = AH9300(ah);3276u_int32_t m1_thresh_low = enable ? 127 : ahp->ah_immunity_vals[0],3277m2_thresh_low = enable ? 127 : ahp->ah_immunity_vals[1],3278m1_thresh = enable ? 127 : ahp->ah_immunity_vals[2],3279m2_thresh = enable ? 127 : ahp->ah_immunity_vals[3],3280m2_count_thr = enable ? 31 : ahp->ah_immunity_vals[4],3281m2_count_thr_low = enable ? 63 : ahp->ah_immunity_vals[5];32823283if (ahp->ah_immunity_on == enable) {3284return;3285}32863287ahp->ah_immunity_on = enable;32883289OS_REG_RMW_FIELD(ah, AR_PHY_SFCORR_LOW,3290AR_PHY_SFCORR_LOW_M1_THRESH_LOW, m1_thresh_low);3291OS_REG_RMW_FIELD(ah, AR_PHY_SFCORR_LOW,3292AR_PHY_SFCORR_LOW_M2_THRESH_LOW, m2_thresh_low);3293OS_REG_RMW_FIELD(ah, AR_PHY_SFCORR,3294AR_PHY_SFCORR_M1_THRESH, m1_thresh);3295OS_REG_RMW_FIELD(ah, AR_PHY_SFCORR,3296AR_PHY_SFCORR_M2_THRESH, m2_thresh);3297OS_REG_RMW_FIELD(ah, AR_PHY_SFCORR,3298AR_PHY_SFCORR_M2COUNT_THR, m2_count_thr);3299OS_REG_RMW_FIELD(ah, AR_PHY_SFCORR_LOW,3300AR_PHY_SFCORR_LOW_M2COUNT_THR_LOW, m2_count_thr_low);33013302OS_REG_RMW_FIELD(ah, AR_PHY_SFCORR_EXT,3303AR_PHY_SFCORR_EXT_M1_THRESH_LOW, m1_thresh_low);3304OS_REG_RMW_FIELD(ah, AR_PHY_SFCORR_EXT,3305AR_PHY_SFCORR_EXT_M2_THRESH_LOW, m2_thresh_low);3306OS_REG_RMW_FIELD(ah, AR_PHY_SFCORR_EXT,3307AR_PHY_SFCORR_EXT_M1_THRESH, m1_thresh);3308OS_REG_RMW_FIELD(ah, AR_PHY_SFCORR_EXT,3309AR_PHY_SFCORR_EXT_M2_THRESH, m2_thresh);33103311if (!enable) {3312OS_REG_SET_BIT(ah, AR_PHY_SFCORR_LOW,3313AR_PHY_SFCORR_LOW_USE_SELF_CORR_LOW);3314} else {3315OS_REG_CLR_BIT(ah, AR_PHY_SFCORR_LOW,3316AR_PHY_SFCORR_LOW_USE_SELF_CORR_LOW);3317}3318}33193320/* XXX FreeBSD: I'm not sure how to implement this.. */3321#if 03322int3323ar9300_get_cal_intervals(struct ath_hal *ah, HAL_CALIBRATION_TIMER **timerp,3324HAL_CAL_QUERY query)3325{3326#define AR9300_IS_CHAIN_RX_IQCAL_INVALID(_ah, _reg) \3327((OS_REG_READ((_ah), _reg) & 0x3fff) == 0)3328#define AR9300_IS_RX_IQCAL_DISABLED(_ah) \3329(!(OS_REG_READ((_ah), AR_PHY_RX_IQCAL_CORR_B0) & \3330AR_PHY_RX_IQCAL_CORR_IQCORR_ENABLE))3331/* Avoid comilation warnings. Variables are not used when EMULATION. */3332struct ath_hal_9300 *ahp = AH9300(ah);3333u_int8_t rxchainmask = ahp->ah_rx_chainmask, i;3334int rx_iqcal_invalid = 0, num_chains = 0;3335static const u_int32_t offset_array[3] = {3336AR_PHY_RX_IQCAL_CORR_B0,3337AR_PHY_RX_IQCAL_CORR_B1,3338AR_PHY_RX_IQCAL_CORR_B2};33393340*timerp = ar9300_cals;33413342switch (query) {3343case HAL_QUERY_CALS:3344return AR9300_NUM_CAL_TYPES;3345case HAL_QUERY_RERUN_CALS:3346for (i = 0; i < AR9300_MAX_CHAINS; i++) {3347if (rxchainmask & (1 << i)) {3348num_chains++;3349}3350}3351for (i = 0; i < num_chains; i++) {3352if (AR_SREV_POSEIDON(ah) || AR_SREV_APHRODITE(ah)) {3353HALASSERT(num_chains == 0x1);3354}3355if (AR9300_IS_CHAIN_RX_IQCAL_INVALID(ah, offset_array[i])) {3356rx_iqcal_invalid = 1;3357}3358}3359if (AR9300_IS_RX_IQCAL_DISABLED(ah)) {3360rx_iqcal_invalid = 1;3361}33623363return rx_iqcal_invalid;3364default:3365HALASSERT(0);3366}3367return 0;3368}3369#endif33703371#if ATH_TRAFFIC_FAST_RECOVER3372#define PLL3 0x161883373#define PLL3_DO_MEAS_MASK 0x400000003374#define PLL4 0x1618c3375#define PLL4_MEAS_DONE 0x83376#define SQSUM_DVC_MASK 0x007ffff83377unsigned long3378ar9300_get_pll3_sqsum_dvc(struct ath_hal *ah)3379{3380if (AR_SREV_HORNET(ah) || AR_SREV_POSEIDON(ah) || AR_SREV_WASP(ah) || AR_SREV_SCORPION(ah)) {3381OS_REG_WRITE(ah, PLL3, (OS_REG_READ(ah, PLL3) & ~(PLL3_DO_MEAS_MASK)));3382OS_DELAY(100);3383OS_REG_WRITE(ah, PLL3, (OS_REG_READ(ah, PLL3) | PLL3_DO_MEAS_MASK));33843385while ( (OS_REG_READ(ah, PLL4) & PLL4_MEAS_DONE) == 0) {3386OS_DELAY(100);3387}33883389return (( OS_REG_READ(ah, PLL3) & SQSUM_DVC_MASK ) >> 3);3390} else {3391HALDEBUG(ah, HAL_DEBUG_UNMASKABLE,3392"%s: unable to get pll3_sqsum_dvc\n",3393__func__);3394return 0;3395}3396}3397#endif339833993400#define RX_GAIN_TABLE_LENGTH 1283401// this will be called if rfGainCAP is enabled and rfGainCAP setting is changed,3402// or rxGainTable setting is changed3403HAL_BOOL ar9300_rf_gain_cap_apply(struct ath_hal *ah, int is_2GHz)3404{3405int i, done = 0, i_rx_gain = 32;3406u_int32_t rf_gain_cap;3407u_int32_t rx_gain_value, a_Byte, rx_gain_value_caped;3408static u_int32_t rx_gain_table[RX_GAIN_TABLE_LENGTH * 2][2];3409ar9300_eeprom_t *eep = &AH9300(ah)->ah_eeprom;3410struct ath_hal_9300 *ahp = AH9300(ah);34113412if ( !((eep->base_eep_header.misc_configuration & 0x80) >> 7) )3413return AH_FALSE;34143415if (is_2GHz)3416{3417rf_gain_cap = (u_int32_t) eep->modal_header_2g.rf_gain_cap;3418}3419else3420{3421rf_gain_cap = (u_int32_t) eep->modal_header_5g.rf_gain_cap;3422}34233424if (rf_gain_cap == 0)3425return AH_FALSE;34263427for (i = 0; i< RX_GAIN_TABLE_LENGTH * 2; i++)3428{3429if (AR_SREV_AR9580(ah))3430{3431// BB_rx_ocgain23432i_rx_gain = 128 + 32;3433switch (ar9300_rx_gain_index_get(ah))3434{3435case 0:3436rx_gain_table[i][0] =3437ar9300_common_rx_gain_table_ar9580_1p0[i][0];3438rx_gain_table[i][1] =3439ar9300_common_rx_gain_table_ar9580_1p0[i][1];3440break;3441case 1:3442rx_gain_table[i][0] =3443ar9300_common_wo_xlna_rx_gain_table_ar9580_1p0[i][0];3444rx_gain_table[i][1] =3445ar9300_common_wo_xlna_rx_gain_table_ar9580_1p0[i][1];3446break;3447}3448}3449else if (AR_SREV_OSPREY_22(ah))3450{3451i_rx_gain = 128 + 32;3452switch (ar9300_rx_gain_index_get(ah))3453{3454case 0:3455rx_gain_table[i][0] = ar9300_common_rx_gain_table_osprey_2p2[i][0];3456rx_gain_table[i][1] = ar9300_common_rx_gain_table_osprey_2p2[i][1];3457break;3458case 1:3459rx_gain_table[i][0] =3460ar9300Common_wo_xlna_rx_gain_table_osprey_2p2[i][0];3461rx_gain_table[i][1] =3462ar9300Common_wo_xlna_rx_gain_table_osprey_2p2[i][1];3463break;3464}3465}3466else3467{3468return AH_FALSE;3469}3470}34713472while (1)3473{3474rx_gain_value = rx_gain_table[i_rx_gain][1];3475rx_gain_value_caped = rx_gain_value;3476a_Byte = rx_gain_value & (0x000000FF);3477if (a_Byte>rf_gain_cap)3478{3479rx_gain_value_caped = (rx_gain_value_caped &3480(0xFFFFFF00)) + rf_gain_cap;3481}3482a_Byte = rx_gain_value & (0x0000FF00);3483if ( a_Byte > ( rf_gain_cap << 8 ) )3484{3485rx_gain_value_caped = (rx_gain_value_caped &3486(0xFFFF00FF)) + (rf_gain_cap<<8);3487}3488a_Byte = rx_gain_value & (0x00FF0000);3489if ( a_Byte > ( rf_gain_cap << 16 ) )3490{3491rx_gain_value_caped = (rx_gain_value_caped &3492(0xFF00FFFF)) + (rf_gain_cap<<16);3493}3494a_Byte = rx_gain_value & (0xFF000000);3495if ( a_Byte > ( rf_gain_cap << 24 ) )3496{3497rx_gain_value_caped = (rx_gain_value_caped &3498(0x00FFFFFF)) + (rf_gain_cap<<24);3499}3500else3501{3502done = 1;3503}3504HALDEBUG(ah, HAL_DEBUG_RESET,3505"%s: rx_gain_address: %x, rx_gain_value: %x rx_gain_value_caped: %x\n",3506__func__, rx_gain_table[i_rx_gain][0], rx_gain_value, rx_gain_value_caped);3507if (rx_gain_value_caped != rx_gain_value)3508{3509rx_gain_table[i_rx_gain][1] = rx_gain_value_caped;3510}3511if (done == 1)3512break;3513i_rx_gain ++;3514}3515INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain, rx_gain_table, ARRAY_LENGTH(rx_gain_table), 2);3516return AH_TRUE;3517}351835193520void ar9300_rx_gain_table_apply(struct ath_hal *ah)3521{3522struct ath_hal_9300 *ahp = AH9300(ah);3523//struct ath_hal_private *ahpriv = AH_PRIVATE(ah);3524u_int32_t xlan_gpio_cfg;3525u_int8_t i;35263527if (AR_SREV_OSPREY(ah) || AR_SREV_AR9580(ah))3528{3529// this will be called if rxGainTable setting is changed3530if (ar9300_rf_gain_cap_apply(ah, 1))3531return;3532}35333534switch (ar9300_rx_gain_index_get(ah))3535{3536case 2:3537if (AR_SREV_JUPITER_10(ah)) {3538INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3539ar9300_common_mixed_rx_gain_table_jupiter_1p0,3540ARRAY_LENGTH(ar9300_common_mixed_rx_gain_table_jupiter_1p0), 2);3541break;3542}3543else if (AR_SREV_JUPITER_20(ah)) {3544INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3545ar9300Common_mixed_rx_gain_table_jupiter_2p0,3546ARRAY_LENGTH(ar9300Common_mixed_rx_gain_table_jupiter_2p0), 2);3547INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain_bb_core,3548ar9462_2p0_baseband_core_mix_rxgain,3549ARRAY_LENGTH(ar9462_2p0_baseband_core_mix_rxgain), 2);3550INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain_bb_postamble,3551ar9462_2p0_baseband_postamble_mix_rxgain,3552ARRAY_LENGTH(ar9462_2p0_baseband_postamble_mix_rxgain), 2);3553INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain_xlna,3554ar9462_2p0_baseband_postamble_5g_xlna,3555ARRAY_LENGTH(ar9462_2p0_baseband_postamble_5g_xlna), 2);3556break;3557}3558else if (AR_SREV_JUPITER_21(ah)) {3559INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3560ar9462_2p1_common_mixed_rx_gain,3561ARRAY_LENGTH(ar9462_2p1_common_mixed_rx_gain), 2);3562INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain_bb_core,3563ar9462_2p1_baseband_core_mix_rxgain,3564ARRAY_LENGTH(ar9462_2p1_baseband_core_mix_rxgain), 2);3565INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain_bb_postamble,3566ar9462_2p1_baseband_postamble_mix_rxgain,3567ARRAY_LENGTH(ar9462_2p1_baseband_postamble_mix_rxgain), 2);3568INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain_xlna,3569ar9462_2p1_baseband_postamble_5g_xlna,3570ARRAY_LENGTH(ar9462_2p1_baseband_postamble_5g_xlna), 2);35713572break;3573}3574case 3:3575if (AR_SREV_JUPITER_21(ah)) {3576INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3577ar9462_2p1_common_5g_xlna_only_rxgain,3578ARRAY_LENGTH(ar9462_2p1_common_5g_xlna_only_rxgain), 2);3579INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain_xlna,3580ar9462_2p1_baseband_postamble_5g_xlna,3581ARRAY_LENGTH(ar9462_2p1_baseband_postamble_5g_xlna), 2);3582} else if (AR_SREV_JUPITER_20(ah)) {3583INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3584ar9462_2p0_common_5g_xlna_only_rxgain,3585ARRAY_LENGTH(ar9462_2p0_common_5g_xlna_only_rxgain), 2);3586INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain_xlna,3587ar9462_2p0_baseband_postamble_5g_xlna,3588ARRAY_LENGTH(ar9462_2p0_baseband_postamble_5g_xlna), 2);3589}3590break;3591case 0:3592default:3593if (AR_SREV_HORNET_12(ah)) {3594INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3595ar9331_common_rx_gain_hornet1_2,3596ARRAY_LENGTH(ar9331_common_rx_gain_hornet1_2), 2);3597} else if (AR_SREV_HORNET_11(ah)) {3598INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3599ar9331_common_rx_gain_hornet1_1,3600ARRAY_LENGTH(ar9331_common_rx_gain_hornet1_1), 2);3601} else if (AR_SREV_POSEIDON_11_OR_LATER(ah)) {3602INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3603ar9485_common_wo_xlna_rx_gain_poseidon1_1,3604ARRAY_LENGTH(ar9485_common_wo_xlna_rx_gain_poseidon1_1), 2);3605/* XXX FreeBSD: this needs to be revisited!! */3606xlan_gpio_cfg = ah->ah_config.ath_hal_ext_lna_ctl_gpio;3607if (xlan_gpio_cfg) {3608for (i = 0; i < 32; i++) {3609if (xlan_gpio_cfg & (1 << i)) {3610/*3611* XXX FreeBSD: definitely make sure this3612* results in the correct value being written3613* to the hardware, or weird crap is very likely3614* to occur!3615*/3616ath_hal_gpioCfgOutput(ah, i,3617HAL_GPIO_OUTPUT_MUX_PCIE_ATTENTION_LED);3618}3619}3620}36213622} else if (AR_SREV_POSEIDON(ah)) {3623INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3624ar9485Common_wo_xlna_rx_gain_poseidon1_0,3625ARRAY_LENGTH(ar9485Common_wo_xlna_rx_gain_poseidon1_0), 2);3626} else if (AR_SREV_JUPITER_10(ah)) {3627INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3628ar9300_common_rx_gain_table_jupiter_1p0,3629ARRAY_LENGTH(ar9300_common_rx_gain_table_jupiter_1p0), 2);3630} else if (AR_SREV_JUPITER_20(ah)) {3631INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3632ar9300Common_rx_gain_table_jupiter_2p0,3633ARRAY_LENGTH(ar9300Common_rx_gain_table_jupiter_2p0), 2);3634} else if (AR_SREV_JUPITER_21(ah)) {3635INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3636ar9462_2p1_common_rx_gain,3637ARRAY_LENGTH(ar9462_2p1_common_rx_gain), 2);3638} else if (AR_SREV_AR9580(ah)) {3639INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3640ar9300_common_rx_gain_table_ar9580_1p0,3641ARRAY_LENGTH(ar9300_common_rx_gain_table_ar9580_1p0), 2);3642} else if (AR_SREV_WASP(ah)) {3643INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3644ar9340Common_rx_gain_table_wasp_1p0,3645ARRAY_LENGTH(ar9340Common_rx_gain_table_wasp_1p0), 2);3646} else if (AR_SREV_SCORPION(ah)) {3647INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3648ar955xCommon_rx_gain_table_scorpion_1p0,3649ARRAY_LENGTH(ar955xCommon_rx_gain_table_scorpion_1p0), 2);3650INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain_bounds,3651ar955xCommon_rx_gain_bounds_scorpion_1p0,3652ARRAY_LENGTH(ar955xCommon_rx_gain_bounds_scorpion_1p0), 5);3653} else if (AR_SREV_HONEYBEE(ah)) {3654INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3655qca953xCommon_rx_gain_table_honeybee_1p0,3656ARRAY_LENGTH(qca953xCommon_rx_gain_table_honeybee_1p0), 2);3657INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain_bounds,3658qca953xCommon_rx_gain_bounds_honeybee_1p0,3659ARRAY_LENGTH(qca953xCommon_rx_gain_bounds_honeybee_1p0), 5);3660} else {3661INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3662ar9300_common_rx_gain_table_osprey_2p2,3663ARRAY_LENGTH(ar9300_common_rx_gain_table_osprey_2p2), 2);3664}3665break;3666case 1:3667if (AR_SREV_HORNET_12(ah)) {3668INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3669ar9331_common_wo_xlna_rx_gain_hornet1_2,3670ARRAY_LENGTH(ar9331_common_wo_xlna_rx_gain_hornet1_2), 2);3671} else if (AR_SREV_HORNET_11(ah)) {3672INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3673ar9331_common_wo_xlna_rx_gain_hornet1_1,3674ARRAY_LENGTH(ar9331_common_wo_xlna_rx_gain_hornet1_1), 2);3675} else if (AR_SREV_POSEIDON_11_OR_LATER(ah)) {3676INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3677ar9485_common_wo_xlna_rx_gain_poseidon1_1,3678ARRAY_LENGTH(ar9485_common_wo_xlna_rx_gain_poseidon1_1), 2);3679} else if (AR_SREV_POSEIDON(ah)) {3680INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3681ar9485Common_wo_xlna_rx_gain_poseidon1_0,3682ARRAY_LENGTH(ar9485Common_wo_xlna_rx_gain_poseidon1_0), 2);3683} else if (AR_SREV_JUPITER_10(ah)) {3684INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3685ar9300_common_wo_xlna_rx_gain_table_jupiter_1p0,3686ARRAY_LENGTH(ar9300_common_wo_xlna_rx_gain_table_jupiter_1p0),36872);3688} else if (AR_SREV_JUPITER_20(ah)) {3689INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3690ar9300Common_wo_xlna_rx_gain_table_jupiter_2p0,3691ARRAY_LENGTH(ar9300Common_wo_xlna_rx_gain_table_jupiter_2p0),36922);3693} else if (AR_SREV_JUPITER_21(ah)) {3694INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3695ar9462_2p1_common_wo_xlna_rx_gain,3696ARRAY_LENGTH(ar9462_2p1_common_wo_xlna_rx_gain),36972);3698} else if (AR_SREV_APHRODITE(ah)) {3699INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3700ar956XCommon_wo_xlna_rx_gain_table_aphrodite_1p0,3701ARRAY_LENGTH(ar956XCommon_wo_xlna_rx_gain_table_aphrodite_1p0),37022);3703} else if (AR_SREV_AR9580(ah)) {3704INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3705ar9300_common_wo_xlna_rx_gain_table_ar9580_1p0,3706ARRAY_LENGTH(ar9300_common_wo_xlna_rx_gain_table_ar9580_1p0), 2);3707} else if (AR_SREV_WASP(ah)) {3708INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3709ar9340Common_wo_xlna_rx_gain_table_wasp_1p0,3710ARRAY_LENGTH(ar9340Common_wo_xlna_rx_gain_table_wasp_1p0), 2);3711} else if (AR_SREV_SCORPION(ah)) {3712INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3713ar955xCommon_wo_xlna_rx_gain_table_scorpion_1p0,3714ARRAY_LENGTH(ar955xCommon_wo_xlna_rx_gain_table_scorpion_1p0), 2);3715INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain_bounds,3716ar955xCommon_wo_xlna_rx_gain_bounds_scorpion_1p0,3717ARRAY_LENGTH(ar955xCommon_wo_xlna_rx_gain_bounds_scorpion_1p0), 5);3718} else if (AR_SREV_HONEYBEE(ah)) {3719INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3720qca953xCommon_wo_xlna_rx_gain_table_honeybee_1p0,3721ARRAY_LENGTH(qca953xCommon_wo_xlna_rx_gain_table_honeybee_1p0), 2);3722INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain_bounds,3723qca953xCommon_wo_xlna_rx_gain_bounds_honeybee_1p0,3724ARRAY_LENGTH(qca953xCommon_wo_xlna_rx_gain_bounds_honeybee_1p0), 5);3725} else {3726INIT_INI_ARRAY(&ahp->ah_ini_modes_rxgain,3727ar9300Common_wo_xlna_rx_gain_table_osprey_2p2,3728ARRAY_LENGTH(ar9300Common_wo_xlna_rx_gain_table_osprey_2p2), 2);3729}3730break;3731}3732}37333734void ar9300_tx_gain_table_apply(struct ath_hal *ah)3735{3736struct ath_hal_9300 *ahp = AH9300(ah);37373738switch (ar9300_tx_gain_index_get(ah))3739{3740case 0:3741default:3742if (AR_SREV_HORNET_12(ah)) {3743INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3744ar9331_modes_lowest_ob_db_tx_gain_hornet1_2,3745ARRAY_LENGTH(ar9331_modes_lowest_ob_db_tx_gain_hornet1_2), 5);3746} else if (AR_SREV_HORNET_11(ah)) {3747INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3748ar9331_modes_lowest_ob_db_tx_gain_hornet1_1,3749ARRAY_LENGTH(ar9331_modes_lowest_ob_db_tx_gain_hornet1_1), 5);3750} else if (AR_SREV_POSEIDON_11_OR_LATER(ah)) {3751INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3752ar9485_modes_lowest_ob_db_tx_gain_poseidon1_1,3753ARRAY_LENGTH(ar9485_modes_lowest_ob_db_tx_gain_poseidon1_1), 5);3754} else if (AR_SREV_POSEIDON(ah)) {3755INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3756ar9485Modes_lowest_ob_db_tx_gain_poseidon1_0,3757ARRAY_LENGTH(ar9485Modes_lowest_ob_db_tx_gain_poseidon1_0), 5);3758} else if (AR_SREV_AR9580(ah)) {3759INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3760ar9300Modes_lowest_ob_db_tx_gain_table_ar9580_1p0,3761ARRAY_LENGTH(ar9300Modes_lowest_ob_db_tx_gain_table_ar9580_1p0),37625);3763} else if (AR_SREV_WASP(ah)) {3764INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3765ar9340Modes_lowest_ob_db_tx_gain_table_wasp_1p0,3766ARRAY_LENGTH(ar9340Modes_lowest_ob_db_tx_gain_table_wasp_1p0),37675);3768} else if (AR_SREV_SCORPION(ah)) {3769INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3770ar955xModes_xpa_tx_gain_table_scorpion_1p0,3771ARRAY_LENGTH(ar955xModes_xpa_tx_gain_table_scorpion_1p0),37729);3773} else if (AR_SREV_JUPITER_10(ah)) {3774INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3775ar9300_modes_low_ob_db_tx_gain_table_jupiter_1p0,3776ARRAY_LENGTH(ar9300_modes_low_ob_db_tx_gain_table_jupiter_1p0),37775);3778} else if (AR_SREV_JUPITER_20(ah)) {3779INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3780ar9300Modes_low_ob_db_tx_gain_table_jupiter_2p0,3781ARRAY_LENGTH(ar9300Modes_low_ob_db_tx_gain_table_jupiter_2p0),37825);3783} else if (AR_SREV_JUPITER_21(ah)) {3784INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3785ar9462_2p1_modes_low_ob_db_tx_gain,3786ARRAY_LENGTH(ar9462_2p1_modes_low_ob_db_tx_gain),37875);3788} else if (AR_SREV_HONEYBEE(ah)) {3789INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3790qca953xModes_xpa_tx_gain_table_honeybee_1p0,3791ARRAY_LENGTH(qca953xModes_xpa_tx_gain_table_honeybee_1p0),37922);3793} else if (AR_SREV_APHRODITE(ah)) {3794INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3795ar956XModes_low_ob_db_tx_gain_table_aphrodite_1p0,3796ARRAY_LENGTH(ar956XModes_low_ob_db_tx_gain_table_aphrodite_1p0),37975);3798} else {3799INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3800ar9300_modes_lowest_ob_db_tx_gain_table_osprey_2p2,3801ARRAY_LENGTH(ar9300_modes_lowest_ob_db_tx_gain_table_osprey_2p2),38025);3803}3804break;3805case 1:3806if (AR_SREV_HORNET_12(ah)) {3807INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3808ar9331_modes_high_ob_db_tx_gain_hornet1_2,3809ARRAY_LENGTH(ar9331_modes_high_ob_db_tx_gain_hornet1_2), 5);3810} else if (AR_SREV_HORNET_11(ah)) {3811INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3812ar9331_modes_high_ob_db_tx_gain_hornet1_1,3813ARRAY_LENGTH(ar9331_modes_high_ob_db_tx_gain_hornet1_1), 5);3814} else if (AR_SREV_POSEIDON_11_OR_LATER(ah)) {3815INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3816ar9485_modes_high_ob_db_tx_gain_poseidon1_1,3817ARRAY_LENGTH(ar9485_modes_high_ob_db_tx_gain_poseidon1_1), 5);3818} else if (AR_SREV_POSEIDON(ah)) {3819INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3820ar9485Modes_high_ob_db_tx_gain_poseidon1_0,3821ARRAY_LENGTH(ar9485Modes_high_ob_db_tx_gain_poseidon1_0), 5);3822} else if (AR_SREV_AR9580(ah)) {3823INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3824ar9300Modes_high_ob_db_tx_gain_table_ar9580_1p0,3825ARRAY_LENGTH(ar9300Modes_high_ob_db_tx_gain_table_ar9580_1p0),38265);3827} else if (AR_SREV_WASP(ah)) {3828INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3829ar9340Modes_high_ob_db_tx_gain_table_wasp_1p0,3830ARRAY_LENGTH(ar9340Modes_high_ob_db_tx_gain_table_wasp_1p0), 5);3831} else if (AR_SREV_SCORPION(ah)) {3832INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3833ar955xModes_no_xpa_tx_gain_table_scorpion_1p0,3834ARRAY_LENGTH(ar955xModes_no_xpa_tx_gain_table_scorpion_1p0), 9);3835} else if (AR_SREV_JUPITER_10(ah)) {3836INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3837ar9300_modes_high_ob_db_tx_gain_table_jupiter_1p0,3838ARRAY_LENGTH(3839ar9300_modes_high_ob_db_tx_gain_table_jupiter_1p0), 5);3840} else if (AR_SREV_JUPITER_20(ah)) {3841INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3842ar9300Modes_high_ob_db_tx_gain_table_jupiter_2p0,3843ARRAY_LENGTH(3844ar9300Modes_high_ob_db_tx_gain_table_jupiter_2p0), 5);3845} else if (AR_SREV_JUPITER_21(ah)) {3846INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3847ar9462_2p1_modes_high_ob_db_tx_gain,3848ARRAY_LENGTH(3849ar9462_2p1_modes_high_ob_db_tx_gain), 5);3850} else if (AR_SREV_APHRODITE(ah)) {3851INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3852ar956XModes_high_ob_db_tx_gain_table_aphrodite_1p0,3853ARRAY_LENGTH(3854ar956XModes_high_ob_db_tx_gain_table_aphrodite_1p0), 5);3855} else if (AR_SREV_HONEYBEE(ah)) {3856if (AR_SREV_HONEYBEE_11(ah)) {3857INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3858qca953xModes_no_xpa_tx_gain_table_honeybee_1p1,3859ARRAY_LENGTH(qca953xModes_no_xpa_tx_gain_table_honeybee_1p1), 2);3860} else {3861INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3862qca953xModes_no_xpa_tx_gain_table_honeybee_1p0,3863ARRAY_LENGTH(qca953xModes_no_xpa_tx_gain_table_honeybee_1p0), 2);3864}3865} else {3866INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3867ar9300Modes_high_ob_db_tx_gain_table_osprey_2p2,3868ARRAY_LENGTH(ar9300Modes_high_ob_db_tx_gain_table_osprey_2p2),38695);3870}3871break;3872case 2:3873if (AR_SREV_HORNET_12(ah)) {3874INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3875ar9331_modes_low_ob_db_tx_gain_hornet1_2,3876ARRAY_LENGTH(ar9331_modes_low_ob_db_tx_gain_hornet1_2), 5);3877} else if (AR_SREV_HORNET_11(ah)) {3878INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3879ar9331_modes_low_ob_db_tx_gain_hornet1_1,3880ARRAY_LENGTH(ar9331_modes_low_ob_db_tx_gain_hornet1_1), 5);3881} else if (AR_SREV_POSEIDON_11_OR_LATER(ah)) {3882INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3883ar9485_modes_low_ob_db_tx_gain_poseidon1_1,3884ARRAY_LENGTH(ar9485_modes_low_ob_db_tx_gain_poseidon1_1), 5);3885} else if (AR_SREV_POSEIDON(ah)) {3886INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3887ar9485Modes_low_ob_db_tx_gain_poseidon1_0,3888ARRAY_LENGTH(ar9485Modes_low_ob_db_tx_gain_poseidon1_0), 5);3889} else if (AR_SREV_AR9580(ah)) {3890INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3891ar9300Modes_low_ob_db_tx_gain_table_ar9580_1p0,3892ARRAY_LENGTH(ar9300Modes_low_ob_db_tx_gain_table_ar9580_1p0),38935);3894} else if (AR_SREV_WASP(ah)) {3895INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3896ar9340Modes_low_ob_db_tx_gain_table_wasp_1p0,3897ARRAY_LENGTH(ar9340Modes_low_ob_db_tx_gain_table_wasp_1p0), 5);3898} else if (AR_SREV_APHRODITE(ah)) {3899INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3900ar956XModes_low_ob_db_tx_gain_table_aphrodite_1p0,3901ARRAY_LENGTH(ar956XModes_low_ob_db_tx_gain_table_aphrodite_1p0), 5);3902} else {3903INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3904ar9300Modes_low_ob_db_tx_gain_table_osprey_2p2,3905ARRAY_LENGTH(ar9300Modes_low_ob_db_tx_gain_table_osprey_2p2),39065);3907}3908break;3909case 3:3910if (AR_SREV_HORNET_12(ah)) {3911INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3912ar9331_modes_high_power_tx_gain_hornet1_2,3913ARRAY_LENGTH(ar9331_modes_high_power_tx_gain_hornet1_2), 5);3914} else if (AR_SREV_HORNET_11(ah)) {3915INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3916ar9331_modes_high_power_tx_gain_hornet1_1,3917ARRAY_LENGTH(ar9331_modes_high_power_tx_gain_hornet1_1), 5);3918} else if (AR_SREV_POSEIDON_11_OR_LATER(ah)) {3919INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3920ar9485_modes_high_power_tx_gain_poseidon1_1,3921ARRAY_LENGTH(ar9485_modes_high_power_tx_gain_poseidon1_1), 5);3922} else if (AR_SREV_POSEIDON(ah)) {3923INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3924ar9485Modes_high_power_tx_gain_poseidon1_0,3925ARRAY_LENGTH(ar9485Modes_high_power_tx_gain_poseidon1_0), 5);3926} else if (AR_SREV_AR9580(ah)) {3927INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3928ar9300Modes_high_power_tx_gain_table_ar9580_1p0,3929ARRAY_LENGTH(ar9300Modes_high_power_tx_gain_table_ar9580_1p0),39305);3931} else if (AR_SREV_WASP(ah)) {3932INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3933ar9340Modes_high_power_tx_gain_table_wasp_1p0,3934ARRAY_LENGTH(ar9340Modes_high_power_tx_gain_table_wasp_1p0),39355);3936} else if (AR_SREV_APHRODITE(ah)) {3937INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3938ar956XModes_high_power_tx_gain_table_aphrodite_1p0,3939ARRAY_LENGTH(ar956XModes_high_power_tx_gain_table_aphrodite_1p0), 5);3940} else {3941INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3942ar9300Modes_high_power_tx_gain_table_osprey_2p2,3943ARRAY_LENGTH(ar9300Modes_high_power_tx_gain_table_osprey_2p2),39445);3945}3946break;3947case 4:3948if (AR_SREV_WASP(ah)) {3949INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3950ar9340Modes_mixed_ob_db_tx_gain_table_wasp_1p0,3951ARRAY_LENGTH(ar9340Modes_mixed_ob_db_tx_gain_table_wasp_1p0),39525);3953} else if (AR_SREV_AR9580(ah)) {3954INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3955ar9300_modes_mixed_ob_db_tx_gain_table_ar9580_1p0,3956ARRAY_LENGTH(ar9300_modes_mixed_ob_db_tx_gain_table_ar9580_1p0),39575);3958} else {3959INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3960ar9300Modes_mixed_ob_db_tx_gain_table_osprey_2p2,3961ARRAY_LENGTH(ar9300Modes_mixed_ob_db_tx_gain_table_osprey_2p2),39625);3963}3964break;3965case 5:3966/* HW Green TX */3967if (AR_SREV_POSEIDON(ah)) {3968if (AR_SREV_POSEIDON_11_OR_LATER(ah)) {3969INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3970ar9485_modes_green_ob_db_tx_gain_poseidon1_1,3971sizeof(ar9485_modes_green_ob_db_tx_gain_poseidon1_1) /3972sizeof(ar9485_modes_green_ob_db_tx_gain_poseidon1_1[0]), 5);3973} else {3974INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3975ar9485_modes_green_ob_db_tx_gain_poseidon1_0,3976sizeof(ar9485_modes_green_ob_db_tx_gain_poseidon1_0) /3977sizeof(ar9485_modes_green_ob_db_tx_gain_poseidon1_0[0]), 5);3978}3979ahp->ah_hw_green_tx_enable = 1;3980}3981else if (AR_SREV_WASP(ah)) {3982INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3983ar9340_modes_ub124_tx_gain_table_wasp_1p0,3984sizeof(ar9340_modes_ub124_tx_gain_table_wasp_1p0) /3985sizeof(ar9340_modes_ub124_tx_gain_table_wasp_1p0[0]), 5);3986}3987else if (AR_SREV_AR9580(ah)) {3988INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3989ar9300_modes_type5_tx_gain_table_ar9580_1p0,3990ARRAY_LENGTH( ar9300_modes_type5_tx_gain_table_ar9580_1p0),39915);3992}3993else if (AR_SREV_OSPREY_22(ah)) {3994INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,3995ar9300_modes_number_5_tx_gain_table_osprey_2p2,3996ARRAY_LENGTH( ar9300_modes_number_5_tx_gain_table_osprey_2p2),39975);3998}3999break;4000case 6:4001if (AR_SREV_WASP(ah)) {4002INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,4003ar9340_modes_low_ob_db_and_spur_tx_gain_table_wasp_1p0,4004sizeof(ar9340_modes_low_ob_db_and_spur_tx_gain_table_wasp_1p0) /4005sizeof(ar9340_modes_low_ob_db_and_spur_tx_gain_table_wasp_1p0[0]), 5);4006}4007/* HW Green TX */4008else if (AR_SREV_POSEIDON(ah)) {4009if (AR_SREV_POSEIDON_11_OR_LATER(ah)) {4010INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,4011ar9485_modes_green_spur_ob_db_tx_gain_poseidon1_1,4012sizeof(ar9485_modes_green_spur_ob_db_tx_gain_poseidon1_1) /4013sizeof(ar9485_modes_green_spur_ob_db_tx_gain_poseidon1_1[0]),40145);4015}4016ahp->ah_hw_green_tx_enable = 1;4017}4018else if (AR_SREV_AR9580(ah)) {4019INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,4020ar9300_modes_type6_tx_gain_table_ar9580_1p0,4021ARRAY_LENGTH( ar9300_modes_type6_tx_gain_table_ar9580_1p0),40225);4023}4024break;4025case 7:4026if (AR_SREV_WASP(ah)) {4027INIT_INI_ARRAY(&ahp->ah_ini_modes_txgain,4028ar9340Modes_cus227_tx_gain_table_wasp_1p0,4029sizeof(ar9340Modes_cus227_tx_gain_table_wasp_1p0) /4030sizeof(ar9340Modes_cus227_tx_gain_table_wasp_1p0[0]), 5);4031}4032break;4033}4034}40354036#if ATH_ANT_DIV_COMB4037void4038ar9300_ant_div_comb_get_config(struct ath_hal *ah,4039HAL_ANT_COMB_CONFIG *div_comb_conf)4040{4041u_int32_t reg_val = OS_REG_READ(ah, AR_PHY_MC_GAIN_CTRL);4042div_comb_conf->main_lna_conf =4043MULTICHAIN_GAIN_CTRL__ANT_DIV_MAIN_LNACONF__READ(reg_val);4044div_comb_conf->alt_lna_conf =4045MULTICHAIN_GAIN_CTRL__ANT_DIV_ALT_LNACONF__READ(reg_val);4046div_comb_conf->fast_div_bias =4047MULTICHAIN_GAIN_CTRL__ANT_FAST_DIV_BIAS__READ(reg_val);4048if (AR_SREV_HORNET_11(ah)) {4049div_comb_conf->antdiv_configgroup = HAL_ANTDIV_CONFIG_GROUP_1;4050} else if (AR_SREV_POSEIDON_11_OR_LATER(ah)) {4051div_comb_conf->antdiv_configgroup = HAL_ANTDIV_CONFIG_GROUP_2;4052} else {4053div_comb_conf->antdiv_configgroup = DEFAULT_ANTDIV_CONFIG_GROUP;4054}40554056/*4057* XXX TODO: allow the HAL to override the rssithres and fast_div_bias4058* values (eg CUS198.)4059*/4060}40614062void4063ar9300_ant_div_comb_set_config(struct ath_hal *ah,4064HAL_ANT_COMB_CONFIG *div_comb_conf)4065{4066u_int32_t reg_val;4067struct ath_hal_9300 *ahp = AH9300(ah);40684069/* DO NOTHING when set to fixed antenna for manufacturing purpose */4070if (AR_SREV_POSEIDON(ah) && ( ahp->ah_diversity_control == HAL_ANT_FIXED_A4071|| ahp->ah_diversity_control == HAL_ANT_FIXED_B)) {4072return;4073}4074reg_val = OS_REG_READ(ah, AR_PHY_MC_GAIN_CTRL);4075reg_val &= ~(MULTICHAIN_GAIN_CTRL__ANT_DIV_MAIN_LNACONF__MASK |4076MULTICHAIN_GAIN_CTRL__ANT_DIV_ALT_LNACONF__MASK |4077MULTICHAIN_GAIN_CTRL__ANT_FAST_DIV_BIAS__MASK |4078MULTICHAIN_GAIN_CTRL__ANT_DIV_MAIN_GAINTB__MASK |4079MULTICHAIN_GAIN_CTRL__ANT_DIV_ALT_GAINTB__MASK );4080reg_val |=4081MULTICHAIN_GAIN_CTRL__ANT_DIV_MAIN_GAINTB__WRITE(4082div_comb_conf->main_gaintb);4083reg_val |=4084MULTICHAIN_GAIN_CTRL__ANT_DIV_ALT_GAINTB__WRITE(4085div_comb_conf->alt_gaintb);4086reg_val |=4087MULTICHAIN_GAIN_CTRL__ANT_DIV_MAIN_LNACONF__WRITE(4088div_comb_conf->main_lna_conf);4089reg_val |=4090MULTICHAIN_GAIN_CTRL__ANT_DIV_ALT_LNACONF__WRITE(4091div_comb_conf->alt_lna_conf);4092reg_val |=4093MULTICHAIN_GAIN_CTRL__ANT_FAST_DIV_BIAS__WRITE(4094div_comb_conf->fast_div_bias);4095OS_REG_WRITE(ah, AR_PHY_MC_GAIN_CTRL, reg_val);40964097}4098#endif /* ATH_ANT_DIV_COMB */40994100static void4101ar9300_init_hostif_offsets(struct ath_hal *ah)4102{4103AR_HOSTIF_REG(ah, AR_RC) =4104AR9300_HOSTIF_OFFSET(HOST_INTF_RESET_CONTROL);4105AR_HOSTIF_REG(ah, AR_WA) =4106AR9300_HOSTIF_OFFSET(HOST_INTF_WORK_AROUND);4107AR_HOSTIF_REG(ah, AR_PM_STATE) =4108AR9300_HOSTIF_OFFSET(HOST_INTF_PM_STATE);4109AR_HOSTIF_REG(ah, AR_H_INFOL) =4110AR9300_HOSTIF_OFFSET(HOST_INTF_CXPL_DEBUG_INFOL);4111AR_HOSTIF_REG(ah, AR_H_INFOH) =4112AR9300_HOSTIF_OFFSET(HOST_INTF_CXPL_DEBUG_INFOH);4113AR_HOSTIF_REG(ah, AR_PCIE_PM_CTRL) =4114AR9300_HOSTIF_OFFSET(HOST_INTF_PM_CTRL);4115AR_HOSTIF_REG(ah, AR_HOST_TIMEOUT) =4116AR9300_HOSTIF_OFFSET(HOST_INTF_TIMEOUT);4117AR_HOSTIF_REG(ah, AR_EEPROM) =4118AR9300_HOSTIF_OFFSET(HOST_INTF_EEPROM_CTRL);4119AR_HOSTIF_REG(ah, AR_SREV) =4120AR9300_HOSTIF_OFFSET(HOST_INTF_SREV);4121AR_HOSTIF_REG(ah, AR_INTR_SYNC_CAUSE) =4122AR9300_HOSTIF_OFFSET(HOST_INTF_INTR_SYNC_CAUSE);4123AR_HOSTIF_REG(ah, AR_INTR_SYNC_CAUSE_CLR) =4124AR9300_HOSTIF_OFFSET(HOST_INTF_INTR_SYNC_CAUSE);4125AR_HOSTIF_REG(ah, AR_INTR_SYNC_ENABLE) =4126AR9300_HOSTIF_OFFSET(HOST_INTF_INTR_SYNC_ENABLE);4127AR_HOSTIF_REG(ah, AR_INTR_ASYNC_MASK) =4128AR9300_HOSTIF_OFFSET(HOST_INTF_INTR_ASYNC_MASK);4129AR_HOSTIF_REG(ah, AR_INTR_SYNC_MASK) =4130AR9300_HOSTIF_OFFSET(HOST_INTF_INTR_SYNC_MASK);4131AR_HOSTIF_REG(ah, AR_INTR_ASYNC_CAUSE_CLR) =4132AR9300_HOSTIF_OFFSET(HOST_INTF_INTR_ASYNC_CAUSE);4133AR_HOSTIF_REG(ah, AR_INTR_ASYNC_CAUSE) =4134AR9300_HOSTIF_OFFSET(HOST_INTF_INTR_ASYNC_CAUSE);4135AR_HOSTIF_REG(ah, AR_INTR_ASYNC_ENABLE) =4136AR9300_HOSTIF_OFFSET(HOST_INTF_INTR_ASYNC_ENABLE);4137AR_HOSTIF_REG(ah, AR_PCIE_SERDES) =4138AR9300_HOSTIF_OFFSET(HOST_INTF_PCIE_PHY_RW);4139AR_HOSTIF_REG(ah, AR_PCIE_SERDES2) =4140AR9300_HOSTIF_OFFSET(HOST_INTF_PCIE_PHY_LOAD);4141AR_HOSTIF_REG(ah, AR_GPIO_OUT) =4142AR9300_HOSTIF_OFFSET(HOST_INTF_GPIO_OUT);4143AR_HOSTIF_REG(ah, AR_GPIO_IN) =4144AR9300_HOSTIF_OFFSET(HOST_INTF_GPIO_IN);4145AR_HOSTIF_REG(ah, AR_GPIO_OE_OUT) =4146AR9300_HOSTIF_OFFSET(HOST_INTF_GPIO_OE);4147AR_HOSTIF_REG(ah, AR_GPIO_OE1_OUT) =4148AR9300_HOSTIF_OFFSET(HOST_INTF_GPIO_OE1);4149AR_HOSTIF_REG(ah, AR_GPIO_INTR_POL) =4150AR9300_HOSTIF_OFFSET(HOST_INTF_GPIO_INTR_POLAR);4151AR_HOSTIF_REG(ah, AR_GPIO_INPUT_EN_VAL) =4152AR9300_HOSTIF_OFFSET(HOST_INTF_GPIO_INPUT_VALUE);4153AR_HOSTIF_REG(ah, AR_GPIO_INPUT_MUX1) =4154AR9300_HOSTIF_OFFSET(HOST_INTF_GPIO_INPUT_MUX1);4155AR_HOSTIF_REG(ah, AR_GPIO_INPUT_MUX2) =4156AR9300_HOSTIF_OFFSET(HOST_INTF_GPIO_INPUT_MUX2);4157AR_HOSTIF_REG(ah, AR_GPIO_OUTPUT_MUX1) =4158AR9300_HOSTIF_OFFSET(HOST_INTF_GPIO_OUTPUT_MUX1);4159AR_HOSTIF_REG(ah, AR_GPIO_OUTPUT_MUX2) =4160AR9300_HOSTIF_OFFSET(HOST_INTF_GPIO_OUTPUT_MUX2);4161AR_HOSTIF_REG(ah, AR_GPIO_OUTPUT_MUX3) =4162AR9300_HOSTIF_OFFSET(HOST_INTF_GPIO_OUTPUT_MUX3);4163AR_HOSTIF_REG(ah, AR_INPUT_STATE) =4164AR9300_HOSTIF_OFFSET(HOST_INTF_GPIO_INPUT_STATE);4165AR_HOSTIF_REG(ah, AR_SPARE) =4166AR9300_HOSTIF_OFFSET(HOST_INTF_SPARE);4167AR_HOSTIF_REG(ah, AR_PCIE_CORE_RESET_EN) =4168AR9300_HOSTIF_OFFSET(HOST_INTF_PCIE_CORE_RST_EN);4169AR_HOSTIF_REG(ah, AR_CLKRUN) =4170AR9300_HOSTIF_OFFSET(HOST_INTF_CLKRUN);4171AR_HOSTIF_REG(ah, AR_EEPROM_STATUS_DATA) =4172AR9300_HOSTIF_OFFSET(HOST_INTF_EEPROM_STS);4173AR_HOSTIF_REG(ah, AR_OBS) =4174AR9300_HOSTIF_OFFSET(HOST_INTF_OBS_CTRL);4175AR_HOSTIF_REG(ah, AR_RFSILENT) =4176AR9300_HOSTIF_OFFSET(HOST_INTF_RFSILENT);4177AR_HOSTIF_REG(ah, AR_GPIO_PDPU) =4178AR9300_HOSTIF_OFFSET(HOST_INTF_GPIO_PDPU);4179AR_HOSTIF_REG(ah, AR_GPIO_DS) =4180AR9300_HOSTIF_OFFSET(HOST_INTF_GPIO_DS);4181AR_HOSTIF_REG(ah, AR_MISC) =4182AR9300_HOSTIF_OFFSET(HOST_INTF_MISC);4183AR_HOSTIF_REG(ah, AR_PCIE_MSI) =4184AR9300_HOSTIF_OFFSET(HOST_INTF_PCIE_MSI);4185#if 0 /* Offsets are not defined in reg_map structure */4186AR_HOSTIF_REG(ah, AR_TSF_SNAPSHOT_BT_ACTIVE) =4187AR9300_HOSTIF_OFFSET(HOST_INTF_TSF_SNAPSHOT_BT_ACTIVE);4188AR_HOSTIF_REG(ah, AR_TSF_SNAPSHOT_BT_PRIORITY) =4189AR9300_HOSTIF_OFFSET(HOST_INTF_TSF_SNAPSHOT_BT_PRIORITY);4190AR_HOSTIF_REG(ah, AR_TSF_SNAPSHOT_BT_CNTL) =4191AR9300_HOSTIF_OFFSET(HOST_INTF_MAC_TSF_SNAPSHOT_BT_CNTL);4192#endif4193AR_HOSTIF_REG(ah, AR_PCIE_PHY_LATENCY_NFTS_ADJ) =4194AR9300_HOSTIF_OFFSET(HOST_INTF_PCIE_PHY_LATENCY_NFTS_ADJ);4195AR_HOSTIF_REG(ah, AR_TDMA_CCA_CNTL) =4196AR9300_HOSTIF_OFFSET(HOST_INTF_MAC_TDMA_CCA_CNTL);4197AR_HOSTIF_REG(ah, AR_TXAPSYNC) =4198AR9300_HOSTIF_OFFSET(HOST_INTF_MAC_TXAPSYNC);4199AR_HOSTIF_REG(ah, AR_TXSYNC_INIT_SYNC_TMR) =4200AR9300_HOSTIF_OFFSET(HOST_INTF_MAC_TXSYNC_INITIAL_SYNC_TMR);4201AR_HOSTIF_REG(ah, AR_INTR_PRIO_SYNC_CAUSE) =4202AR9300_HOSTIF_OFFSET(HOST_INTF_INTR_PRIORITY_SYNC_CAUSE);4203AR_HOSTIF_REG(ah, AR_INTR_PRIO_SYNC_ENABLE) =4204AR9300_HOSTIF_OFFSET(HOST_INTF_INTR_PRIORITY_SYNC_ENABLE);4205AR_HOSTIF_REG(ah, AR_INTR_PRIO_ASYNC_MASK) =4206AR9300_HOSTIF_OFFSET(HOST_INTF_INTR_PRIORITY_ASYNC_MASK);4207AR_HOSTIF_REG(ah, AR_INTR_PRIO_SYNC_MASK) =4208AR9300_HOSTIF_OFFSET(HOST_INTF_INTR_PRIORITY_SYNC_MASK);4209AR_HOSTIF_REG(ah, AR_INTR_PRIO_ASYNC_CAUSE) =4210AR9300_HOSTIF_OFFSET(HOST_INTF_INTR_PRIORITY_ASYNC_CAUSE);4211AR_HOSTIF_REG(ah, AR_INTR_PRIO_ASYNC_ENABLE) =4212AR9300_HOSTIF_OFFSET(HOST_INTF_INTR_PRIORITY_ASYNC_ENABLE);4213}42144215static void4216ar9340_init_hostif_offsets(struct ath_hal *ah)4217{4218AR_HOSTIF_REG(ah, AR_RC) =4219AR9340_HOSTIF_OFFSET(HOST_INTF_RESET_CONTROL);4220AR_HOSTIF_REG(ah, AR_WA) =4221AR9340_HOSTIF_OFFSET(HOST_INTF_WORK_AROUND);4222AR_HOSTIF_REG(ah, AR_PCIE_PM_CTRL) =4223AR9340_HOSTIF_OFFSET(HOST_INTF_PM_CTRL);4224AR_HOSTIF_REG(ah, AR_HOST_TIMEOUT) =4225AR9340_HOSTIF_OFFSET(HOST_INTF_TIMEOUT);4226AR_HOSTIF_REG(ah, AR_SREV) =4227AR9340_HOSTIF_OFFSET(HOST_INTF_SREV);4228AR_HOSTIF_REG(ah, AR_INTR_SYNC_CAUSE) =4229AR9340_HOSTIF_OFFSET(HOST_INTF_INTR_SYNC_CAUSE);4230AR_HOSTIF_REG(ah, AR_INTR_SYNC_CAUSE_CLR) =4231AR9340_HOSTIF_OFFSET(HOST_INTF_INTR_SYNC_CAUSE);4232AR_HOSTIF_REG(ah, AR_INTR_SYNC_ENABLE) =4233AR9340_HOSTIF_OFFSET(HOST_INTF_INTR_SYNC_ENABLE);4234AR_HOSTIF_REG(ah, AR_INTR_ASYNC_MASK) =4235AR9340_HOSTIF_OFFSET(HOST_INTF_INTR_ASYNC_MASK);4236AR_HOSTIF_REG(ah, AR_INTR_SYNC_MASK) =4237AR9340_HOSTIF_OFFSET(HOST_INTF_INTR_SYNC_MASK);4238AR_HOSTIF_REG(ah, AR_INTR_ASYNC_CAUSE_CLR) =4239AR9340_HOSTIF_OFFSET(HOST_INTF_INTR_ASYNC_CAUSE);4240AR_HOSTIF_REG(ah, AR_INTR_ASYNC_CAUSE) =4241AR9340_HOSTIF_OFFSET(HOST_INTF_INTR_ASYNC_CAUSE);4242AR_HOSTIF_REG(ah, AR_INTR_ASYNC_ENABLE) =4243AR9340_HOSTIF_OFFSET(HOST_INTF_INTR_ASYNC_ENABLE);4244AR_HOSTIF_REG(ah, AR_GPIO_OUT) =4245AR9340_HOSTIF_OFFSET(HOST_INTF_GPIO_OUT);4246AR_HOSTIF_REG(ah, AR_GPIO_IN) =4247AR9340_HOSTIF_OFFSET(HOST_INTF_GPIO_IN);4248AR_HOSTIF_REG(ah, AR_GPIO_OE_OUT) =4249AR9340_HOSTIF_OFFSET(HOST_INTF_GPIO_OE);4250AR_HOSTIF_REG(ah, AR_GPIO_OE1_OUT) =4251AR9340_HOSTIF_OFFSET(HOST_INTF_GPIO_OE1);4252AR_HOSTIF_REG(ah, AR_GPIO_INTR_POL) =4253AR9340_HOSTIF_OFFSET(HOST_INTF_GPIO_INTR_POLAR);4254AR_HOSTIF_REG(ah, AR_GPIO_INPUT_EN_VAL) =4255AR9340_HOSTIF_OFFSET(HOST_INTF_GPIO_INPUT_VALUE);4256AR_HOSTIF_REG(ah, AR_GPIO_INPUT_MUX1) =4257AR9340_HOSTIF_OFFSET(HOST_INTF_GPIO_INPUT_MUX1);4258AR_HOSTIF_REG(ah, AR_GPIO_INPUT_MUX2) =4259AR9340_HOSTIF_OFFSET(HOST_INTF_GPIO_INPUT_MUX2);4260AR_HOSTIF_REG(ah, AR_GPIO_OUTPUT_MUX1) =4261AR9340_HOSTIF_OFFSET(HOST_INTF_GPIO_OUTPUT_MUX1);4262AR_HOSTIF_REG(ah, AR_GPIO_OUTPUT_MUX2) =4263AR9340_HOSTIF_OFFSET(HOST_INTF_GPIO_OUTPUT_MUX2);4264AR_HOSTIF_REG(ah, AR_GPIO_OUTPUT_MUX3) =4265AR9340_HOSTIF_OFFSET(HOST_INTF_GPIO_OUTPUT_MUX3);4266AR_HOSTIF_REG(ah, AR_INPUT_STATE) =4267AR9340_HOSTIF_OFFSET(HOST_INTF_GPIO_INPUT_STATE);4268AR_HOSTIF_REG(ah, AR_CLKRUN) =4269AR9340_HOSTIF_OFFSET(HOST_INTF_CLKRUN);4270AR_HOSTIF_REG(ah, AR_EEPROM_STATUS_DATA) =4271AR9340_HOSTIF_OFFSET(HOST_INTF_EEPROM_STS);4272AR_HOSTIF_REG(ah, AR_OBS) =4273AR9340_HOSTIF_OFFSET(HOST_INTF_OBS_CTRL);4274AR_HOSTIF_REG(ah, AR_RFSILENT) =4275AR9340_HOSTIF_OFFSET(HOST_INTF_RFSILENT);4276AR_HOSTIF_REG(ah, AR_MISC) =4277AR9340_HOSTIF_OFFSET(HOST_INTF_MISC);4278AR_HOSTIF_REG(ah, AR_PCIE_MSI) =4279AR9340_HOSTIF_OFFSET(HOST_INTF_PCIE_MSI);4280AR_HOSTIF_REG(ah, AR_TDMA_CCA_CNTL) =4281AR9340_HOSTIF_OFFSET(HOST_INTF_MAC_TDMA_CCA_CNTL);4282AR_HOSTIF_REG(ah, AR_TXAPSYNC) =4283AR9340_HOSTIF_OFFSET(HOST_INTF_MAC_TXAPSYNC);4284AR_HOSTIF_REG(ah, AR_TXSYNC_INIT_SYNC_TMR) =4285AR9340_HOSTIF_OFFSET(HOST_INTF_MAC_TXSYNC_INITIAL_SYNC_TMR);4286AR_HOSTIF_REG(ah, AR_INTR_PRIO_SYNC_CAUSE) =4287AR9340_HOSTIF_OFFSET(HOST_INTF_INTR_PRIORITY_SYNC_CAUSE);4288AR_HOSTIF_REG(ah, AR_INTR_PRIO_SYNC_ENABLE) =4289AR9340_HOSTIF_OFFSET(HOST_INTF_INTR_PRIORITY_SYNC_ENABLE);4290AR_HOSTIF_REG(ah, AR_INTR_PRIO_ASYNC_MASK) =4291AR9340_HOSTIF_OFFSET(HOST_INTF_INTR_PRIORITY_ASYNC_MASK);4292AR_HOSTIF_REG(ah, AR_INTR_PRIO_SYNC_MASK) =4293AR9340_HOSTIF_OFFSET(HOST_INTF_INTR_PRIORITY_SYNC_MASK);4294AR_HOSTIF_REG(ah, AR_INTR_PRIO_ASYNC_CAUSE) =4295AR9340_HOSTIF_OFFSET(HOST_INTF_INTR_PRIORITY_ASYNC_CAUSE);4296AR_HOSTIF_REG(ah, AR_INTR_PRIO_ASYNC_ENABLE) =4297AR9340_HOSTIF_OFFSET(HOST_INTF_INTR_PRIORITY_ASYNC_ENABLE);4298}42994300/*4301* Host interface register offsets are different for Osprey and Wasp4302* and hence store the offsets in hal structure4303*/4304static int ar9300_init_offsets(struct ath_hal *ah, u_int16_t devid)4305{4306if (devid == AR9300_DEVID_AR9340) {4307ar9340_init_hostif_offsets(ah);4308} else {4309ar9300_init_hostif_offsets(ah);4310}4311return 0;4312}431343144315static const char*4316ar9300_probe(uint16_t vendorid, uint16_t devid)4317{4318if (vendorid != ATHEROS_VENDOR_ID)4319return AH_NULL;43204321switch (devid) {4322case AR9300_DEVID_AR9380_PCIE: /* PCIE (Osprey) */4323return "Atheros AR938x";4324case AR9300_DEVID_AR9340: /* Wasp */4325return "Atheros AR934x";4326case AR9300_DEVID_AR9485_PCIE: /* Poseidon */4327return "Atheros AR9485";4328case AR9300_DEVID_AR9580_PCIE: /* Peacock */4329return "Atheros AR9580";4330case AR9300_DEVID_AR946X_PCIE: /* AR9462, AR9463, AR9482 */4331return "Atheros AR946x/AR948x";4332case AR9300_DEVID_AR9330: /* Hornet */4333return "Atheros AR933x";4334case AR9300_DEVID_QCA955X: /* Scorpion */4335return "Qualcomm Atheros QCA955x";4336case AR9300_DEVID_QCA9565: /* Aphrodite */4337return "Qualcomm Atheros AR9565";4338case AR9300_DEVID_QCA953X: /* Honeybee */4339return "Qualcomm Atheros QCA953x";4340case AR9300_DEVID_AR1111_PCIE:4341return "Atheros AR1111";4342default:4343return AH_NULL;4344}43454346return AH_NULL;4347}43484349AH_CHIP(AR9300, ar9300_probe, ar9300_attach);4350435143524353