Browse Source

fix compile warnings for gcc 6.2.0

Most of issues discovered by gcc 6.2.0 are:
warning: implicit declaration of function '...'
which make sense since this functions was never declared,
espesially functions provided by ROM.

In the last case, correct usage of this functions was never
checked by compiler.

So, wellcome in to GCC 6.2.0 age ;)

Signed-off-by: Oleksij Rempel <linux@rempel-privat.de>
Oleksij Rempel 7 years ago
parent
commit
24b5105e07

+ 2 - 0
target_firmware/CMakeLists.txt

@@ -77,6 +77,8 @@ ELSE()
 ENDIF()
 
 INCLUDE_DIRECTORIES(
+	${CMAKE_SOURCE_DIR}/include
+	${CMAKE_SOURCE_DIR}/magpie_fw_dev/target/
 	${CMAKE_SOURCE_DIR}/magpie_fw_dev/target/inc
 	${CMAKE_SOURCE_DIR}/magpie_fw_dev/target/inc/xtensa-elf
 	${CMAKE_SOURCE_DIR}/magpie_fw_dev/target/inc/${PLATFORM_NAME}

+ 65 - 0
target_firmware/include/rom.h

@@ -0,0 +1,65 @@
+/*
+ * Copyright (c) 2013 Qualcomm Atheros, Inc.
+ * Copyright (c) 2016 Oleksij Rempel <linux@rempel-privat.de>
+ *
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted (subject to the limitations in the
+ * disclaimer below) provided that the following conditions are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *
+ *  * Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the
+ *    distribution.
+ *
+ *  * Neither the name of Qualcomm Atheros nor the names of its
+ *    contributors may be used to endorse or promote products derived
+ *    from this software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
+ * GRANTED BY THIS LICENSE.  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT
+ * HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
+ * BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
+ * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
+ * OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
+ * IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef _ATH_ROM_H_
+#define _ATH_ROM_H_
+
+#include <dt_defs.h>
+#include <hif_api.h>
+#include <htc.h>
+
+int strcmp(const char *s1, const char *s2);
+
+LOCAL BOOLEAN bSet_configuration(void);
+LOCAL void HTCControlSvcProcessMsg(HTC_ENDPOINT_ID EndpointID,
+		adf_nbuf_t hdr_buf, adf_nbuf_t pBuffers, void *arg);
+LOCAL void HTCMsgRecvHandler(adf_nbuf_t hdr_buf,
+		adf_nbuf_t buffer, void *context);
+
+void athos_indirection_table_install(void);
+
+void HIFusb_DescTraceDump(void);
+void _HIFusb_isr_handler(hif_handle_t);
+void _HIFusb_start(hif_handle_t);
+void mUsbEPinHighBandSet(uint8_t EPn, uint8_t dir, uint16_t size);
+void mUsbEPMap(uint8_t EPn, uint8_t MAP);
+void mUsbEPMxPtSzHigh(uint8_t EPn, uint8_t dir, uint16_t size);
+void mUsbEPMxPtSzLow(uint8_t EPn, uint8_t dir, uint16_t size);
+void mUsbFIFOConfig(uint8_t FIFOn, uint8_t cfg);
+void mUsbFIFOMap(uint8_t FIFOn, uint8_t MAP);
+
+#endif /* _ATH_ROM_H_ */

+ 3 - 0
target_firmware/magpie_fw_dev/target/cmnos/dbg_api.c

@@ -32,6 +32,9 @@
  * OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
  * IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  */
+
+#include <rom.h>
+
 #include "sys_cfg.h"
 #include "athos_api.h"
 

+ 1 - 0
target_firmware/magpie_fw_dev/target/cmnos/dbg_api.h

@@ -72,5 +72,6 @@ struct dbg_api {
     void (*_dbg_task)(void);
 };
 
+void cmnos_dbg_module_install(struct dbg_api *apis);
 
 #endif

+ 2 - 1
target_firmware/magpie_fw_dev/target/hif/k2_HIF_usb_patch.c

@@ -42,6 +42,7 @@
 #include <vdesc_api.h>
 #include <adf_os_mem.h> 
 #include <adf_os_io.h>
+#include <rom.h>
 
 #include "hif_usb.h"
 
@@ -67,5 +68,5 @@ void _HIFusb_isr_handler_patch(hif_handle_t h)
 {
     A_USB_FW_TASK();
 
-    _HIFusb_isr_handler();
+    _HIFusb_isr_handler(h);
 }

+ 3 - 0
target_firmware/magpie_fw_dev/target/hif/usb_api_magpie_patch.c

@@ -32,6 +32,9 @@
  * OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
  * IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  */
+
+#include <init/app_start.h>
+
 #include "usb_defs.h"
 #include "usb_type.h"
 #include "usb_pre.h"

+ 3 - 0
target_firmware/magpie_fw_dev/target/hif/usb_api_main_patch.c

@@ -1,5 +1,8 @@
 /* shared patches for k2 and magpie */
 
+#include <ah_osdep.h>
+#include <rom.h>
+
 #include "usb_defs.h"
 #include "usb_type.h"
 #include "usb_pre.h"

+ 0 - 167
target_firmware/magpie_fw_dev/target/inc/adf_net.h

@@ -121,20 +121,6 @@ adf_net_dev_create(adf_drv_handle_t   hdl,
     return (__adf_net_dev_create(hdl, op, info));
 }
 
-
-/**
- * @brief unregister a real device with the kernel
- * 
- * @param[in] hdl opaque device handle returned by adf_net_dev_create()
- * @see adf_net_dev_create()
- */
-static inline void
-adf_net_dev_delete(adf_net_handle_t hdl)
-{
-    __adf_net_dev_delete(hdl);
-}
-
-
 /**
  * @brief register a virtual device with the kernel.
  * A virtual device is always backed by a real device.
@@ -157,66 +143,6 @@ adf_net_vdev_create(adf_net_handle_t   dev_hdl,
     return (__adf_net_vdev_create(dev_hdl, hdl, op, info));
 }
 
-
-/**
- * @brief unregister the virtual device with the kernel.
- * 
- * @param[in] hdl opaque device handle returned by adf_net_vdev_create()
- *
- * @see adf_net_vdev_create()
- */
-static inline void
-adf_net_vdev_delete(adf_net_handle_t hdl)
-{
-    __adf_net_vdev_delete(hdl);
-}
-
-
-/**
- * @brief open the real device
- * 
- * @param[in] hdl opaque device handle
- * 
- * @return status of the operation
- *
- * @see adf_net_dev_create()
- */
-static inline a_status_t
-adf_net_dev_open(adf_net_handle_t hdl)
-{
-        return (__adf_net_dev_open(hdl));
-}
-
-
-/**
- * @brief close the real device
- * 
- * @param[in] hdl opaque device handle
- * 
- * @see adf_net_dev_open()
- */
-static inline void
-adf_net_dev_close(adf_net_handle_t hdl)
-{
-    __adf_net_dev_close(hdl);
-}
-
-
-/**
- * @brief transmit a network buffer using a device
- * 
- * @param[in] hdl opaque device handle
- * @param[in] pkt network buffer to transmit
- * 
- * @return status of the operation
- */
-static inline a_status_t 
-adf_net_dev_tx(adf_net_handle_t hdl, adf_nbuf_t pkt)
-{
-       return (__adf_net_dev_tx(hdl,pkt));
-}
-
-
 /**
  * @brief Checks if the interface is running or not
  * 
@@ -344,45 +270,6 @@ adf_net_queue_stopped(adf_net_handle_t hdl)
     return(__adf_net_queue_stopped(hdl));
 }
 
-
-/**
- * @brief This indicates a packet to the networking stack
- * (minus the FCS). The driver should just strip
- * the FCS and give the packet as a whole. This is
- * necessary because different native stacks have
- * different expectation of how they want to recv the
- * packet. This fucntion will strip off whatever is
- * required for the OS interface. The routine will also
- * figure out whether its being called in irq context and
- * call the appropriate OS API.
- * 
- * @param[in] hdl opaque device handle
- * @param[in] pkt network buffer to indicate
- * @param[in] len length of buffer
- */
-static inline void 
-adf_net_indicate_packet(adf_net_handle_t hdl, adf_nbuf_t pkt, a_uint32_t len)
-{
-    __adf_net_indicate_packet(hdl, pkt, len);
-}
-
-/**
- * @brief use this when indicating a vlan tagged packet on RX
- * 
- * @param[in] hdl opaque device handle
- * @param[in] pkt network buffer to indicate
- * @param[in] len length of buffer
- * @param[in] vid vlan id
- * 
- * @return status of operation
- */
-static inline a_status_t 
-adf_net_indicate_vlanpkt(adf_net_handle_t hdl, adf_nbuf_t pkt, 
-                         a_uint32_t len, adf_net_vid_t *vid)
-{
-    return (__adf_net_indicate_vlanpkt(hdl, pkt, len, vid));
-}
-
 /**
  * @brief get interface name
  * 
@@ -396,60 +283,6 @@ adf_net_ifname(adf_net_handle_t  hdl)
     return (__adf_net_ifname(hdl));
 }
 
-/**
- * @brief send management packets to apps (listener).
- * This is used for wireless applications.
- * 
- * @param[in] hdl opaque device handle
- * @param[in] pkt network buffer to send
- * @param[in] len length of buffer
- */
-static inline void
-adf_net_fw_mgmt_to_app(adf_net_handle_t hdl, adf_nbuf_t pkt, a_uint32_t len)
-{
-    __adf_net_fw_mgmt_to_app(hdl, pkt, len);
-}
-/**
- * @brief send wireless events to listening applications
- * 
- * @param[in] hdl opaque device handle
- * @param[in] what event to send
- * @param[in] data information about event
- * @param[in] data_len length of accompanying information
- */
-static inline void
-adf_net_send_wireless_event(adf_net_handle_t hdl, 
-                            adf_net_wireless_event_t what, 
-                            void *data, adf_os_size_t data_len)
-{
-    __adf_net_send_wireless_event(hdl, what, data, data_len); 
-}
-
-/**
- * @brief schedule the poll controller.
- * 
- * @param[in] hdl opaque device handle
- */
-static inline void 
-adf_net_poll_schedule(adf_net_handle_t hdl)
-{
-    __adf_net_poll_schedule(hdl);
-}
-
-
-/**
- * @brief per cpu deffered callback (e.g. for RSS)
- * 
- * @param[in] hdl opaque device handle
- * @param[in] cpu_msk
- * @param[in] arg
- */
-static inline void 
-adf_net_poll_schedule_cpu(adf_net_handle_t hdl, a_uint32_t cpu_msk, void *arg)
-{
-    __adf_net_poll_schedule_cpu(hdl, cpu_msk, arg);
-}
-
 /**
  * @brief Get OS Handle from OS device object.
  *

+ 2 - 0
target_firmware/magpie_fw_dev/target/inc/k2/Magpie_api.h

@@ -43,7 +43,9 @@
 #ifndef _MAGPIE_API_H
 #define _MAGPIE_API_H
 
+#include <dbg_api.h>
 #include <sys_cfg.h>
+
 #include "cmnos_api.h"
 #include "vbuf_api.h"
 #include "vdesc_api.h"

+ 6 - 0
target_firmware/magpie_fw_dev/target/init/app_start.c

@@ -32,6 +32,11 @@
  * OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
  * IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  */
+
+#include <wlan_pci.h>
+#include <Magpie_api.h>
+#include <rom.h>
+
 #include "dt_defs.h"
 #include "athos_api.h"
 
@@ -41,6 +46,7 @@
 #include "adf_os_io.h"
 
 #include "init.h"
+#include "app_start.h"
 #include <linux/compiler.h>
 
 // @TODO: Should define the memory region later~

+ 45 - 0
target_firmware/magpie_fw_dev/target/init/app_start.h

@@ -0,0 +1,45 @@
+/*
+ * Copyright (c) 2013 Qualcomm Atheros, Inc.
+ * Copyright (c) 2016 Oleksij Rempel <linux@rempel-privat.de>
+ *
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted (subject to the limitations in the
+ * disclaimer below) provided that the following conditions are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *
+ *  * Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the
+ *    distribution.
+ *
+ *  * Neither the name of Qualcomm Atheros nor the names of its
+ *    contributors may be used to endorse or promote products derived
+ *    from this software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
+ * GRANTED BY THIS LICENSE.  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT
+ * HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
+ * BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
+ * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
+ * OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
+ * IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+#ifndef _ATH_APP_START_H_
+#define _ATH_APP_START_H_
+
+#include <linux/compiler.h>
+
+void __section(boot) __noreturn __visible app_start(void);
+void Magpie_init(void);
+
+#endif /* _ATH_APP_START_H_ */

+ 3 - 0
target_firmware/magpie_fw_dev/target/init/init.c

@@ -34,6 +34,9 @@
  */
 #if defined(_RAM_)
 
+#include <wlan_pci.h>
+#include <rom.h>
+
 #include "athos_api.h"
 #include "usb_defs.h"
 

+ 4 - 0
target_firmware/magpie_fw_dev/target/init/init.h

@@ -66,7 +66,11 @@ extern void _fw_usb_reset_fifo(void);
 
 #endif
 
+#if defined(PROJECT_MAGPIE)
+void change_magpie_clk(void);
+#endif
 
 void fatal_exception_func();
 void init_mem();
 void __noreturn wlan_task();
+void reset_EP4_FIFO(void);

+ 1 - 0
target_firmware/magpie_fw_dev/target/init/magpie.c

@@ -33,6 +33,7 @@
  * IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  */
 #include "sys_cfg.h"
+#include "app_start.h"
 
 #if defined(_RAM_)
 

+ 3 - 2
target_firmware/magpie_fw_dev/target/rompatch/HIF_usb_patch.c

@@ -36,6 +36,7 @@
 #include "dt_defs.h"
 #include "reg_defs.h"
 
+#include <rom.h>
 #include <osapi.h>
 #include <hif_api.h>
 #include <Magpie_api.h>
@@ -67,7 +68,7 @@ void _HIFusb_isr_handler_patch(hif_handle_t h)
 {
     A_USB_FW_TASK();
 
-    _HIFusb_isr_handler();
+    _HIFusb_isr_handler(h);
 }
 
 
@@ -100,5 +101,5 @@ void _HIFusb_start_patch(hif_handle_t handle)
             break;
         }
     }
-    _HIFusb_start();
+    _HIFusb_start(handle);
 }

+ 3 - 0
target_firmware/magpie_fw_dev/target/wlan/wlan_pci.h

@@ -43,6 +43,9 @@
 #ifndef _WLAN_PCI_H
 #define _WLAN_PCI_H
 
+#include <adf_os_stdtypes.h>
+#include <adf_os_types.h>
+
 typedef int (*A_PCI_INIT_FUNC)(void);
 
 //extern A_PCI_INIT_FUNC g_pci_init_func;

+ 5 - 0
target_firmware/wlan/ieee80211_var.h

@@ -219,4 +219,9 @@ ieee80211_anyhdrsize(const void *data)
 		return ieee80211_hdrsize(data);
 }
 
+a_status_t
+ieee80211_tgt_crypto_encap(struct ieee80211_frame *wh,
+			   struct ieee80211_node_target *ni,
+		           a_uint8_t keytype);
+
 #endif

+ 2 - 0
target_firmware/wlan/if_ath.c

@@ -56,6 +56,8 @@
 #include "if_athvar.h"
 #include "ah_desc.h"
 #include "ah.h"
+#include "ratectrl.h"
+#include "ah_internal.h"
 
 static a_int32_t ath_numrxbufs = -1;
 static a_int32_t ath_numrxdescs = -1;

+ 6 - 0
target_firmware/wlan/if_athrate.h

@@ -113,4 +113,10 @@ void ath_rate_tx_complete(struct ath_softc_tgt *, struct ath_node_target *,
 void ath_rate_stateupdate(struct ath_softc_tgt *sc, struct ath_node_target *an, 
 			  enum ath_rc_cwmode cwmode);
 
+
+void ath_tx_status_update_rate(struct ath_softc_tgt *sc,
+			       struct ath_rc_series rcs[],
+			       int series,
+			       WMI_TXSTATUS_EVENT *txs);
+
 #endif /* _ATH_RATECTRL_H_ */

+ 9 - 0
target_firmware/wlan/if_athvar.h

@@ -488,5 +488,14 @@ typedef enum {
 } owl_txq_state_t;
 
 a_uint8_t ath_get_minrateidx(struct ath_softc_tgt *sc, struct ath_vap_target *avp);
+void ath_tgt_tx_cleanup(struct ath_softc_tgt *sc, struct ath_node_target *an,
+			ath_atx_tid_t *tid, a_uint8_t discard_all);
+void ath_tgt_handle_normal(struct ath_softc_tgt *sc, struct ath_tx_buf *bf);
+void ath_tgt_handle_aggr(struct ath_softc_tgt *sc, struct ath_tx_buf *bf);
+void ath_tgt_tid_drain(struct ath_softc_tgt *sc, struct ath_atx_tid *tid);
+void ath_tx_status_clear(struct ath_softc_tgt *sc);
+
+void wmi_event(wmi_handle_t handle, WMI_EVENT_ID evt_id,
+	       void *buffer, a_int32_t Length);
 
 #endif /* _DEV_ATH_ATHVAR_H */

+ 3 - 0
target_firmware/wlan/if_owl.c

@@ -57,6 +57,7 @@
 #include "if_athrate.h"
 #include "if_athvar.h"
 #include "ah_desc.h"
+#include "ah_internal.h"
 
 #define ath_tgt_free_skb  adf_nbuf_free
 
@@ -147,6 +148,8 @@ static void ath_tx_comp_cleanup(struct ath_softc_tgt *sc, struct ath_tx_buf *bf)
 int ath_tgt_tx_add_to_aggr(struct ath_softc_tgt *sc,
 			   struct ath_buf *bf,int datatype,
 			   ath_atx_tid_t *tid, int is_burst);
+int ath_tgt_tx_form_aggr(struct ath_softc_tgt *sc, ath_atx_tid_t *tid,
+			 ath_tx_bufhead *bf_q);
 
 struct ieee80211_frame *ATH_SKB_2_WH(adf_nbuf_t skb)
 {

+ 13 - 0
target_firmware/wlan/ratectrl.h

@@ -284,4 +284,17 @@ struct fusion_rate_info {
 
 void ar5416AttachRateTables(struct atheros_softc *sc);
 
+void ath_rate_node_update(struct ath_softc_tgt *sc,
+			  struct ath_node_target *an,
+			  a_int32_t isnew,
+			  a_uint32_t capflag,
+			  struct ieee80211_rate *rs);
+
+
+void ath_rate_newstate(struct ath_softc_tgt *sc,
+		       struct ieee80211vap_target *vap,
+		       enum ieee80211_state state,
+		       a_uint32_t capflag,
+		       struct ieee80211_rate *rs);
+
 #endif /* _RATECTRL_H_ */

+ 0 - 5
target_firmware/wlan/ratectrl11n.h

@@ -183,9 +183,4 @@ void rcUpdate_11n(struct ath_softc_tgt *sc,
 		  int nBad,
 		  int sh_lo_retry);
 
-void ath_tx_status_update_rate(struct ath_softc_tgt *sc,
-			       struct ath_rc_series rcs[],
-			       int series,
-			       WMI_TXSTATUS_EVENT *txs);
-
 #endif /* _RATECTRL11N_H_ */