bt_att.c 49 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791179217931794179517961797179817991800180118021803180418051806180718081809181018111812181318141815181618171818181918201821182218231824182518261827182818291830183118321833183418351836183718381839184018411842184318441845184618471848184918501851185218531854185518561857185818591860186118621863186418651866186718681869187018711872187318741875187618771878187918801881188218831884188518861887188818891890189118921893189418951896189718981899190019011902190319041905190619071908190919101911191219131914191519161917191819191920192119221923192419251926192719281929193019311932193319341935193619371938193919401941
  1. /****************************************************************************
  2. * wireless/bluetooth/bt_att.c
  3. * Attribute protocol handling.
  4. *
  5. * Copyright (C) 2018 Gregory Nutt. All rights reserved.
  6. * Author: Gregory Nutt <gnutt@nuttx.org>
  7. *
  8. * Ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package
  9. * where the code was released with a compatible 3-clause BSD license:
  10. *
  11. * Copyright (c) 2016, Intel Corporation
  12. * All rights reserved.
  13. *
  14. * Redistribution and use in source and binary forms, with or without
  15. * modification, are permitted provided that the following conditions are
  16. * met:
  17. *
  18. * 1. Redistributions of source code must retain the above copyright notice,
  19. * this list of conditions and the following disclaimer.
  20. *
  21. * 2. Redistributions in binary form must reproduce the above copyright
  22. * notice, this list of conditions and the following disclaimer in the
  23. * documentation and/or other materials provided with the distribution.
  24. *
  25. * 3. Neither the name of the copyright holder nor the names of its
  26. * contributors may be used to endorse or promote products derived from
  27. * this software without specific prior written permission.
  28. *
  29. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  30. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
  31. * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
  32. * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
  33. * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
  34. * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
  35. * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS
  36. * ; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
  37. * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
  38. * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
  39. * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  40. *
  41. ****************************************************************************/
  42. /****************************************************************************
  43. * Included Files
  44. ****************************************************************************/
  45. #include <nuttx/config.h>
  46. #include <stdbool.h>
  47. #include <string.h>
  48. #include <errno.h>
  49. #include <debug.h>
  50. #include <nuttx/net/bluetooth.h>
  51. #include <nuttx/wireless/bluetooth/bt_hci.h>
  52. #include <nuttx/wireless/bluetooth/bt_core.h>
  53. #include <nuttx/wireless/bluetooth/bt_uuid.h>
  54. #include <nuttx/wireless/bluetooth/bt_gatt.h>
  55. #include "bt_hcicore.h"
  56. #include "bt_conn.h"
  57. #include "bt_l2cap.h"
  58. #include "bt_att.h"
  59. /****************************************************************************
  60. * Pre-processor Definitions
  61. ****************************************************************************/
  62. #if !defined(CONFIG_BLUETOOTH_DEBUG_ATT)
  63. # undef wlinfo
  64. # define wlinfo(fmt, ...)
  65. #endif
  66. #define BT_GATT_PERM_READ_MASK (BT_GATT_PERM_READ | \
  67. BT_GATT_PERM_READ_ENCRYPT | \
  68. BT_GATT_PERM_READ_AUTHEN | \
  69. BT_GATT_PERM_AUTHOR)
  70. #define BT_GATT_PERM_WRITE_MASK (BT_GATT_PERM_WRITE | \
  71. BT_GATT_PERM_WRITE_ENCRYPT | \
  72. BT_GATT_PERM_WRITE_AUTHEN | \
  73. BT_GATT_PERM_AUTHOR)
  74. #define BT_GATT_PERM_ENCRYPT_MASK (BT_GATT_PERM_READ_ENCRYPT | \
  75. BT_GATT_PERM_WRITE_ENCRYPT)
  76. #define BT_GATT_PERM_AUTHEN_MASK (BT_GATT_PERM_READ_AUTHEN | \
  77. BT_GATT_PERM_WRITE_AUTHEN)
  78. #define BT_ATT_OP_CMD_MASK (BT_ATT_OP_WRITE_CMD & \
  79. BT_ATT_OP_SIGNED_WRITE_CMD)
  80. /****************************************************************************
  81. * Private Types
  82. ****************************************************************************/
  83. /* ATT request context */
  84. struct bt_att_req_s
  85. {
  86. bt_att_func_t func;
  87. FAR void *user_data;
  88. bt_att_destroy_t destroy;
  89. uint8_t op;
  90. };
  91. /* ATT channel specific context */
  92. struct bt_att_s
  93. {
  94. /* The connection this context is associated with */
  95. FAR struct bt_conn_s *conn;
  96. uint16_t mtu;
  97. struct bt_att_req_s req;
  98. /* TODO: Allow more than one pending request */
  99. };
  100. struct find_info_data_s
  101. {
  102. FAR struct bt_conn_s *conn;
  103. FAR struct bt_buf_s *buf;
  104. FAR struct bt_att_find_info_rsp_s *rsp;
  105. union
  106. {
  107. FAR struct bt_att_info_16_s *info16;
  108. FAR struct bt_att_info_128_s *info128;
  109. } u;
  110. };
  111. struct find_type_data_s
  112. {
  113. FAR struct bt_conn_s *conn;
  114. FAR struct bt_buf_s *buf;
  115. FAR struct bt_att_handle_group_s *group;
  116. FAR const void *value;
  117. uint8_t value_len;
  118. };
  119. struct read_type_data_s
  120. {
  121. FAR struct bt_conn_s *conn;
  122. FAR struct bt_uuid_s *uuid;
  123. FAR struct bt_buf_s *buf;
  124. FAR struct bt_att_read_type_rsp_s *rsp;
  125. FAR struct bt_att_data_s *item;
  126. };
  127. struct read_data_s
  128. {
  129. FAR struct bt_conn_s *conn;
  130. uint16_t offset;
  131. FAR struct bt_buf_s *buf;
  132. FAR struct bt_att_read_rsp_s *rsp;
  133. uint8_t err;
  134. };
  135. struct read_group_data_s
  136. {
  137. FAR struct bt_conn_s *conn;
  138. FAR struct bt_uuid_s *uuid;
  139. FAR struct bt_buf_s *buf;
  140. FAR struct bt_att_read_group_rsp_s *rsp;
  141. FAR struct bt_att_group_data_s *group;
  142. };
  143. struct write_data_s
  144. {
  145. FAR struct bt_conn_s *conn;
  146. FAR struct bt_buf_s *buf;
  147. uint8_t op;
  148. FAR const void *value;
  149. uint8_t len;
  150. uint16_t offset;
  151. uint8_t err;
  152. };
  153. struct flush_data_s
  154. {
  155. FAR struct bt_conn_s *conn;
  156. FAR struct bt_buf_s *buf;
  157. uint8_t flags;
  158. uint8_t err;
  159. };
  160. struct handler_info_s
  161. {
  162. uint8_t op;
  163. CODE uint8_t(*func)(FAR struct bt_conn_s *conn, FAR struct bt_buf_s *buf);
  164. uint8_t expect_len;
  165. };
  166. /****************************************************************************
  167. * Private Function Prototypes
  168. ****************************************************************************/
  169. static void att_req_destroy(FAR struct bt_att_req_s *req);
  170. static void send_err_rsp(struct bt_conn_s *conn, uint8_t req,
  171. uint16_t handle, uint8_t err);
  172. static uint8_t att_mtu_req(struct bt_conn_s *conn, struct bt_buf_s *data);
  173. static uint8_t att_handle_rsp(struct bt_conn_s *conn, void *pdu,
  174. uint16_t len, uint8_t err);
  175. static uint8_t att_mtu_rsp(FAR struct bt_conn_s *conn,
  176. FAR struct bt_buf_s *buf);
  177. static bool range_is_valid(uint16_t start, uint16_t end,
  178. FAR uint16_t *err);
  179. static uint8_t find_info_cb(FAR const struct bt_gatt_attr_s *attr,
  180. FAR void *user_data);
  181. static uint8_t att_find_info_rsp(FAR struct bt_conn_s *conn,
  182. uint16_t start_handle, uint16_t end_handle);
  183. static uint8_t att_find_info_req(FAR struct bt_conn_s *conn,
  184. FAR struct bt_buf_s *data);
  185. static uint8_t find_type_cb(FAR const struct bt_gatt_attr_s *attr,
  186. FAR void *user_data);
  187. static uint8_t att_find_type_rsp(FAR struct bt_conn_s *conn,
  188. FAR uint16_t start_handle, uint16_t end_handle,
  189. FAR const void *value, uint8_t value_len);
  190. static uint8_t att_find_type_req(FAR struct bt_conn_s *conn,
  191. FAR struct bt_buf_s *data);
  192. static bool uuid_create(FAR struct bt_uuid_s *uuid,
  193. FAR struct bt_buf_s *data);
  194. static uint8_t read_type_cb(FAR const struct bt_gatt_attr_s *attr,
  195. FAR void *user_data);
  196. static uint8_t att_read_type_rsp(FAR struct bt_conn_s *conn,
  197. FAR struct bt_uuid_s *uuid, uint16_t start_handle,
  198. uint16_t end_handle);
  199. static uint8_t att_read_type_req(FAR struct bt_conn_s *conn,
  200. FAR struct bt_buf_s *data);
  201. static uint8_t err_to_att(int err);
  202. static uint8_t check_perm(FAR struct bt_conn_s *conn,
  203. FAR const struct bt_gatt_attr_s *attr, uint8_t mask);
  204. static uint8_t read_cb(FAR const struct bt_gatt_attr_s *attr,
  205. FAR void *user_data);
  206. static uint8_t att_read_rsp(FAR struct bt_conn_s *conn, uint8_t op,
  207. uint8_t rsp, uint16_t handle, uint16_t offset);
  208. static uint8_t att_read_req(FAR struct bt_conn_s *conn,
  209. FAR struct bt_buf_s *data);
  210. static uint8_t att_read_blob_req(FAR struct bt_conn_s *conn,
  211. FAR struct bt_buf_s *data);
  212. static uint8_t att_read_mult_req(FAR struct bt_conn_s *conn,
  213. FAR struct bt_buf_s *buf);
  214. static uint8_t read_group_cb(FAR const struct bt_gatt_attr_s *attr,
  215. FAR void *user_data);
  216. static uint8_t att_read_group_rsp(FAR struct bt_conn_s *conn,
  217. FAR struct bt_uuid_s *uuid, uint16_t start_handle,
  218. uint16_t end_handle);
  219. static uint8_t att_read_group_req(FAR struct bt_conn_s *conn,
  220. FAR struct bt_buf_s *data);
  221. static uint8_t write_cb(FAR const struct bt_gatt_attr_s *attr,
  222. FAR void *user_data);
  223. static uint8_t att_write_rsp(FAR struct bt_conn_s *conn, uint8_t op,
  224. uint8_t rsp, uint16_t handle, uint16_t offset,
  225. FAR const void *value, uint8_t len);
  226. static uint8_t att_write_req(FAR struct bt_conn_s *conn,
  227. FAR struct bt_buf_s *data);
  228. static uint8_t att_prepare_write_req(FAR struct bt_conn_s *conn,
  229. FAR struct bt_buf_s *data);
  230. static uint8_t flush_cb(FAR const struct bt_gatt_attr_s *attr,
  231. FAR void *user_data);
  232. static uint8_t att_exec_write_rsp(FAR struct bt_conn_s *conn,
  233. uint8_t flags);
  234. static uint8_t att_exec_write_req(FAR struct bt_conn_s *conn,
  235. FAR struct bt_buf_s *data);
  236. static uint8_t att_write_cmd(FAR struct bt_conn_s *conn,
  237. FAR struct bt_buf_s *data);
  238. static uint8_t att_signed_write_cmd(FAR struct bt_conn_s *conn,
  239. FAR struct bt_buf_s *data);
  240. static uint8_t att_error_rsp(FAR struct bt_conn_s *conn,
  241. FAR struct bt_buf_s *data);
  242. static uint8_t att_handle_find_info_rsp(FAR struct bt_conn_s *conn,
  243. FAR struct bt_buf_s *buf);
  244. static uint8_t att_handle_find_type_rsp(FAR struct bt_conn_s *conn,
  245. FAR struct bt_buf_s *buf);
  246. static uint8_t att_handle_read_type_rsp(FAR struct bt_conn_s *conn,
  247. FAR struct bt_buf_s *buf);
  248. static uint8_t att_handle_read_rsp(FAR struct bt_conn_s *conn,
  249. FAR struct bt_buf_s *buf);
  250. static uint8_t att_handle_read_blob_rsp(FAR struct bt_conn_s *conn,
  251. FAR struct bt_buf_s *buf);
  252. static uint8_t att_handle_read_mult_rsp(FAR struct bt_conn_s *conn,
  253. FAR struct bt_buf_s *buf);
  254. static uint8_t att_handle_write_rsp(FAR struct bt_conn_s *conn,
  255. FAR struct bt_buf_s *buf);
  256. static void bt_att_receive(FAR struct bt_conn_s *conn,
  257. FAR struct bt_buf_s *buf, FAR void *context, uint16_t cid);
  258. static void bt_att_connected(FAR struct bt_conn_s *conn, FAR void *context,
  259. uint16_t cid);
  260. static void bt_att_disconnected(FAR struct bt_conn_s *conn,
  261. FAR void *context, uint16_t cid);
  262. /****************************************************************************
  263. * Private Data
  264. ****************************************************************************/
  265. static struct bt_att_s g_bt_att_pool[CONFIG_BLUETOOTH_MAX_CONN];
  266. static const struct bt_uuid_s g_primary_uuid =
  267. {
  268. BT_UUID_16,
  269. {
  270. BT_UUID_GATT_PRIMARY
  271. }
  272. };
  273. static const struct bt_uuid_s g_secondary_uuid =
  274. {
  275. BT_UUID_16,
  276. {
  277. BT_UUID_GATT_SECONDARY
  278. },
  279. };
  280. static const struct handler_info_s g_handlers[] =
  281. {
  282. {
  283. BT_ATT_OP_ERROR_RSP,
  284. att_error_rsp,
  285. sizeof(struct bt_att_error_rsp_s)
  286. },
  287. {
  288. BT_ATT_OP_MTU_REQ,
  289. att_mtu_req,
  290. sizeof(struct bt_att_exchange_mtu_req_s)
  291. },
  292. {
  293. BT_ATT_OP_MTU_RSP,
  294. att_mtu_rsp,
  295. sizeof(struct bt_att_exchange_mtu_rsp_s)
  296. },
  297. {
  298. BT_ATT_OP_FIND_INFO_REQ,
  299. att_find_info_req,
  300. sizeof(struct bt_att_find_info_req_s)
  301. },
  302. {
  303. BT_ATT_OP_FIND_INFO_RSP,
  304. att_handle_find_info_rsp,
  305. sizeof(struct bt_att_find_info_rsp_s)
  306. },
  307. {
  308. BT_ATT_OP_FIND_TYPE_REQ,
  309. att_find_type_req,
  310. sizeof(struct bt_att_find_type_req_s)
  311. },
  312. {
  313. BT_ATT_OP_FIND_TYPE_RSP,
  314. att_handle_find_type_rsp,
  315. sizeof(struct bt_att_find_type_rsp_s)
  316. },
  317. {
  318. BT_ATT_OP_READ_TYPE_REQ,
  319. att_read_type_req,
  320. sizeof(struct bt_att_read_type_req_s)
  321. },
  322. {
  323. BT_ATT_OP_READ_TYPE_RSP,
  324. att_handle_read_type_rsp,
  325. sizeof(struct bt_att_read_type_rsp_s)
  326. },
  327. {
  328. BT_ATT_OP_READ_REQ,
  329. att_read_req,
  330. sizeof(struct bt_att_read_req_s)
  331. },
  332. {
  333. BT_ATT_OP_READ_RSP,
  334. att_handle_read_rsp,
  335. sizeof(struct bt_att_read_rsp_s)
  336. },
  337. {
  338. BT_ATT_OP_READ_BLOB_REQ,
  339. att_read_blob_req,
  340. sizeof(struct bt_att_read_blob_req_s)
  341. },
  342. {
  343. BT_ATT_OP_READ_BLOB_RSP,
  344. att_handle_read_blob_rsp,
  345. sizeof(struct bt_att_read_blob_rsp_s)
  346. },
  347. {
  348. BT_ATT_OP_READ_MULT_REQ,
  349. att_read_mult_req,
  350. BT_ATT_READ_MULT_MIN_LEN_REQ
  351. },
  352. {
  353. BT_ATT_OP_READ_MULT_RSP,
  354. att_handle_read_mult_rsp,
  355. sizeof(struct bt_att_read_mult_rsp_s)
  356. },
  357. {
  358. BT_ATT_OP_READ_GROUP_REQ,
  359. att_read_group_req,
  360. sizeof(struct bt_att_read_group_req_s)
  361. },
  362. {
  363. BT_ATT_OP_WRITE_REQ,
  364. att_write_req,
  365. sizeof(struct bt_att_write_req_s)
  366. },
  367. {
  368. BT_ATT_OP_WRITE_RSP,
  369. att_handle_write_rsp,
  370. 0
  371. },
  372. {
  373. BT_ATT_OP_PREPARE_WRITE_REQ,
  374. att_prepare_write_req,
  375. sizeof(struct bt_att_prepare_write_req_s)
  376. },
  377. {
  378. BT_ATT_OP_EXEC_WRITE_REQ,
  379. att_exec_write_req,
  380. sizeof(struct bt_att_exec_write_req_s)
  381. },
  382. {
  383. BT_ATT_OP_WRITE_CMD,
  384. att_write_cmd,
  385. sizeof(struct bt_att_write_cmd_s)
  386. },
  387. {
  388. BT_ATT_OP_SIGNED_WRITE_CMD,
  389. att_signed_write_cmd,
  390. sizeof(struct bt_att_write_cmd_s) + sizeof(struct bt_att_signature_s)
  391. }
  392. };
  393. #define NHANDLERS (sizeof(g_handlers) / sizeof(struct handler_info_s))
  394. /****************************************************************************
  395. * Private Functions
  396. ****************************************************************************/
  397. static void att_req_destroy(FAR struct bt_att_req_s *req)
  398. {
  399. if (req->destroy)
  400. {
  401. req->destroy(req->user_data);
  402. }
  403. memset(req, 0, sizeof(*req));
  404. }
  405. static void send_err_rsp(struct bt_conn_s *conn,
  406. uint8_t req,
  407. uint16_t handle,
  408. uint8_t err)
  409. {
  410. struct bt_att_error_rsp_s *rsp;
  411. struct bt_buf_s *buf;
  412. /* Ignore opcode 0x00 */
  413. if (!req)
  414. {
  415. return;
  416. }
  417. buf = bt_att_create_pdu(conn, BT_ATT_OP_ERROR_RSP, sizeof(*rsp));
  418. if (!buf)
  419. {
  420. return;
  421. }
  422. rsp = bt_buf_extend(buf, sizeof(*rsp));
  423. rsp->request = req;
  424. rsp->handle = BT_HOST2LE16(handle);
  425. rsp->error = err;
  426. bt_l2cap_send(conn, BT_L2CAP_CID_ATT, buf);
  427. }
  428. static uint8_t att_mtu_req(struct bt_conn_s *conn, struct bt_buf_s *data)
  429. {
  430. FAR struct bt_att_s *att = conn->att;
  431. struct bt_att_exchange_mtu_req_s *req;
  432. struct bt_att_exchange_mtu_rsp_s *rsp;
  433. struct bt_buf_s *buf;
  434. uint16_t maxmtu;
  435. uint16_t mtu;
  436. req = (void *)data->data;
  437. mtu = BT_LE162HOST(req->mtu);
  438. wlinfo("Client MTU %u\n", mtu);
  439. if (mtu > BT_ATT_MAX_LE_MTU || mtu < BT_ATT_DEFAULT_LE_MTU)
  440. {
  441. return BT_ATT_ERR_INVALID_PDU;
  442. }
  443. buf = bt_att_create_pdu(conn, BT_ATT_OP_MTU_RSP, sizeof(*rsp));
  444. if (!buf)
  445. {
  446. return BT_ATT_ERR_UNLIKELY;
  447. }
  448. /* Select MTU based on the amount of room we have in bt_buf_s including one
  449. * extra byte for ATT header.
  450. */
  451. maxmtu = bt_buf_tailroom(buf) + 1;
  452. if (mtu > maxmtu)
  453. {
  454. mtu = maxmtu;
  455. }
  456. wlinfo("Server MTU %u\n", mtu);
  457. att->mtu = mtu;
  458. rsp = bt_buf_extend(buf, sizeof(*rsp));
  459. rsp->mtu = BT_HOST2LE16(mtu);
  460. bt_l2cap_send(conn, BT_L2CAP_CID_ATT, buf);
  461. return 0;
  462. }
  463. static uint8_t att_handle_rsp(struct bt_conn_s *conn,
  464. void *pdu,
  465. uint16_t len,
  466. uint8_t err)
  467. {
  468. FAR struct bt_att_s *att = conn->att;
  469. struct bt_att_req_s req;
  470. if (!att->req.func)
  471. {
  472. return 0;
  473. }
  474. /* Reset request before callback so another request can be queued */
  475. memcpy(&req, &att->req, sizeof(req));
  476. att->req.func = NULL;
  477. req.func(conn, err, pdu, len, req.user_data);
  478. att_req_destroy(&req);
  479. return 0;
  480. }
  481. static uint8_t att_mtu_rsp(FAR struct bt_conn_s *conn,
  482. FAR struct bt_buf_s *buf)
  483. {
  484. FAR struct bt_att_s *att = conn->att;
  485. FAR struct bt_att_exchange_mtu_rsp_s *rsp;
  486. uint16_t maxmtu;
  487. uint16_t mtu;
  488. if (!att)
  489. {
  490. return 0;
  491. }
  492. rsp = (void *)buf->data;
  493. mtu = BT_LE162HOST(rsp->mtu);
  494. wlinfo("Server MTU %u\n", mtu);
  495. /* Check if MTU is within allowed range */
  496. if (mtu > BT_ATT_MAX_LE_MTU || mtu < BT_ATT_DEFAULT_LE_MTU)
  497. {
  498. return att_handle_rsp(conn, NULL, 0, BT_ATT_ERR_INVALID_PDU);
  499. }
  500. /* Clip MTU based on the maximum amount of data bt_buf_s can hold excluding
  501. * L2CAP, ACL and driver headers.
  502. */
  503. maxmtu = BLUETOOTH_MAX_FRAMELEN - (sizeof(struct bt_l2cap_hdr_s) +
  504. sizeof(struct bt_hci_acl_hdr_s) +
  505. g_btdev.btdev->head_reserve);
  506. if (mtu > maxmtu)
  507. {
  508. mtu = maxmtu;
  509. }
  510. att->mtu = mtu;
  511. return att_handle_rsp(conn, rsp, buf->len, 0);
  512. }
  513. static bool range_is_valid(uint16_t start, uint16_t end, FAR uint16_t *err)
  514. {
  515. /* Handle 0 is invalid */
  516. if (!start || !end)
  517. {
  518. if (err)
  519. {
  520. *err = 0;
  521. }
  522. return false;
  523. }
  524. /* Check if range is valid */
  525. if (start > end)
  526. {
  527. if (err)
  528. {
  529. *err = start;
  530. }
  531. return false;
  532. }
  533. return true;
  534. }
  535. static uint8_t find_info_cb(FAR const struct bt_gatt_attr_s *attr,
  536. FAR void *user_data)
  537. {
  538. FAR struct find_info_data_s *data = user_data;
  539. FAR struct bt_att_s *att = data->conn->att;
  540. wlinfo("handle 0x%04x\n", attr->handle);
  541. /* Initialize rsp at first entry */
  542. if (!data->rsp)
  543. {
  544. data->rsp = bt_buf_extend(data->buf, sizeof(*data->rsp));
  545. data->rsp->format = (attr->uuid->type == BT_UUID_16) ?
  546. BT_ATT_INFO_16 : BT_ATT_INFO_128;
  547. }
  548. switch (data->rsp->format)
  549. {
  550. case BT_ATT_INFO_16:
  551. if (attr->uuid->type != BT_UUID_16)
  552. {
  553. return BT_GATT_ITER_STOP;
  554. }
  555. /* Fast forward to next item position */
  556. data->u.info16 = bt_buf_extend(data->buf,
  557. sizeof(*data->u.info16));
  558. data->u.info16->handle = BT_HOST2LE16(attr->handle);
  559. data->u.info16->uuid = BT_HOST2LE16(attr->uuid->u.u16);
  560. return att->mtu - data->buf->len > sizeof(*data->u.info16) ?
  561. BT_GATT_ITER_CONTINUE : BT_GATT_ITER_STOP;
  562. case BT_ATT_INFO_128:
  563. if (attr->uuid->type != BT_UUID_128)
  564. {
  565. return BT_GATT_ITER_STOP;
  566. }
  567. /* Fast forward to next item position */
  568. data->u.info128 = bt_buf_extend(data->buf,
  569. sizeof(*data->u.info128));
  570. data->u.info128->handle = BT_HOST2LE16(attr->handle);
  571. memcpy(data->u.info128->uuid,
  572. attr->uuid->u.u128,
  573. sizeof(data->u.info128->uuid));
  574. return att->mtu - data->buf->len > sizeof(*data->u.info128) ?
  575. BT_GATT_ITER_CONTINUE : BT_GATT_ITER_STOP;
  576. }
  577. return BT_GATT_ITER_STOP;
  578. }
  579. static uint8_t att_find_info_rsp(FAR struct bt_conn_s *conn,
  580. uint16_t start_handle,
  581. uint16_t end_handle)
  582. {
  583. struct find_info_data_s data;
  584. memset(&data, 0, sizeof(data));
  585. data.buf = bt_att_create_pdu(conn, BT_ATT_OP_FIND_INFO_RSP, 0);
  586. if (!data.buf)
  587. {
  588. return BT_ATT_ERR_UNLIKELY;
  589. }
  590. data.conn = conn;
  591. bt_gatt_foreach_attr(start_handle, end_handle, find_info_cb, &data);
  592. if (!data.rsp)
  593. {
  594. bt_buf_release(data.buf);
  595. /* Respond since handle is set */
  596. send_err_rsp(conn, BT_ATT_OP_FIND_INFO_REQ, start_handle,
  597. BT_ATT_ERR_ATTRIBUTE_NOT_FOUND);
  598. return 0;
  599. }
  600. bt_l2cap_send(conn, BT_L2CAP_CID_ATT, data.buf);
  601. return 0;
  602. }
  603. static uint8_t att_find_info_req(FAR struct bt_conn_s *conn,
  604. FAR struct bt_buf_s *data)
  605. {
  606. FAR struct bt_att_find_info_req_s *req;
  607. uint16_t start_handle;
  608. uint16_t end_handle;
  609. uint16_t err_handle;
  610. req = (void *)data->data;
  611. start_handle = BT_LE162HOST(req->start_handle);
  612. end_handle = BT_LE162HOST(req->end_handle);
  613. wlinfo("start_handle 0x%04x end_handle 0x%04x\n",
  614. start_handle, end_handle);
  615. if (!range_is_valid(start_handle, end_handle, &err_handle))
  616. {
  617. send_err_rsp(conn, BT_ATT_OP_FIND_INFO_REQ, err_handle,
  618. BT_ATT_ERR_INVALID_HANDLE);
  619. return 0;
  620. }
  621. return att_find_info_rsp(conn, start_handle, end_handle);
  622. }
  623. static uint8_t find_type_cb(FAR const struct bt_gatt_attr_s *attr,
  624. FAR void *user_data)
  625. {
  626. FAR struct find_type_data_s *data = user_data;
  627. FAR struct bt_att_s *att = data->conn->att;
  628. uint8_t uuid[16];
  629. int read;
  630. /* Skip if not a primary service */
  631. if (bt_uuid_cmp(attr->uuid, &g_primary_uuid))
  632. {
  633. if (data->group && attr->handle > data->group->end_handle)
  634. {
  635. data->group->end_handle = BT_HOST2LE16(attr->handle);
  636. }
  637. return BT_GATT_ITER_CONTINUE;
  638. }
  639. wlinfo("handle 0x%04x\n", attr->handle);
  640. /* Stop if there is no space left */
  641. if (att->mtu - data->buf->len < sizeof(*data->group))
  642. {
  643. return BT_GATT_ITER_STOP;
  644. }
  645. /* Read attribute value and store in the buffer */
  646. read = attr->read(data->conn, attr, uuid, sizeof(uuid), 0);
  647. if (read < 0)
  648. {
  649. /* TODO: Return an error if this fails */
  650. return BT_GATT_ITER_STOP;
  651. }
  652. /* Check if data matches */
  653. if (read != data->value_len || memcmp(data->value, uuid, read))
  654. {
  655. /* If a group exists stop otherwise continue */
  656. return data->group ? BT_GATT_ITER_STOP : BT_GATT_ITER_CONTINUE;
  657. }
  658. /* Fast forward to next item position */
  659. data->group = bt_buf_extend(data->buf, sizeof(*data->group));
  660. data->group->start_handle = BT_HOST2LE16(attr->handle);
  661. data->group->end_handle = BT_HOST2LE16(attr->handle);
  662. /* Continue to find the end_handle */
  663. return BT_GATT_ITER_CONTINUE;
  664. }
  665. static uint8_t att_find_type_rsp(FAR struct bt_conn_s *conn,
  666. FAR uint16_t start_handle,
  667. uint16_t end_handle,
  668. FAR const void *value,
  669. uint8_t value_len)
  670. {
  671. struct find_type_data_s data;
  672. memset(&data, 0, sizeof(data));
  673. data.buf = bt_att_create_pdu(conn, BT_ATT_OP_FIND_TYPE_RSP, 0);
  674. if (!data.buf)
  675. {
  676. return BT_ATT_ERR_UNLIKELY;
  677. }
  678. data.conn = conn;
  679. data.value = value;
  680. data.value_len = value_len;
  681. bt_gatt_foreach_attr(start_handle, end_handle, find_type_cb, &data);
  682. if (!data.group)
  683. {
  684. bt_buf_release(data.buf);
  685. /* Respond since handle is set */
  686. send_err_rsp(conn, BT_ATT_OP_FIND_TYPE_REQ, start_handle,
  687. BT_ATT_ERR_ATTRIBUTE_NOT_FOUND);
  688. return 0;
  689. }
  690. bt_l2cap_send(conn, BT_L2CAP_CID_ATT, data.buf);
  691. return 0;
  692. }
  693. static uint8_t att_find_type_req(FAR struct bt_conn_s *conn,
  694. FAR struct bt_buf_s *data)
  695. {
  696. FAR struct bt_att_find_type_req_s *req;
  697. FAR uint8_t *value;
  698. uint16_t start_handle;
  699. uint16_t end_handle;
  700. uint16_t err_handle;
  701. uint16_t type;
  702. req = (FAR void *)data->data;
  703. start_handle = BT_LE162HOST(req->start_handle);
  704. end_handle = BT_LE162HOST(req->end_handle);
  705. type = BT_LE162HOST(req->type);
  706. value = bt_buf_consume(data, sizeof(*req));
  707. wlinfo("start_handle 0x%04x end_handle 0x%04x type %u\n", start_handle,
  708. end_handle, type);
  709. if (!range_is_valid(start_handle, end_handle, &err_handle))
  710. {
  711. send_err_rsp(conn, BT_ATT_OP_FIND_TYPE_REQ, err_handle,
  712. BT_ATT_ERR_INVALID_HANDLE);
  713. return 0;
  714. }
  715. /* The Attribute Protocol Find By Type Value Request shall be used with the
  716. * Attribute Type parameter set to the UUID for «Primary Service» and the
  717. * Attribute Value set to the 16-bit Bluetooth UUID or 128-bit UUID for the
  718. * specific primary service.
  719. */
  720. if (type != BT_UUID_GATT_PRIMARY)
  721. {
  722. send_err_rsp(conn, BT_ATT_OP_FIND_TYPE_REQ, start_handle,
  723. BT_ATT_ERR_ATTRIBUTE_NOT_FOUND);
  724. return 0;
  725. }
  726. return att_find_type_rsp(conn, start_handle, end_handle, value, data->len);
  727. }
  728. static bool uuid_create(FAR struct bt_uuid_s *uuid,
  729. FAR struct bt_buf_s *data)
  730. {
  731. if (data->len > sizeof(uuid->u.u128))
  732. {
  733. return false;
  734. }
  735. switch (data->len)
  736. {
  737. case 2:
  738. uuid->type = BT_UUID_16;
  739. uuid->u.u16 = bt_buf_get_le16(data);
  740. return true;
  741. case 16:
  742. uuid->type = BT_UUID_128;
  743. memcpy(uuid->u.u128, data->data, data->len);
  744. return true;
  745. }
  746. return false;
  747. }
  748. static uint8_t read_type_cb(FAR const struct bt_gatt_attr_s *attr,
  749. FAR void *user_data)
  750. {
  751. FAR struct read_type_data_s *data = user_data;
  752. FAR struct bt_att_s *att = data->conn->att;
  753. int read;
  754. /* Skip if doesn't match */
  755. if (bt_uuid_cmp(attr->uuid, data->uuid))
  756. {
  757. return BT_GATT_ITER_CONTINUE;
  758. }
  759. wlinfo("handle 0x%04x\n", attr->handle);
  760. /* Fast forward to next item position */
  761. data->item = bt_buf_extend(data->buf, sizeof(*data->item));
  762. data->item->handle = BT_HOST2LE16(attr->handle);
  763. /* Read attribute value and store in the buffer */
  764. read = attr->read(data->conn, attr, data->buf->data + data->buf->len,
  765. att->mtu - data->buf->len, 0);
  766. if (read < 0)
  767. {
  768. /* TODO: Handle read errors */
  769. return BT_GATT_ITER_STOP;
  770. }
  771. if (!data->rsp->len)
  772. {
  773. /* Set len to be the first item found */
  774. data->rsp->len = read + sizeof(*data->item);
  775. }
  776. else if (data->rsp->len != read + sizeof(*data->item))
  777. {
  778. /* All items should have the same size */
  779. data->buf->len -= sizeof(*data->item);
  780. return BT_GATT_ITER_STOP;
  781. }
  782. bt_buf_extend(data->buf, read);
  783. /* Return true only if there are still space for more items */
  784. return att->mtu - data->buf->len > data->rsp->len ?
  785. BT_GATT_ITER_CONTINUE : BT_GATT_ITER_STOP;
  786. }
  787. static uint8_t att_read_type_rsp(FAR struct bt_conn_s *conn,
  788. FAR struct bt_uuid_s *uuid,
  789. uint16_t start_handle,
  790. uint16_t end_handle)
  791. {
  792. struct read_type_data_s data;
  793. memset(&data, 0, sizeof(data));
  794. data.buf = bt_att_create_pdu(conn, BT_ATT_OP_READ_TYPE_RSP,
  795. sizeof(*data.rsp));
  796. if (!data.buf)
  797. {
  798. return BT_ATT_ERR_UNLIKELY;
  799. }
  800. data.conn = conn;
  801. data.uuid = uuid;
  802. data.rsp = bt_buf_extend(data.buf, sizeof(*data.rsp));
  803. data.rsp->len = 0;
  804. bt_gatt_foreach_attr(start_handle, end_handle, read_type_cb, &data);
  805. if (!data.rsp->len)
  806. {
  807. bt_buf_release(data.buf);
  808. /* Response here since handle is set */
  809. send_err_rsp(conn, BT_ATT_OP_READ_TYPE_REQ, start_handle,
  810. BT_ATT_ERR_ATTRIBUTE_NOT_FOUND);
  811. return 0;
  812. }
  813. bt_l2cap_send(conn, BT_L2CAP_CID_ATT, data.buf);
  814. return 0;
  815. }
  816. static uint8_t att_read_type_req(FAR struct bt_conn_s *conn,
  817. FAR struct bt_buf_s *data)
  818. {
  819. FAR struct bt_att_read_type_req_s *req;
  820. struct bt_uuid_s uuid;
  821. uint16_t start_handle;
  822. uint16_t end_handle;
  823. uint16_t err_handle;
  824. /* Type can only be UUID16 or UUID128 */
  825. if (data->len != sizeof(*req) + sizeof(uuid.u.u16) &&
  826. data->len != sizeof(*req) + sizeof(uuid.u.u128))
  827. {
  828. return BT_ATT_ERR_INVALID_PDU;
  829. }
  830. req = (FAR void *)data->data;
  831. start_handle = BT_LE162HOST(req->start_handle);
  832. end_handle = BT_LE162HOST(req->end_handle);
  833. bt_buf_consume(data, sizeof(*req));
  834. if (!uuid_create(&uuid, data))
  835. {
  836. return BT_ATT_ERR_UNLIKELY;
  837. }
  838. wlinfo("start_handle 0x%04x end_handle 0x%04x type %u\n",
  839. start_handle, end_handle, uuid.u.u16);
  840. if (!range_is_valid(start_handle, end_handle, &err_handle))
  841. {
  842. send_err_rsp(conn, BT_ATT_OP_READ_TYPE_REQ, err_handle,
  843. BT_ATT_ERR_INVALID_HANDLE);
  844. return 0;
  845. }
  846. return att_read_type_rsp(conn, &uuid, start_handle, end_handle);
  847. }
  848. static uint8_t err_to_att(int err)
  849. {
  850. wlinfo("%d", err);
  851. switch (err)
  852. {
  853. case -EINVAL:
  854. return BT_ATT_ERR_INVALID_OFFSET;
  855. case -EFBIG:
  856. return BT_ATT_ERR_INVALID_ATTRIBUTE_LEN;
  857. default:
  858. return BT_ATT_ERR_UNLIKELY;
  859. }
  860. }
  861. static uint8_t check_perm(FAR struct bt_conn_s *conn,
  862. FAR const struct bt_gatt_attr_s *attr,
  863. uint8_t mask)
  864. {
  865. if ((mask & BT_GATT_PERM_READ) && !(attr->perm & BT_GATT_PERM_READ))
  866. {
  867. return BT_ATT_ERR_READ_NOT_PERMITTED;
  868. }
  869. if ((mask & BT_GATT_PERM_WRITE) && !(attr->perm & BT_GATT_PERM_WRITE))
  870. {
  871. return BT_ATT_ERR_READ_NOT_PERMITTED;
  872. }
  873. mask &= attr->perm;
  874. if (mask & BT_GATT_PERM_AUTHEN_MASK)
  875. {
  876. /* TODO: Check conn authentication */
  877. return BT_ATT_ERR_AUTHENTICATION;
  878. }
  879. if ((mask & BT_GATT_PERM_ENCRYPT_MASK) && !conn->encrypt)
  880. {
  881. return BT_ATT_ERR_INSUFFICIENT_ENCRYPTION;
  882. }
  883. if (mask & BT_GATT_PERM_AUTHOR)
  884. {
  885. return BT_ATT_ERR_AUTHORIZATION;
  886. }
  887. return 0;
  888. }
  889. static uint8_t read_cb(FAR const struct bt_gatt_attr_s *attr,
  890. FAR void *user_data)
  891. {
  892. FAR struct read_data_s *data = user_data;
  893. FAR struct bt_att_s *att = data->conn->att;
  894. int read;
  895. wlinfo("handle 0x%04x\n", attr->handle);
  896. data->rsp = bt_buf_extend(data->buf, sizeof(*data->rsp));
  897. if (!attr->read)
  898. {
  899. data->err = BT_ATT_ERR_READ_NOT_PERMITTED;
  900. return BT_GATT_ITER_STOP;
  901. }
  902. /* Check attribute permissions */
  903. data->err = check_perm(data->conn, attr, BT_GATT_PERM_READ_MASK);
  904. if (data->err)
  905. {
  906. return BT_GATT_ITER_STOP;
  907. }
  908. /* Read attribute value and store in the buffer */
  909. read = attr->read(data->conn, attr, data->buf->data + data->buf->len,
  910. att->mtu - data->buf->len, data->offset);
  911. if (read < 0)
  912. {
  913. data->err = err_to_att(read);
  914. return BT_GATT_ITER_STOP;
  915. }
  916. bt_buf_extend(data->buf, read);
  917. return BT_GATT_ITER_CONTINUE;
  918. }
  919. static uint8_t att_read_rsp(FAR struct bt_conn_s *conn, uint8_t op,
  920. uint8_t rsp, uint16_t handle, uint16_t offset)
  921. {
  922. struct read_data_s data;
  923. if (!handle)
  924. {
  925. return BT_ATT_ERR_INVALID_HANDLE;
  926. }
  927. memset(&data, 0, sizeof(data));
  928. data.buf = bt_att_create_pdu(conn, rsp, 0);
  929. if (!data.buf)
  930. {
  931. return BT_ATT_ERR_UNLIKELY;
  932. }
  933. data.conn = conn;
  934. data.offset = offset;
  935. bt_gatt_foreach_attr(handle, handle, read_cb, &data);
  936. /* In case of error discard data and respond with an error */
  937. if (data.err)
  938. {
  939. bt_buf_release(data.buf);
  940. /* Respond here since handle is set */
  941. send_err_rsp(conn, op, handle, data.err);
  942. return 0;
  943. }
  944. bt_l2cap_send(conn, BT_L2CAP_CID_ATT, data.buf);
  945. return 0;
  946. }
  947. static uint8_t att_read_req(FAR struct bt_conn_s *conn,
  948. FAR struct bt_buf_s *data)
  949. {
  950. FAR struct bt_att_read_req_s *req;
  951. uint16_t handle;
  952. req = (void *)data->data;
  953. handle = BT_LE162HOST(req->handle);
  954. wlinfo("handle 0x%04x\n", handle);
  955. return att_read_rsp(conn,
  956. BT_ATT_OP_READ_REQ,
  957. BT_ATT_OP_READ_RSP,
  958. handle,
  959. 0);
  960. }
  961. static uint8_t att_read_blob_req(FAR struct bt_conn_s *conn,
  962. FAR struct bt_buf_s *data)
  963. {
  964. FAR struct bt_att_read_blob_req_s *req;
  965. uint16_t handle;
  966. uint16_t offset;
  967. req = (FAR void *)data->data;
  968. handle = BT_LE162HOST(req->handle);
  969. offset = BT_LE162HOST(req->offset);
  970. wlinfo("handle 0x%04x offset %u\n", handle, offset);
  971. return att_read_rsp(conn, BT_ATT_OP_READ_BLOB_REQ,
  972. BT_ATT_OP_READ_BLOB_RSP, handle, offset);
  973. }
  974. static uint8_t att_read_mult_req(FAR struct bt_conn_s *conn,
  975. FAR struct bt_buf_s *buf)
  976. {
  977. struct read_data_s data;
  978. uint16_t handle;
  979. memset(&data, 0, sizeof(data));
  980. data.buf = bt_att_create_pdu(conn, BT_ATT_OP_READ_MULT_RSP, 0);
  981. if (!data.buf)
  982. {
  983. return BT_ATT_ERR_UNLIKELY;
  984. }
  985. data.conn = conn;
  986. while (buf->len >= sizeof(uint16_t))
  987. {
  988. handle = bt_buf_get_le16(buf);
  989. wlinfo("handle 0x%04x \n", handle);
  990. bt_gatt_foreach_attr(handle, handle, read_cb, &data);
  991. /* Stop reading in case of error */
  992. if (data.err)
  993. {
  994. bt_buf_release(data.buf);
  995. /* Respond here since handle is set */
  996. send_err_rsp(conn, BT_ATT_OP_READ_MULT_REQ, handle, data.err);
  997. return 0;
  998. }
  999. }
  1000. bt_l2cap_send(conn, BT_L2CAP_CID_ATT, data.buf);
  1001. return 0;
  1002. }
  1003. static uint8_t read_group_cb(FAR const struct bt_gatt_attr_s *attr,
  1004. FAR void *user_data)
  1005. {
  1006. FAR struct read_group_data_s *data = user_data;
  1007. FAR struct bt_att_s *att = data->conn->att;
  1008. int read;
  1009. /* If UUID don't match update group end_handle */
  1010. if (bt_uuid_cmp(attr->uuid, data->uuid))
  1011. {
  1012. if (data->group && attr->handle > data->group->end_handle)
  1013. {
  1014. data->group->end_handle = BT_HOST2LE16(attr->handle);
  1015. }
  1016. return BT_GATT_ITER_CONTINUE;
  1017. }
  1018. wlinfo("handle 0x%04x\n", attr->handle);
  1019. /* Stop if there is no space left */
  1020. if (data->rsp->len && att->mtu - data->buf->len < data->rsp->len)
  1021. {
  1022. return BT_GATT_ITER_STOP;
  1023. }
  1024. /* Fast forward to next group position */
  1025. data->group = bt_buf_extend(data->buf, sizeof(*data->group));
  1026. /* Initialize group handle range */
  1027. data->group->start_handle = BT_HOST2LE16(attr->handle);
  1028. data->group->end_handle = BT_HOST2LE16(attr->handle);
  1029. /* Read attribute value and store in the buffer */
  1030. read = attr->read(data->conn, attr, data->buf->data + data->buf->len,
  1031. att->mtu - data->buf->len, 0);
  1032. if (read < 0)
  1033. {
  1034. /* TODO: Handle read errors */
  1035. return BT_GATT_ITER_STOP;
  1036. }
  1037. if (!data->rsp->len)
  1038. {
  1039. /* Set len to be the first group found */
  1040. data->rsp->len = read + sizeof(*data->group);
  1041. }
  1042. else if (data->rsp->len != read + sizeof(*data->group))
  1043. {
  1044. /* All groups entries should have the same size */
  1045. data->buf->len -= sizeof(*data->group);
  1046. return false;
  1047. }
  1048. bt_buf_extend(data->buf, read);
  1049. /* Continue to find the end handle */
  1050. return BT_GATT_ITER_CONTINUE;
  1051. }
  1052. static uint8_t att_read_group_rsp(FAR struct bt_conn_s *conn,
  1053. FAR struct bt_uuid_s *uuid,
  1054. uint16_t start_handle,
  1055. uint16_t end_handle)
  1056. {
  1057. struct read_group_data_s data;
  1058. memset(&data, 0, sizeof(data));
  1059. data.buf = bt_att_create_pdu(conn, BT_ATT_OP_READ_GROUP_RSP,
  1060. sizeof(*data.rsp));
  1061. if (!data.buf)
  1062. {
  1063. return BT_ATT_ERR_UNLIKELY;
  1064. }
  1065. data.conn = conn;
  1066. data.uuid = uuid;
  1067. data.rsp = bt_buf_extend(data.buf, sizeof(*data.rsp));
  1068. data.rsp->len = 0;
  1069. bt_gatt_foreach_attr(start_handle, end_handle, read_group_cb, &data);
  1070. if (!data.rsp->len)
  1071. {
  1072. bt_buf_release(data.buf);
  1073. /* Respond here since handle is set */
  1074. send_err_rsp(conn, BT_ATT_OP_READ_GROUP_REQ, start_handle,
  1075. BT_ATT_ERR_ATTRIBUTE_NOT_FOUND);
  1076. return 0;
  1077. }
  1078. bt_l2cap_send(conn, BT_L2CAP_CID_ATT, data.buf);
  1079. return 0;
  1080. }
  1081. static uint8_t att_read_group_req(FAR struct bt_conn_s *conn,
  1082. FAR struct bt_buf_s *data)
  1083. {
  1084. FAR struct bt_att_read_group_req_s *req;
  1085. struct bt_uuid_s uuid;
  1086. uint16_t start_handle;
  1087. uint16_t end_handle;
  1088. uint16_t err_handle;
  1089. /* Type can only be UUID16 or UUID128 */
  1090. if (data->len != sizeof(*req) + sizeof(uuid.u.u16) &&
  1091. data->len != sizeof(*req) + sizeof(uuid.u.u128))
  1092. {
  1093. return BT_ATT_ERR_INVALID_PDU;
  1094. }
  1095. req = (FAR void *)data->data;
  1096. start_handle = BT_LE162HOST(req->start_handle);
  1097. end_handle = BT_LE162HOST(req->end_handle);
  1098. bt_buf_consume(data, sizeof(*req));
  1099. if (!uuid_create(&uuid, data))
  1100. {
  1101. return BT_ATT_ERR_UNLIKELY;
  1102. }
  1103. wlinfo("start_handle 0x%04x end_handle 0x%04x type %u\n",
  1104. start_handle, end_handle, uuid.u.u16);
  1105. if (!range_is_valid(start_handle, end_handle, &err_handle))
  1106. {
  1107. send_err_rsp(conn, BT_ATT_OP_READ_GROUP_REQ, err_handle,
  1108. BT_ATT_ERR_INVALID_HANDLE);
  1109. return 0;
  1110. }
  1111. /* Core v4.2, Vol 3, sec 2.5.3 Attribute Grouping: Not all of the grouping
  1112. * attributes can be used in the ATT Read By Group Type Request. The
  1113. * «Primary Service» and «Secondary Service» grouping types may be used
  1114. * in the Read By Group Type Request. The «Characteristic» grouping type
  1115. * shall not be used in the ATT Read By Group Type Request.
  1116. */
  1117. if (bt_uuid_cmp(&uuid, &g_primary_uuid) &&
  1118. bt_uuid_cmp(&uuid, &g_secondary_uuid))
  1119. {
  1120. send_err_rsp(conn, BT_ATT_OP_READ_GROUP_REQ, start_handle,
  1121. BT_ATT_ERR_UNSUPPORTED_GROUP_TYPE);
  1122. return 0;
  1123. }
  1124. return att_read_group_rsp(conn, &uuid, start_handle, end_handle);
  1125. }
  1126. static uint8_t write_cb(FAR const struct bt_gatt_attr_s *attr,
  1127. FAR void *user_data)
  1128. {
  1129. FAR struct write_data_s *data = user_data;
  1130. int write;
  1131. wlinfo("handle 0x%04x\n", attr->handle);
  1132. /* Check for write support and flush support in case of prepare */
  1133. if (!attr->write ||
  1134. (data->op == BT_ATT_OP_PREPARE_WRITE_REQ && !attr->flush))
  1135. {
  1136. data->err = BT_ATT_ERR_WRITE_NOT_PERMITTED;
  1137. return BT_GATT_ITER_STOP;
  1138. }
  1139. /* Check attribute permissions */
  1140. data->err = check_perm(data->conn, attr, BT_GATT_PERM_WRITE_MASK);
  1141. if (data->err)
  1142. {
  1143. return BT_GATT_ITER_STOP;
  1144. }
  1145. /* Read attribute value and store in the buffer */
  1146. write = attr->write(data->conn,
  1147. attr,
  1148. data->value,
  1149. data->len,
  1150. data->offset);
  1151. if (write < 0 || write != data->len)
  1152. {
  1153. data->err = err_to_att(write);
  1154. return BT_GATT_ITER_STOP;
  1155. }
  1156. /* Flush in case of regular write operation */
  1157. if (attr->flush && data->op != BT_ATT_OP_PREPARE_WRITE_REQ)
  1158. {
  1159. write = attr->flush(data->conn, attr, BT_GATT_FLUSH_SYNC);
  1160. if (write < 0)
  1161. {
  1162. data->err = err_to_att(write);
  1163. return BT_GATT_ITER_STOP;
  1164. }
  1165. }
  1166. data->err = 0;
  1167. return BT_GATT_ITER_CONTINUE;
  1168. }
  1169. static uint8_t att_write_rsp(FAR struct bt_conn_s *conn, uint8_t op,
  1170. uint8_t rsp, uint16_t handle,
  1171. uint16_t offset, FAR const void *value,
  1172. uint8_t len)
  1173. {
  1174. struct write_data_s data;
  1175. if (!handle)
  1176. {
  1177. return BT_ATT_ERR_INVALID_HANDLE;
  1178. }
  1179. memset(&data, 0, sizeof(data));
  1180. /* Only allocate buf if required to respond */
  1181. if (rsp)
  1182. {
  1183. data.buf = bt_att_create_pdu(conn, rsp, 0);
  1184. if (!data.buf)
  1185. {
  1186. return BT_ATT_ERR_UNLIKELY;
  1187. }
  1188. }
  1189. data.conn = conn;
  1190. data.op = op;
  1191. data.offset = offset;
  1192. data.value = value;
  1193. data.len = len;
  1194. data.err = BT_ATT_ERR_INVALID_HANDLE;
  1195. bt_gatt_foreach_attr(handle, handle, write_cb, &data);
  1196. /* In case of error discard data and respond with an error */
  1197. if (data.err)
  1198. {
  1199. if (rsp)
  1200. {
  1201. bt_buf_release(data.buf);
  1202. /* Respond here since handle is set */
  1203. send_err_rsp(conn, op, handle, data.err);
  1204. }
  1205. return 0;
  1206. }
  1207. if (data.buf)
  1208. {
  1209. /* Add prepare write response */
  1210. if (rsp == BT_ATT_OP_PREPARE_WRITE_RSP)
  1211. {
  1212. FAR struct bt_att_prepare_write_rsp_s *wrrsp;
  1213. wrrsp = bt_buf_extend(data.buf, sizeof(*wrrsp));
  1214. wrrsp->handle = BT_HOST2LE16(handle);
  1215. wrrsp->offset = BT_HOST2LE16(offset);
  1216. bt_buf_extend(data.buf, len);
  1217. memcpy(wrrsp->value, value, len);
  1218. }
  1219. bt_l2cap_send(conn, BT_L2CAP_CID_ATT, data.buf);
  1220. }
  1221. return 0;
  1222. }
  1223. static uint8_t att_write_req(FAR struct bt_conn_s *conn,
  1224. FAR struct bt_buf_s *data)
  1225. {
  1226. FAR struct bt_att_write_req_s *req;
  1227. uint16_t handle;
  1228. req = (FAR void *)data->data;
  1229. handle = BT_LE162HOST(req->handle);
  1230. bt_buf_consume(data, sizeof(*req));
  1231. wlinfo("handle 0x%04x\n", handle);
  1232. return att_write_rsp(conn, BT_ATT_OP_WRITE_REQ, BT_ATT_OP_WRITE_RSP,
  1233. handle, 0, data->data, data->len);
  1234. }
  1235. static uint8_t att_prepare_write_req(FAR struct bt_conn_s *conn,
  1236. FAR struct bt_buf_s *data)
  1237. {
  1238. FAR struct bt_att_prepare_write_req_s *req;
  1239. uint16_t handle;
  1240. uint16_t offset;
  1241. req = (FAR void *)data->data;
  1242. handle = BT_LE162HOST(req->handle);
  1243. offset = BT_LE162HOST(req->offset);
  1244. bt_buf_consume(data, sizeof(*req));
  1245. wlinfo("handle 0x%04x offset %u\n", handle, offset);
  1246. return att_write_rsp(conn, BT_ATT_OP_PREPARE_WRITE_REQ,
  1247. BT_ATT_OP_PREPARE_WRITE_RSP, handle, offset,
  1248. data->data, data->len);
  1249. }
  1250. typedef CODE uint8_t
  1251. (*bt_gatt_attr_func_t)(FAR const struct bt_gatt_attr_s *attr,
  1252. FAR void *user_data);
  1253. static uint8_t flush_cb(FAR const struct bt_gatt_attr_s *attr,
  1254. FAR void *user_data)
  1255. {
  1256. FAR struct flush_data_s *data = user_data;
  1257. int err;
  1258. /* If attribute cannot be flushed continue to next */
  1259. if (!attr->flush)
  1260. {
  1261. return BT_GATT_ITER_CONTINUE;
  1262. }
  1263. wlinfo("handle 0x%04x flags 0x%02x\n", attr->handle, data->flags);
  1264. /* Flush attribute any data cached to be written */
  1265. err = attr->flush(data->conn, attr, data->flags);
  1266. if (err < 0)
  1267. {
  1268. data->err = err_to_att(err);
  1269. return BT_GATT_ITER_STOP;
  1270. }
  1271. data->err = 0;
  1272. return BT_GATT_ITER_CONTINUE;
  1273. }
  1274. static uint8_t att_exec_write_rsp(FAR struct bt_conn_s *conn, uint8_t flags)
  1275. {
  1276. struct flush_data_s data;
  1277. memset(&data, 0, sizeof(data));
  1278. data.buf = bt_att_create_pdu(conn, BT_ATT_OP_EXEC_WRITE_RSP, 0);
  1279. if (!data.buf)
  1280. {
  1281. return BT_ATT_ERR_UNLIKELY;
  1282. }
  1283. data.conn = conn;
  1284. data.flags = flags;
  1285. /* Apply to the whole database */
  1286. bt_gatt_foreach_attr(0x0000, 0xffff, flush_cb, &data);
  1287. /* In case of error discard data */
  1288. if (data.err)
  1289. {
  1290. bt_buf_release(data.buf);
  1291. return data.err;
  1292. }
  1293. bt_l2cap_send(conn, BT_L2CAP_CID_ATT, data.buf);
  1294. return 0;
  1295. }
  1296. static uint8_t att_exec_write_req(FAR struct bt_conn_s *conn,
  1297. FAR struct bt_buf_s *data)
  1298. {
  1299. FAR struct bt_att_exec_write_req_s *req;
  1300. req = (FAR void *)data->data;
  1301. wlinfo("flags 0x%02x\n", req->flags);
  1302. return att_exec_write_rsp(conn, req->flags);
  1303. }
  1304. static uint8_t att_write_cmd(FAR struct bt_conn_s *conn,
  1305. FAR struct bt_buf_s *data)
  1306. {
  1307. FAR struct bt_att_write_cmd_s *req;
  1308. uint16_t handle;
  1309. if (data->len < sizeof(*req))
  1310. {
  1311. /* Commands don't have any response */
  1312. return 0;
  1313. }
  1314. req = (FAR void *)data->data;
  1315. handle = BT_LE162HOST(req->handle);
  1316. wlinfo("handle 0x%04x\n", handle);
  1317. return att_write_rsp(conn, 0, 0, handle, 0, data->data, data->len);
  1318. }
  1319. static uint8_t att_signed_write_cmd(FAR struct bt_conn_s *conn,
  1320. FAR struct bt_buf_s *data)
  1321. {
  1322. FAR struct bt_att_signed_write_cmd_s *req;
  1323. uint16_t handle;
  1324. req = (FAR void *)data->data;
  1325. handle = BT_LE162HOST(req->handle);
  1326. bt_buf_consume(data, sizeof(*req));
  1327. wlinfo("handle 0x%04x\n", handle);
  1328. /* TODO: Validate signature */
  1329. return att_write_rsp(conn, 0, 0, handle, 0, data->data,
  1330. data->len - sizeof(struct bt_att_signature_s));
  1331. }
  1332. static uint8_t att_error_rsp(FAR struct bt_conn_s *conn,
  1333. FAR struct bt_buf_s *data)
  1334. {
  1335. FAR struct bt_att_s *att = conn->att;
  1336. FAR struct bt_att_error_rsp_s *rsp;
  1337. uint8_t err;
  1338. rsp = (FAR void *)data->data;
  1339. wlinfo("request 0x%02x handle 0x%04x error 0x%02x\n",
  1340. rsp->request, BT_LE162HOST(rsp->handle), rsp->error);
  1341. /* Match request with response */
  1342. err = rsp->request == att->req.op ? rsp->error : BT_ATT_ERR_UNLIKELY;
  1343. return att_handle_rsp(conn, NULL, 0, err);
  1344. }
  1345. static uint8_t att_handle_find_info_rsp(FAR struct bt_conn_s *conn,
  1346. FAR struct bt_buf_s *buf)
  1347. {
  1348. wlinfo("\n");
  1349. return att_handle_rsp(conn, buf->data, buf->len, 0);
  1350. }
  1351. static uint8_t att_handle_find_type_rsp(FAR struct bt_conn_s *conn,
  1352. FAR struct bt_buf_s *buf)
  1353. {
  1354. wlinfo("\n");
  1355. return att_handle_rsp(conn, buf->data, buf->len, 0);
  1356. }
  1357. static uint8_t att_handle_read_type_rsp(FAR struct bt_conn_s *conn,
  1358. FAR struct bt_buf_s *buf)
  1359. {
  1360. wlinfo("\n");
  1361. return att_handle_rsp(conn, buf->data, buf->len, 0);
  1362. }
  1363. static uint8_t att_handle_read_rsp(FAR struct bt_conn_s *conn,
  1364. FAR struct bt_buf_s *buf)
  1365. {
  1366. wlinfo("\n");
  1367. return att_handle_rsp(conn, buf->data, buf->len, 0);
  1368. }
  1369. static uint8_t att_handle_read_blob_rsp(FAR struct bt_conn_s *conn,
  1370. FAR struct bt_buf_s *buf)
  1371. {
  1372. wlinfo("\n");
  1373. return att_handle_rsp(conn, buf->data, buf->len, 0);
  1374. }
  1375. static uint8_t att_handle_read_mult_rsp(FAR struct bt_conn_s *conn,
  1376. FAR struct bt_buf_s *buf)
  1377. {
  1378. wlinfo("\n");
  1379. return att_handle_rsp(conn, buf->data, buf->len, 0);
  1380. }
  1381. static uint8_t att_handle_write_rsp(FAR struct bt_conn_s *conn,
  1382. FAR struct bt_buf_s *buf)
  1383. {
  1384. wlinfo("\n");
  1385. return att_handle_rsp(conn, buf->data, buf->len, 0);
  1386. }
  1387. static void bt_att_receive(FAR struct bt_conn_s *conn,
  1388. FAR struct bt_buf_s *buf, FAR void *context,
  1389. uint16_t cid)
  1390. {
  1391. FAR struct bt_att_hdr_s *hdr = (FAR void *)buf->data;
  1392. uint8_t err = BT_ATT_ERR_NOT_SUPPORTED;
  1393. size_t i;
  1394. DEBUGASSERT(conn->att);
  1395. if (buf->len < sizeof(*hdr))
  1396. {
  1397. wlerr("ERROR: Too small ATT PDU received\n");
  1398. goto done;
  1399. }
  1400. wlinfo("Received ATT code 0x%02x len %u\n", hdr->code, buf->len);
  1401. bt_buf_consume(buf, sizeof(*hdr));
  1402. for (i = 0; i < NHANDLERS; i++)
  1403. {
  1404. if (hdr->code != g_handlers[i].op)
  1405. {
  1406. continue;
  1407. }
  1408. if (buf->len < g_handlers[i].expect_len)
  1409. {
  1410. wlerr("ERROR: Invalid len %u for code 0x%02x\n",
  1411. buf->len, hdr->code);
  1412. err = BT_ATT_ERR_INVALID_PDU;
  1413. break;
  1414. }
  1415. err = g_handlers[i].func(conn, buf);
  1416. break;
  1417. }
  1418. /* Commands don't have response */
  1419. if ((hdr->code & BT_ATT_OP_CMD_MASK))
  1420. {
  1421. goto done;
  1422. }
  1423. if (err)
  1424. {
  1425. wlinfo("ATT error 0x%02x", err);
  1426. send_err_rsp(conn, hdr->code, 0, err);
  1427. }
  1428. done:
  1429. bt_buf_release(buf);
  1430. }
  1431. static void bt_att_connected(FAR struct bt_conn_s *conn, FAR void *context,
  1432. uint16_t cid)
  1433. {
  1434. int i;
  1435. wlinfo("conn %p handle %u\n", conn, conn->handle);
  1436. for (i = 0; i < CONFIG_BLUETOOTH_MAX_CONN; i++)
  1437. {
  1438. FAR struct bt_att_s *att = &g_bt_att_pool[i];
  1439. if (!att->conn)
  1440. {
  1441. att->conn = conn;
  1442. conn->att = att;
  1443. att->mtu = BT_ATT_DEFAULT_LE_MTU;
  1444. bt_gatt_connected(conn);
  1445. return;
  1446. }
  1447. }
  1448. wlerr("ERROR: No available ATT context for conn %p\n", conn);
  1449. }
  1450. static void bt_att_disconnected(FAR struct bt_conn_s *conn,
  1451. FAR void *context, uint16_t cid)
  1452. {
  1453. FAR struct bt_att_s *att = conn->att;
  1454. if (!att)
  1455. {
  1456. return;
  1457. }
  1458. wlinfo("conn %p handle %u\n", conn, conn->handle);
  1459. conn->att = NULL;
  1460. memset(att, 0, sizeof(*att));
  1461. bt_gatt_disconnected(conn);
  1462. }
  1463. /****************************************************************************
  1464. * Public Functions
  1465. ****************************************************************************/
  1466. void bt_att_initialize(void)
  1467. {
  1468. static struct bt_l2cap_chan_s chan =
  1469. {
  1470. .cid = BT_L2CAP_CID_ATT,
  1471. .receive = bt_att_receive,
  1472. .connected = bt_att_connected,
  1473. .disconnected = bt_att_disconnected,
  1474. };
  1475. bt_l2cap_chan_register(&chan);
  1476. }
  1477. FAR struct bt_buf_s *bt_att_create_pdu(FAR struct bt_conn_s *conn,
  1478. uint8_t op,
  1479. size_t len)
  1480. {
  1481. FAR struct bt_att_hdr_s *hdr;
  1482. FAR struct bt_buf_s *buf;
  1483. FAR FAR struct bt_att_s *att = conn->att;
  1484. if (len + sizeof(op) > att->mtu)
  1485. {
  1486. wlwarn("ATT MTU exceeded, max %u, wanted %zu\n", att->mtu, len);
  1487. return NULL;
  1488. }
  1489. buf = bt_l2cap_create_pdu(conn);
  1490. if (!buf)
  1491. {
  1492. return NULL;
  1493. }
  1494. hdr = bt_buf_extend(buf, sizeof(*hdr));
  1495. hdr->code = op;
  1496. return buf;
  1497. }
  1498. int bt_att_send(FAR struct bt_conn_s *conn, FAR struct bt_buf_s *buf,
  1499. bt_att_func_t func, FAR void *user_data,
  1500. bt_att_destroy_t destroy)
  1501. {
  1502. FAR struct bt_att_s *att;
  1503. if (!conn)
  1504. {
  1505. return -EINVAL;
  1506. }
  1507. att = conn->att;
  1508. if (!att)
  1509. {
  1510. return -ENOTCONN;
  1511. }
  1512. if (func)
  1513. {
  1514. FAR struct bt_att_hdr_s *hdr;
  1515. /* Check if there is a request pending */
  1516. if (att->req.func)
  1517. {
  1518. /* TODO: Allow more than one pending request */
  1519. return -EBUSY;
  1520. }
  1521. hdr = (void *)buf->data;
  1522. att->req.op = hdr->code;
  1523. att->req.func = func;
  1524. att->req.user_data = user_data;
  1525. att->req.destroy = destroy;
  1526. }
  1527. bt_l2cap_send(conn, BT_L2CAP_CID_ATT, buf);
  1528. return 0;
  1529. }
  1530. void bt_att_cancel(FAR struct bt_conn_s *conn)
  1531. {
  1532. FAR struct bt_att_s *att;
  1533. if (!conn)
  1534. {
  1535. return;
  1536. }
  1537. att = conn->att;
  1538. if (!att)
  1539. {
  1540. return;
  1541. }
  1542. att_req_destroy(&att->req);
  1543. }