FastArduino v1.10
C++ library to build fast but small Arduino/AVR projects
Loading...
Searching...
No Matches
i2c_handler_atmega.h
Go to the documentation of this file.
1// Copyright 2016-2023 Jean-Francois Poilpret
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
16
22#ifndef I2C_HANDLER_ATMEGA_HH
23#define I2C_HANDLER_ATMEGA_HH
24
25#include <util/delay_basic.h>
26
27#include "i2c.h"
28#include "future.h"
29#include "queue.h"
30#include "interrupts.h"
31#include "bits.h"
32#include "utilities.h"
33#include "i2c_handler_common.h"
34
35// Prevent direct inclusion (must be done through i2c_handler.h)
36#ifndef I2C_HANDLER_HH
37#error "i2c_handler_atmega.h shall not be directly included! Include 'i2c_handler.h' instead."
38#endif
39// Prevent inclusion for ATtiny architecture
40#ifndef TWCR
41#error "i2c_handler_atmega.h cannot be included in an ATtiny program!"
42#endif
43
49#define I2C_TRUE_ASYNC 1
50
57#define REGISTER_I2C_ISR(MANAGER) \
58ISR(TWI_vect) \
59{ \
60 i2c::isr_handler::i2c_change<MANAGER>(); \
61}
62
76#define REGISTER_I2C_ISR_FUNCTION(MANAGER, CALLBACK) \
77ISR(TWI_vect) \
78{ \
79 i2c::isr_handler::i2c_change_function<MANAGER, CALLBACK>(); \
80}
81
96#define REGISTER_I2C_ISR_METHOD(MANAGER, HANDLER, CALLBACK) \
97ISR(TWI_vect) \
98{ \
99 i2c::isr_handler::i2c_change_method<MANAGER, HANDLER, CALLBACK>(); \
100}
101
108#define DECL_I2C_ISR_HANDLERS_FRIEND \
109 friend struct i2c::isr_handler; \
110 DECL_TWI_FRIENDS
111
112namespace i2c
113{
118 enum class I2CCallback : uint8_t
119 {
121 NONE = 0,
127 ERROR
128 };
129
131 template<I2CErrorPolicy POLICY = I2CErrorPolicy::DO_NOTHING> struct I2CErrorPolicySupport
132 {
133 I2CErrorPolicySupport() = default;
134 template<typename T>
135 void handle_error(UNUSED const I2CCommand<T>& current, UNUSED containers::Queue<I2CCommand<T>>& commands)
136 {
137 // Intentionally empty: do nothing in this policy
138 }
139 };
140 template<> struct I2CErrorPolicySupport<I2CErrorPolicy::CLEAR_ALL_COMMANDS>
141 {
142 I2CErrorPolicySupport() = default;
143 template<typename T>
144 void handle_error(UNUSED const I2CCommand<T>& current, containers::Queue<I2CCommand<T>>& commands)
145 {
146 commands.clear_();
147 }
148 };
149 template<> struct I2CErrorPolicySupport<I2CErrorPolicy::CLEAR_TRANSACTION_COMMANDS>
150 {
151 I2CErrorPolicySupport() = default;
152 template<typename T>
153 void handle_error(const I2CCommand<T>& current, containers::Queue<I2CCommand<T>>& commands)
154 {
155 // Clear command belonging to the same transaction (i.e. same future)
156 const auto future = current.future();
157 I2CCommand<T> command;
158 while (commands.peek_(command))
159 {
160 if (command.future() != future)
161 break;
162 commands.pull_(command);
163 }
164 }
165 };
167
168 //==============
169 // Sync Handler
170 //==============
172 template<I2CMode MODE_, bool HAS_STATUS_ = false, typename STATUS_HOOK_ = I2C_STATUS_HOOK>
173 class ATmegaI2CSyncHandler
174 {
175 private:
176 using MODE_TRAIT = I2CMode_trait<MODE_>;
177 using I2C_TRAIT = board_traits::TWI_trait;
178 using REG8 = board_traits::REG8;
179 using STATUS = I2CStatusSupport<HAS_STATUS_, STATUS_HOOK_>;
180
181 public:
182 explicit ATmegaI2CSyncHandler(STATUS_HOOK_ status_hook = nullptr) : status_hook_{status_hook} {}
183
184 void begin_()
185 {
186 // 1. set SDA/SCL pullups
187 I2C_TRAIT::PORT |= I2C_TRAIT::SCL_SDA_MASK;
188 // 2. set I2C frequency
189 TWBR_ = MODE_TRAIT::FREQUENCY;
190 TWSR_ = 0;
191 // 3. Enable TWI
192 TWCR_ = bits::BV8(TWEN);
193 }
194
195 void end_()
196 {
197 // 1. Disable TWI
198 TWCR_ = 0;
199 // 2. remove SDA/SCL pullups
200 I2C_TRAIT::PORT &= bits::COMPL(I2C_TRAIT::SCL_SDA_MASK);
201 }
202
203 // Low-level methods to handle the bus in an asynchronous way
204 bool exec_start_()
205 {
206 TWCR_ = bits::BV8(TWEN, TWINT, TWSTA);
207 return wait_twint(Status::START_TRANSMITTED);
208 }
209
210 bool exec_repeat_start_()
211 {
212 TWCR_ = bits::BV8(TWEN, TWINT, TWSTA);
213 return wait_twint(Status::REPEAT_START_TRANSMITTED);
214 }
215
216 bool exec_send_slar_(uint8_t target)
217 {
218 send_byte(target | 0x01U);
219 return wait_twint(Status::SLA_R_TRANSMITTED_ACK);
220 }
221
222 bool exec_send_slaw_(uint8_t target)
223 {
224 send_byte(target);
225 return wait_twint(Status::SLA_W_TRANSMITTED_ACK);
226 }
227
228 bool exec_send_data_(uint8_t data)
229 {
230 send_byte(data);
231 return wait_twint(Status::DATA_TRANSMITTED_ACK);
232 }
233
234 bool exec_receive_data_(bool last_byte, uint8_t& data)
235 {
236 const uint8_t twcr = (last_byte ? bits::BV8(TWEN, TWINT) : bits::BV8(TWEN, TWINT, TWEA));
237 const Status expected = (last_byte ? Status::DATA_RECEIVED_NACK : Status::DATA_RECEIVED_ACK);
238 TWCR_ = twcr;
239 if (wait_twint(expected))
240 {
241 data = TWDR_;
242 return true;
243 }
244 return false;
245 }
246
247 void exec_stop_()
248 {
249 TWCR_ = bits::BV8(TWEN, TWINT, TWSTO);
250 }
251
252 private:
253 static constexpr const REG8 TWBR_{TWBR};
254 static constexpr const REG8 TWSR_{TWSR};
255 static constexpr const REG8 TWCR_{TWCR};
256 static constexpr const REG8 TWDR_{TWDR};
257
258 void send_byte(uint8_t data)
259 {
260 TWDR_ = data;
261 TWCR_ = bits::BV8(TWEN, TWINT);
262 }
263
264 bool wait_twint(Status expected_status)
265 {
266 TWCR_.loop_until_bit_set(TWINT);
267 const Status status = Status(TWSR_ & bits::BV8(TWS3, TWS4, TWS5, TWS6, TWS7));
268 status_hook_.call_hook(expected_status, status);
269 return (status == expected_status);
270 }
271
272 STATUS status_hook_;
273 };
275
301 template<I2CMode MODE_, bool HAS_STATUS_, typename STATUS_HOOK_, bool HAS_DEBUG_, typename DEBUG_HOOK_>
303 : public AbstractI2CSyncManager<ATmegaI2CSyncHandler<MODE_, HAS_STATUS_, STATUS_HOOK_>,
304 MODE_, STATUS_HOOK_, HAS_DEBUG_, DEBUG_HOOK_>
305 {
306 private:
308 MODE_, STATUS_HOOK_, HAS_DEBUG_, DEBUG_HOOK_>;
309
310 public:
313 template<typename OUT, typename IN> using FUTURE = typename PARENT::template FUTURE<OUT, IN>;
315
316 protected:
319 STATUS_HOOK_ status_hook = nullptr, DEBUG_HOOK_ debug_hook = nullptr)
320 : PARENT{status_hook, debug_hook} {}
322
323 template<typename> friend class I2CDevice;
324 };
325
326 //===============
327 // Async Manager
328 //===============
356 template<I2CMode MODE_, I2CErrorPolicy POLICY_,
357 bool HAS_STATUS_, typename STATUS_HOOK_, bool HAS_DEBUG_, typename DEBUG_HOOK_>
359 {
360 private:
361 using MODE_TRAIT = I2CMode_trait<MODE_>;
362 using I2C_TRAIT = board_traits::TWI_trait;
363 using REG8 = board_traits::REG8;
364 using STATUS = I2CStatusSupport<HAS_STATUS_, STATUS_HOOK_>;
365 using DEBUG = I2CDebugSupport<HAS_DEBUG_, DEBUG_HOOK_>;
366 using POLICY = I2CErrorPolicySupport<POLICY_>;
367
368 public:
374
379 template<typename OUT, typename IN> using FUTURE = future::Future<OUT, IN>;
380
386
394 void begin()
395 {
396 synchronized begin_();
397 }
398
405 void end()
406 {
407 synchronized end_();
408 }
409
417 void begin_()
418 {
419 // 1. set SDA/SCL pullups
420 I2C_TRAIT::PORT |= I2C_TRAIT::SCL_SDA_MASK;
421 // 2. set I2C frequency
422 TWBR_ = MODE_TRAIT::FREQUENCY;
423 TWSR_ = 0;
424 // 3. Enable TWI
425 TWCR_ = bits::BV8(TWEN);
426 }
427
434 void end_()
435 {
436 // 1. Disable TWI
437 TWCR_ = 0;
438 // 2. remove SDA/SCL pullups
439 I2C_TRAIT::PORT &= bits::COMPL(I2C_TRAIT::SCL_SDA_MASK);
440 }
441
442 protected:
444 template<uint8_t SIZE>
446 I2CCOMMAND (&buffer)[SIZE],
447 STATUS_HOOK_ status_hook = nullptr,
448 DEBUG_HOOK_ debug_hook = nullptr)
449 : commands_{buffer},
450 status_hook_{status_hook}, debug_hook_{debug_hook} {}
452
453 private:
454 bool ensure_num_commands_(uint8_t num_commands) const
455 {
456 return commands_.free_() >= num_commands;
457 }
458
459 bool push_command_(
460 I2CLightCommand command, uint8_t target, ABSTRACT_FUTURE& future)
461 {
462 return commands_.push_(I2CCOMMAND{command, target, future});
463 }
464
465 void last_command_pushed_()
466 {
467 // Check if need to initiate transmission (i.e no current command is executed)
468 if (command_.type().is_none())
469 {
470 // Dequeue first pending command and start TWI operation
471 dequeue_command_(true);
472 }
473 }
474
475 static constexpr const REG8 TWBR_{TWBR};
476 static constexpr const REG8 TWSR_{TWSR};
477 static constexpr const REG8 TWCR_{TWCR};
478 static constexpr const REG8 TWDR_{TWDR};
479
480 // States of execution of an I2C command through ISR calls
481 enum class State : uint8_t
482 {
483 NONE = 0,
484 START,
485 SLAW,
486 SLAR,
487 SEND,
488 RECV,
489 RECV_LAST,
490 STOP
491 };
492
493 ABSTRACT_FUTURE& current_future() const
494 {
495 return command_.future();
496 }
497
498 void send_byte(uint8_t data)
499 {
500 TWDR_ = data;
501 TWCR_ = bits::BV8(TWEN, TWIE, TWINT);
502 }
503
504 // Dequeue the next command in the queue and process it immediately
505 void dequeue_command_(bool first)
506 {
507 if (!commands_.pull_(command_))
508 {
509 command_ = I2CCOMMAND{};
510 current_ = State::NONE;
511 // No more I2C command to execute
512 TWCR_ = bits::BV8(TWINT);
513 return;
514 }
515
516 // Start new commmand
517 current_ = State::START;
518 if (first)
519 exec_start_();
520 else
521 exec_repeat_start_();
522 }
523
524 // Method to compute next state
525 State next_state_()
526 {
527 switch (current_)
528 {
529 case State::START:
530 return (command_.type().is_write() ? State::SLAW : State::SLAR);
531
532 case State::SLAR:
533 case State::RECV:
534 if (command_.byte_count() > 1)
535 return State::RECV;
536 else
537 return State::RECV_LAST;
538
539 case State::RECV_LAST:
540 return State::STOP;
541
542 case State::SLAW:
543 return State::SEND;
544
545 case State::SEND:
546 if (command_.byte_count() >= 1)
547 return State::SEND;
548 else
549 return State::STOP;
550
551 case State::STOP:
552 case State::NONE:
553 return State::NONE;
554 }
555 }
556
557 // Low-level methods to handle the bus in an asynchronous way
558 void exec_start_()
559 {
560 debug_hook_.call_hook(DebugStatus::START);
561 expected_status_ = Status::START_TRANSMITTED;
562 TWCR_ = bits::BV8(TWEN, TWIE, TWINT, TWSTA);
563 }
564 void exec_repeat_start_()
565 {
566 debug_hook_.call_hook(DebugStatus::REPEAT_START);
567 expected_status_ = Status::REPEAT_START_TRANSMITTED;
568 TWCR_ = bits::BV8(TWEN, TWIE, TWINT, TWSTA);
569 }
570 void exec_send_slar_()
571 {
572 debug_hook_.call_hook(DebugStatus::SLAR, command_.target());
573 // Read device address from queue
574 expected_status_ = Status::SLA_R_TRANSMITTED_ACK;
575 send_byte(command_.target() | 0x01U);
576 }
577 void exec_send_slaw_()
578 {
579 debug_hook_.call_hook(DebugStatus::SLAW, command_.target());
580 // Read device address from queue
581 expected_status_ = Status::SLA_W_TRANSMITTED_ACK;
582 send_byte(command_.target());
583 }
584 void exec_send_data_()
585 {
586 // Determine next data byte
587 uint8_t data = 0;
588 ABSTRACT_FUTURE& future = current_future();
589 bool ok = future.get_storage_value_(data);
590 debug_hook_.call_hook(DebugStatus::SEND, data);
591 // This should only happen if there are 2 concurrent consumers for that Future
592 if (ok)
593 command_.decrement_byte_count();
594 else
595 future.set_future_error_(errors::EILSEQ);
596 debug_hook_.call_hook(ok ? DebugStatus::SEND_OK : DebugStatus::SEND_ERROR);
597 expected_status_ = Status::DATA_TRANSMITTED_ACK;
598 send_byte(data);
599 }
600 void exec_receive_data_()
601 {
602 // Is this the last byte to receive?
603 if (command_.byte_count() == 1)
604 {
605 debug_hook_.call_hook(DebugStatus::RECV_LAST);
606 // Send NACK for the last data byte we want
607 expected_status_ = Status::DATA_RECEIVED_NACK;
608 TWCR_ = bits::BV8(TWEN, TWIE, TWINT);
609 }
610 else
611 {
612 debug_hook_.call_hook(DebugStatus::RECV);
613 // Send ACK for data byte if not the last one we want
614 expected_status_ = Status::DATA_RECEIVED_ACK;
615 TWCR_ = bits::BV8(TWEN, TWIE, TWINT, TWEA);
616 }
617 }
618 void exec_stop_(bool error = false)
619 {
620 debug_hook_.call_hook(DebugStatus::STOP);
621 TWCR_ = bits::BV8(TWEN, TWINT, TWSTO);
622 if (!error)
623 expected_status_ = Status::OK;
624 command_ = I2CCOMMAND{};
625 current_ = State::NONE;
626 // If so then delay 4.0us + 4.7us (100KHz) or 0.6us + 1.3us (400KHz)
627 // (ATMEGA328P datasheet 29.7 Tsu;sto + Tbuf)
628 _delay_loop_1(MODE_TRAIT::DELAY_AFTER_STOP);
629 }
630
631 bool is_end_transaction() const
632 {
633 return command_.type().is_end();
634 }
635
636 bool handle_no_error(ABSTRACT_FUTURE& future, Status status)
637 {
638 if (check_no_error(future, status)) return true;
639 policy_.handle_error(command_, commands_);
640 // In case of an error, immediately send a STOP condition
641 exec_stop_(true);
642 dequeue_command_(true);
643 return false;
644 }
645
646 I2CCallback i2c_change()
647 {
648 // Check status Vs. expected status
649 const Status status = Status(TWSR_ & bits::BV8(TWS3, TWS4, TWS5, TWS6, TWS7));
650 ABSTRACT_FUTURE& future = current_future();
651 if (!handle_no_error(future, status))
652 return I2CCallback::ERROR;
653
654 // Handle TWI interrupt when data received
655 if ((current_ == State::RECV) || (current_ == State::RECV_LAST))
656 {
657 const uint8_t data = TWDR_;
658 bool ok = future.set_future_value_(data);
659 // This should only happen in case there are 2 concurrent providers for this future
660 if (ok)
661 command_.decrement_byte_count();
662 else
663 future.set_future_error_(errors::EILSEQ);
664 debug_hook_.call_hook(ok ? DebugStatus::RECV_OK : DebugStatus::RECV_ERROR, data);
665 }
666
667 // Handle next step in current command
669 current_ = next_state_();
670 switch (current_)
671 {
672 case State::NONE:
673 case State::START:
674 // This cannot happen
675 break;
676
677 case State::SLAR:
678 exec_send_slar_();
679 break;
680
681 case State::RECV:
682 case State::RECV_LAST:
683 exec_receive_data_();
684 break;
685
686 case State::SLAW:
687 exec_send_slaw_();
688 break;
689
690 case State::SEND:
691 exec_send_data_();
692 break;
693
694 case State::STOP:
695 // Check if we need to finish the current future
696 if (command_.type().is_finish())
697 future.set_future_finish_();
698 result = (is_end_transaction() ? I2CCallback::END_TRANSACTION : I2CCallback::END_COMMAND);
699 // Check if we need to STOP (no more pending commands in queue)
700 if (commands_.empty_())
701 exec_stop_();
702 // Check if we need to STOP or REPEAT START (current command requires STOP)
703 else if (command_.type().is_stop())
704 {
705 exec_stop_();
706 // Handle next command
707 dequeue_command_(true);
708 }
709 else
710 // Handle next command
711 dequeue_command_(false);
712 }
713 return result;
714 }
715
716 bool check_no_error(ABSTRACT_FUTURE& future, Status status)
717 {
718 status_hook_.call_hook(expected_status_, status);
719 if (status == expected_status_) return true;
720 // Handle special case of last transmitted byte possibly not acknowledged by device
721 if ( (expected_status_ == Status::DATA_TRANSMITTED_ACK)
722 && (status == Status::DATA_TRANSMITTED_NACK)
723 && (command_.byte_count() == 0))
724 return true;
725
726 // The future must be marked as error
727 if (future.status() != future::FutureStatus::ERROR)
728 future.set_future_error_(errors::EPROTO);
729 return false;
730 }
731
732 // Status of current command processing
733 I2CCOMMAND command_;
734
735 // Latest I2C status
736 Status expected_status_ = Status::OK;
737
738 // Status of current command processing
739 State current_ = State::NONE;
740
741 // Queue of commands to execute
743
744 POLICY policy_{};
745 STATUS status_hook_;
746 DEBUG debug_hook_;
747
748 template<typename> friend class I2CDevice;
749 friend struct isr_handler;
750 };
751
766 template<I2CMode MODE_, I2CErrorPolicy POLICY_ = I2CErrorPolicy::CLEAR_ALL_COMMANDS>
768 public AbstractI2CAsyncManager<MODE_, POLICY_, false, I2C_STATUS_HOOK, false, I2C_DEBUG_HOOK>
769 {
771 public:
780 template<uint8_t SIZE>
781 explicit I2CAsyncManager(typename PARENT::I2CCOMMAND (&buffer)[SIZE]) : PARENT{buffer}
782 {
784 }
785 };
786
804 template<
805 I2CMode MODE_,
807 typename DEBUG_HOOK_ = I2C_DEBUG_HOOK>
809 public AbstractI2CAsyncManager<MODE_, POLICY_, false, I2C_STATUS_HOOK, true, DEBUG_HOOK_>
810 {
812 public:
823 template<uint8_t SIZE>
825 typename PARENT::I2CCOMMAND (&buffer)[SIZE], DEBUG_HOOK_ debug_hook)
826 : PARENT{buffer, nullptr, debug_hook}
827 {
829 }
830 };
831
849 template<
850 I2CMode MODE_,
852 typename STATUS_HOOK_ = I2C_STATUS_HOOK>
854 public AbstractI2CAsyncManager<MODE_, POLICY_, true, STATUS_HOOK_, false, I2C_DEBUG_HOOK>
855 {
857 public:
868 template<uint8_t SIZE>
870 typename PARENT::I2CCOMMAND (&buffer)[SIZE], STATUS_HOOK_ status_hook)
871 : PARENT{buffer, status_hook}
872 {
874 }
875 };
876
898 template<
899 I2CMode MODE_,
901 typename STATUS_HOOK_ = I2C_STATUS_HOOK,
902 typename DEBUG_HOOK_ = I2C_DEBUG_HOOK>
904 public AbstractI2CAsyncManager<MODE_, POLICY_, true, STATUS_HOOK_, true, DEBUG_HOOK_>
905 {
907 public:
920 template<uint8_t SIZE>
922 typename PARENT::I2CCOMMAND (&buffer)[SIZE], STATUS_HOOK_ status_hook, DEBUG_HOOK_ debug_hook)
923 : PARENT{buffer, status_hook, debug_hook}
924 {
926 }
927 };
928
937 template<I2CMode MODE_>
939 public AbstractI2CSyncATmegaManager<MODE_, false, I2C_STATUS_HOOK, false, I2C_DEBUG_HOOK>
940 {
942 public:
944 I2CSyncManager() : PARENT{} {}
946 };
947
960 template<I2CMode MODE_, typename STATUS_HOOK_ = I2C_STATUS_HOOK>
962 public AbstractI2CSyncATmegaManager<MODE_, true, STATUS_HOOK_, false, I2C_DEBUG_HOOK>
963 {
965 public:
967 explicit I2CSyncStatusManager(STATUS_HOOK_ status_hook) : PARENT{status_hook} {}
969 };
970
982 template<I2CMode MODE_, typename DEBUG_HOOK_ = I2C_DEBUG_HOOK>
984 public AbstractI2CSyncATmegaManager<MODE_, false, I2C_STATUS_HOOK, true, DEBUG_HOOK_>
985 {
987 public:
989 explicit I2CSyncDebugManager(DEBUG_HOOK_ debug_hook) : PARENT{nullptr, debug_hook} {}
991 };
992
1008 template<I2CMode MODE_, typename STATUS_HOOK_ = I2C_STATUS_HOOK, typename DEBUG_HOOK_ = I2C_DEBUG_HOOK>
1010 public AbstractI2CSyncATmegaManager<MODE_, true, STATUS_HOOK_, true, DEBUG_HOOK_>
1011 {
1013 public:
1015 explicit I2CSyncStatusDebugManager(STATUS_HOOK_ status_hook, DEBUG_HOOK_ debug_hook)
1016 : PARENT{status_hook, debug_hook} {}
1018 };
1019
1021 // Specific traits for I2C Manager
1022 // Async managers first
1023 template<I2CMode MODE_, I2CErrorPolicy POLICY_>
1024 struct I2CManager_trait<I2CAsyncManager<MODE_, POLICY_>>
1025 : I2CManager_trait_impl<true, false, false, MODE_> {};
1026
1027 template<I2CMode MODE_, I2CErrorPolicy POLICY_, typename DEBUG_HOOK_>
1028 struct I2CManager_trait<I2CAsyncDebugManager<MODE_, POLICY_, DEBUG_HOOK_>>
1029 : I2CManager_trait_impl<true, false, true, MODE_> {};
1030
1031 template<I2CMode MODE_, I2CErrorPolicy POLICY_, typename STATUS_HOOK_>
1032 struct I2CManager_trait<I2CAsyncStatusManager<MODE_, POLICY_, STATUS_HOOK_>>
1033 : I2CManager_trait_impl<true, true, false, MODE_> {};
1034
1035 template<I2CMode MODE_, I2CErrorPolicy POLICY_, typename STATUS_HOOK_, typename DEBUG_HOOK_>
1036 struct I2CManager_trait<I2CAsyncStatusDebugManager<MODE_, POLICY_, STATUS_HOOK_, DEBUG_HOOK_>>
1037 : I2CManager_trait_impl<true, true, true, MODE_> {};
1039
1041 struct isr_handler
1042 {
1043 template<typename MANAGER>
1044 static void i2c_change()
1045 {
1046 static_assert(I2CManager_trait<MANAGER>::IS_I2CMANAGER, "MANAGER must be an I2C Manager");
1047 static_assert(I2CManager_trait<MANAGER>::IS_ASYNC, "MANAGER must be an asynchronous I2C Manager");
1048 interrupt::HandlerHolder<MANAGER>::handler()->i2c_change();
1049 }
1050
1051 template<typename MANAGER, void (*CALLBACK_)(I2CCallback, typename MANAGER::ABSTRACT_FUTURE&)>
1052 static void i2c_change_function()
1053 {
1054 using interrupt::HandlerHolder;
1055 static_assert(I2CManager_trait<MANAGER>::IS_I2CMANAGER, "MANAGER must be an I2C Manager");
1056 static_assert(I2CManager_trait<MANAGER>::IS_ASYNC, "MANAGER must be an asynchronous I2C Manager");
1057 typename MANAGER::ABSTRACT_FUTURE& future = HandlerHolder<MANAGER>::handler()->current_future();
1058 I2CCallback callback = HandlerHolder<MANAGER>::handler()->i2c_change();
1059 if (callback != I2CCallback::NONE)
1060 {
1061 CALLBACK_(callback, future);
1062 }
1063 }
1064
1065 template<typename MANAGER, typename HANDLER_,
1066 void (HANDLER_::*CALLBACK_)(I2CCallback, typename MANAGER::ABSTRACT_FUTURE&)>
1067 static void i2c_change_method()
1068 {
1069 using interrupt::HandlerHolder;
1070 using interrupt::CallbackHandler;
1071 static_assert(I2CManager_trait<MANAGER>::IS_I2CMANAGER, "MANAGER must be an I2C Manager");
1072 static_assert(I2CManager_trait<MANAGER>::IS_ASYNC, "MANAGER must be an asynchronous I2C Manager");
1073 typename MANAGER::ABSTRACT_FUTURE& future = HandlerHolder<MANAGER>::handler()->current_future();
1074 I2CCallback callback = HandlerHolder<MANAGER>::handler()->i2c_change();
1075 if (callback != I2CCallback::NONE)
1076 {
1077 using HANDLER =
1078 CallbackHandler<void (HANDLER_::*)(I2CCallback, typename MANAGER::ABSTRACT_FUTURE&), CALLBACK_>;
1079 HANDLER::call(callback, future);
1080 }
1081 }
1082 };
1084}
1085
1086#endif /* I2C_HANDLER_ATMEGA_HH */
Useful bits manipulation utilities.
Queue of type T_ items.
Definition: queue.h:59
Base class for all FakeFutures.
Definition: future.h:1142
Base class for all Futures.
Definition: future.h:426
Actual FakeFuture, it has the exact same API as Future and can be used in lieu of Future.
Definition: future.h:1300
Represent a value to be obtained, in some asynchronous way, in the future.
Definition: future.h:867
Abstract asynchronous I2C Manager.
I2CCommand< ABSTRACT_FUTURE > I2CCOMMAND
The type of I2CCommand to use in the buffer passed to the constructor of this AbstractI2CAsyncManager...
void begin_()
Prepare and enable the MCU for I2C transmission.
void begin()
Prepare and enable the MCU for I2C transmission.
future::AbstractFuture ABSTRACT_FUTURE
The abstract base class of all futures to be defined for this I2C Manager.
void end()
Disable MCU I2C transmission.
void end_()
Disable MCU I2C transmission.
Abstract synchronous I2C Manager for ATmega architecture.
Abstract synchronous I2C Manager for all MCU architectures.
future::AbstractFakeFuture ABSTRACT_FUTURE
The abstract base class of all futures to be defined for this I2C Manager.
Asynchronous I2C Manager for ATmega architecture with debug facility.
I2CAsyncDebugManager(typename PARENT::I2CCOMMAND(&buffer)[SIZE], DEBUG_HOOK_ debug_hook)
Create an asynchronous I2C Manager for ATmega MCUs.
Asynchronous I2C Manager for ATmega architecture.
I2CAsyncManager(typename PARENT::I2CCOMMAND(&buffer)[SIZE])
Create an asynchronous I2C Manager for ATmega MCUs.
Asynchronous I2C Manager for ATmega architecture with debug and status notification facilities.
I2CAsyncStatusDebugManager(typename PARENT::I2CCOMMAND(&buffer)[SIZE], STATUS_HOOK_ status_hook, DEBUG_HOOK_ debug_hook)
Create an asynchronous I2C Manager for ATmega MCUs.
Asynchronous I2C Manager for ATmega architecture with status notification facility.
I2CAsyncStatusManager(typename PARENT::I2CCOMMAND(&buffer)[SIZE], STATUS_HOOK_ status_hook)
Create an asynchronous I2C Manager for ATmega MCUs.
Base class for all I2C devices.
Definition: i2c_device.h:84
Synchronous I2C Manager for ATmega architecture with debug facility.
Synchronous I2C Manager for ATmega architecture.
Synchronous I2C Manager for ATmega architecture with status notification and debug facility.
Synchronous I2C Manager for ATmega architecture wit status notification facility.
#define UNUSED
Specific GCC attribute to declare an argument or variable unused, so that the compiler does not emit ...
Definition: defines.h:45
Utility API to handle the concept of futures.
I2C API common definitions.
Common I2C Manager API.
General API for handling AVR interrupt vectors.
@ NONE
No interrupt will be generated by the Anolog Comparator.
Defines utility methods for bits manipulation.
Definition: bits.h:34
static constexpr uint8_t COMPL(uint8_t value)
Return the uint8_t 2-complement of a byte.
Definition: bits.h:253
static constexpr uint8_t BV8(uint8_t bit)
Create a uint8_t bitmask for the given bit number.
Definition: bits.h:41
constexpr const int EPROTO
Protocol error.
Definition: errors.h:58
constexpr const int EILSEQ
Illegal byte sequence.
Definition: errors.h:65
Contains the API around Future implementation.
Definition: future.h:312
@ ERROR
The status of a Future once a value provider has reported an error to it.
STATUS
Indicate when status should be traced.
Definition: i2c_status.h:47
Define API to define and manage I2C devices.
Definition: i2c.h:51
void(*)(Status expected, Status actual) I2C_STATUS_HOOK
The default status observer hook type.
@ SEND_OK
The latest sent byte has been acknowledged by the slave.
@ SEND_ERROR
The latest sent byte has not been acknowledged by the slave.
@ SLAR
A slave address has just been sent for reading.
@ RECV_OK
I2C Manager has acknowledged the latest received byte from the slave.
@ SEND
A byte has just be sent to the slave.
@ STOP
A stop condition has just been sent.
@ REPEAT_START
A repeat start condition has just been sent.
@ RECV_LAST
The last byte is being received from the slave.
@ START
A start condition has just been sent.
@ RECV
A byte is being received from the slave.
@ RECV_ERROR
I2C Manager has not acknowledged the latest received byte from the slave.
@ SLAW
A slave address has just been sent for writing.
I2CCallback
Type passed to I2C ISR registered callbacks (asynchronous I2C Manager only) when an asynchronous I2C ...
@ END_TRANSACTION
The last I2C command in a transaction has just been finished executing.
@ END_COMMAND
An I2C command has just been finished executed.
@ NONE
An I2C command is being processed (intermediate step).
@ ERROR
An error has occurred during I2C transaction execution.
void(*)(DebugStatus status, uint8_t data) I2C_DEBUG_HOOK
The default debugging hook type.
I2CErrorPolicy
I2C Manager policy to use in case of an error during I2C transaction.
@ CLEAR_ALL_COMMANDS
In case of an error during I2C transaction, then all I2CCommand currently in queue will be removed.
@ CLEAR_TRANSACTION_COMMANDS
In case of an error during I2C transaction, then all pending I2CCommand of the current transaction wi...
I2CMode
I2C available transmission modes.
Definition: i2c.h:168
Status
Transmission status codes.
Definition: i2c.h:67
@ START_TRANSMITTED
[Transmitter/Receiver modes] A START condition has been transmitted.
@ REPEAT_START_TRANSMITTED
[Transmitter/Receiver modes] A repeated START condition has been transmitted.
@ DATA_TRANSMITTED_ACK
[Transmitter mode] Data byte has been transmitted; ACK has been received.
@ SLA_W_TRANSMITTED_ACK
[Transmitter mode] SLA+W has been transmitted; ACK has been received.
@ DATA_TRANSMITTED_NACK
[Transmitter mode] Data byte has been transmitted; NOT ACK has been received.
@ DATA_RECEIVED_ACK
[Receiver mode] Data byte has been transmitted; ACK has been returned.
@ DATA_RECEIVED_NACK
[Receiver mode] Data byte has been transmitted; NOT ACK has been returned.
@ SLA_R_TRANSMITTED_ACK
[Receiver mode] SLA+R has been transmitted; ACK has been received.
@ OK
Code indicating the last called method executed as expected without any issue.
void register_handler(Handler &handler)
Register a class instance containing methods that shall be called back by an ISR.
Definition: interrupts.h:185
Utility API to handle ring-buffer queue containers.
General utilities API that have broad application in programs.