FastArduino v1.10
C++ library to build fast but small Arduino/AVR projects
Loading...
Searching...
No Matches
sonar.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
21#ifndef SONAR_H
22#define SONAR_H
23
24#include <fastarduino/boards/board.h>
25#include <fastarduino/gpio.h>
26#include <fastarduino/time.h>
29
30#include <fastarduino/int.h>
31#include <fastarduino/pci.h>
32
46#define REGISTER_HCSR04_INT_ISR(TIMER, INT_NUM, TRIGGER, ECHO) \
47 ISR(CAT3(INT, INT_NUM, _vect)) \
48 { \
49 devices::sonar::isr_handler::sonar_int<INT_NUM, TIMER, TRIGGER, ECHO>(); \
50 }
51
70#define REGISTER_HCSR04_PCI_ISR(TIMER, PCI_NUM, TRIGGER, ECHO, ...) \
71 ISR(CAT3(PCINT, PCI_NUM, _vect)) \
72 { \
73 devices::sonar::isr_handler::sonar_pci<PCI_NUM, TIMER, TRIGGER, ECHO, ##__VA_ARGS__>(); \
74 }
75
86#define SONAR_PINS(TRIGGER, ECHO) devices::sonar::isr_handler::TriggerEcho<TRIGGER, ECHO>
87
107#define REGISTER_DISTINCT_HCSR04_PCI_ISR(TIMER, PCI_NUM, SONAR_PINS1, ...) \
108 ISR(CAT3(PCINT, PCI_NUM, _vect)) \
109 { \
110 devices::sonar::isr_handler::sonar_distinct_pci<PCI_NUM, TIMER, SONAR_PINS1, ##__VA_ARGS__>(); \
111 }
112
133#define REGISTER_HCSR04_INT_ISR_METHOD(TIMER, INT_NUM, TRIGGER, ECHO, HANDLER, CALLBACK) \
134 ISR(CAT3(INT, INT_NUM, _vect)) \
135 { \
136 devices::sonar::isr_handler::sonar_int_method<INT_NUM, TIMER, TRIGGER, ECHO, HANDLER, CALLBACK>(); \
137 }
138
157#define REGISTER_HCSR04_INT_ISR_FUNCTION(TIMER, INT_NUM, TRIGGER, ECHO, CALLBACK) \
158 ISR(CAT3(INT, INT_NUM, _vect)) \
159 { \
160 devices::sonar::isr_handler::sonar_int_function<INT_NUM, TIMER, TRIGGER, ECHO, CALLBACK>(); \
161 }
162
185#define REGISTER_HCSR04_PCI_ISR_METHOD(TIMER, PCI_NUM, TRIGGER, ECHO, HANDLER, CALLBACK) \
186 ISR(CAT3(PCINT, PCI_NUM, _vect)) \
187 { \
188 devices::sonar::isr_handler::sonar_pci_method<PCI_NUM, TIMER, TRIGGER, ECHO, HANDLER, CALLBACK>(); \
189 }
190
210#define REGISTER_HCSR04_PCI_ISR_FUNCTION(TIMER, PCI_NUM, TRIGGER, ECHO, CALLBACK) \
211 ISR(CAT3(PCINT, PCI_NUM, _vect)) \
212 { \
213 devices::sonar::isr_handler::sonar_pci_function<PCI_NUM, TIMER, TRIGGER, ECHO, CALLBACK>(); \
214 }
215
232#define REGISTER_HCSR04_RTT_TIMEOUT(TIMER_NUM, SONAR, ...) \
233 ISR(CAT3(TIMER, TIMER_NUM, _COMPA_vect)) \
234 { \
235 devices::sonar::isr_handler::sonar_rtt_change<TIMER_NUM, SONAR, ##__VA_ARGS__>(); \
236 }
237
257#define REGISTER_HCSR04_RTT_TIMEOUT_METHOD(TIMER_NUM, HANDLER, CALLBACK, SONAR, ...) \
258 ISR(CAT3(TIMER, TIMER_NUM, _COMPA_vect)) \
259 { \
260 if (devices::sonar::isr_handler::sonar_rtt_change<TIMER_NUM, SONAR, ##__VA_ARGS__>()) \
261 interrupt::CallbackHandler<void (HANDLER::*)(), CALLBACK>::call(); \
262 }
263
282#define REGISTER_HCSR04_RTT_TIMEOUT_FUNCTION(TIMER_NUM, CALLBACK, SONAR, ...) \
283 ISR(CAT3(TIMER, TIMER_NUM, _COMPA_vect)) \
284 { \
285 if (devices::sonar::isr_handler::sonar_rtt_change<TIMER_NUM, SONAR, ##__VA_ARGS__>()) \
286 interrupt::CallbackHandler<void (*)(), CALLBACK>::call(); \
287 }
288
313#define REGISTER_MULTI_HCSR04_PCI_ISR_METHOD(TIMER, PCI_NUM, TRIGGER, ECHO_PORT, ECHO_MASK, HANDLER, CALLBACK) \
314 ISR(CAT3(PCINT, PCI_NUM, _vect)) \
315 { \
316 using ISRHANDLER = devices::sonar::isr_handler; \
317 ISRHANDLER::multi_sonar_pci_method<PCI_NUM, TIMER, TRIGGER, ECHO_PORT, ECHO_MASK, HANDLER, CALLBACK>();\
318 }
319
342#define REGISTER_MULTI_HCSR04_PCI_ISR_FUNCTION(TIMER, PCI_NUM, TRIGGER, ECHO_PORT, ECHO_MASK, CALLBACK) \
343 ISR(CAT3(PCINT, PCI_NUM, _vect)) \
344 { \
345 using ISRHANDLER = devices::sonar::isr_handler; \
346 ISRHANDLER::multi_sonar_pci_function<PCI_NUM, TIMER, TRIGGER, ECHO_PORT, ECHO_MASK, CALLBACK>();\
347 }
348
367#define REGISTER_MULTI_HCSR04_RTT_TIMEOUT_METHOD(TIMER_NUM, SONAR, HANDLER, CALLBACK) \
368 ISR(CAT3(TIMER, TIMER_NUM, _COMPA_vect)) \
369 { \
370 using EVENT = typename SONAR::EVENT; \
371 EVENT event = devices::sonar::isr_handler::multi_sonar_rtt_change<TIMER_NUM, SONAR, EVENT>(); \
372 if (event.timeout()) interrupt::CallbackHandler<void (HANDLER::*)(const EVENT&), CALLBACK>::call(event); \
373 }
374
391#define REGISTER_MULTI_HCSR04_RTT_TIMEOUT_FUNCTION(TIMER_NUM, SONAR, CALLBACK) \
392 ISR(CAT3(TIMER, TIMER_NUM, _COMPA_vect)) \
393 { \
394 using EVENT = typename SONAR::EVENT; \
395 EVENT event = devices::sonar::isr_handler::multi_sonar_rtt_change<TIMER_NUM, SONAR, EVENT>(); \
396 if (event.timeout()) interrupt::CallbackHandler<void (*)(const EVENT&), CALLBACK>::call(event); \
397 }
398
423#define REGISTER_MULTI_HCSR04_RTT_TIMEOUT_TRIGGER_METHOD(TIMER_NUM, SONAR, HANDLER, CB_TIMEOUT, CB_RTT) \
424 ISR(CAT3(TIMER, TIMER_NUM, _COMPA_vect)) \
425 { \
426 using EVENT = typename SONAR::EVENT; \
427 EVENT event = devices::sonar::isr_handler::multi_sonar_rtt_change<TIMER_NUM, SONAR, EVENT>(); \
428 if (event.timeout()) \
429 interrupt::CallbackHandler<void (HANDLER::*)(const EVENT&), CB_TIMEOUT>::call(event); \
430 interrupt::CallbackHandler<void (HANDLER::*)(), CB_RTT>::call(); \
431 }
432
454#define REGISTER_MULTI_HCSR04_RTT_TIMEOUT_TRIGGER_FUNCTION(TIMER_NUM, SONAR, CB_TIMEOUT, CB_RTT) \
455 ISR(CAT3(TIMER, TIMER_NUM, _COMPA_vect)) \
456 { \
457 using EVENT = typename SONAR::EVENT; \
458 EVENT event = devices::sonar::isr_handler::multi_sonar_rtt_change<TIMER_NUM, SONAR, EVENT>(); \
459 if (event.timeout()) \
460 interrupt::CallbackHandler<void (*)(const EVENT&), CB_TIMEOUT>::call(event); \
461 interrupt::CallbackHandler<void (*)(), CB_RTT>::call(); \
462 }
463
476#define DECL_SONAR_ISR_HANDLERS_FRIEND \
477 friend struct devices::sonar::isr_handler; \
478 DECL_INT_ISR_FRIENDS \
479 DECL_PCINT_ISR_FRIENDS \
480 DECL_TIMER_COMP_FRIENDS
481
482namespace devices
483{
496 namespace sonar
497 {
498 }
499}
500
501namespace devices::sonar
502{
509 static constexpr const uint32_t SPEED_OF_SOUND = 340UL;
510
526 static constexpr uint16_t echo_us_to_distance_mm(uint16_t echo_us)
527 {
528 // 340 m/s => 340000mm in 1000000us => 340/1000 mm/us
529 // Divide by 2 as echo time includes full sound round-trip
530 return uint16_t(echo_us * SPEED_OF_SOUND / 1000UL / 2UL);
531 }
532
550 static constexpr uint16_t distance_mm_to_echo_us(uint16_t distance_mm)
551 {
552 // 340 m/s => 340000mm in 1000000us => 340/1000 mm/us
553 // Multiply by 2 as echo time must include full sound round-trip
554 return uint16_t(distance_mm * 1000UL * 2UL / SPEED_OF_SOUND);
555 }
556
570 enum class SonarType : uint8_t
571 {
573 BLOCKING,
580 ASYNC_INT,
588 };
589
599 template<board::Timer NTIMER_> class AbstractSonar
600 {
601 public:
604
614 bool ready() const
615 {
616 return status_ == READY;
617 }
618
629 uint16_t latest_echo_us() const
630 {
631 synchronized
632 {
633 if (status_ == READY)
634 return echo_time_();
635 else
636 return 0;
637 }
638 }
639
640 private:
641 using RAW_TIME = typename RTT::RAW_TIME;
642
643 protected:
645 AbstractSonar(const AbstractSonar&) = delete;
646 AbstractSonar& operator=(const AbstractSonar&) = delete;
647
648 explicit AbstractSonar(const RTT& rtt) : rtt_{rtt} {}
649
650 uint16_t async_echo_us(uint16_t timeout_ms)
651 {
652 uint32_t now = rtt_.millis();
653 now += timeout_ms;
654 // Wait for echo signal start
655 while (status_ != READY)
656 if (rtt_.millis() >= now)
657 {
658 synchronized
659 {
660 status_ = READY;
661 echo_start_ = echo_end_ = RAW_TIME::EMPTY_TIME;
662 }
663 return 0;
664 }
665 return echo_time_();
666 }
667
668 template<board::DigitalPin ECHO>
669 uint16_t blocking_echo_us(gpio::FAST_PIN<ECHO>& echo, uint16_t timeout_ms)
670 {
671 uint32_t now = rtt_.millis();
672 now += timeout_ms;
673 while (!echo.value())
674 if (rtt_.millis() >= now) return 0;
675 synchronized
676 {
677 status_ = ECHO_STARTED;
678 echo_start_ = rtt_.raw_time();
679 }
680 // Wait for echo signal end
681 while (echo.value())
682 if (rtt_.millis() >= now) return 0;
683 synchronized
684 {
685 status_ = READY;
686 echo_end_ = rtt_.raw_time();
687 return echo_time_();
688 }
689 }
690
691 void trigger_sent(uint16_t timeout_ms)
692 {
693 synchronized
694 {
695 status_ = TRIGGERED;
696 timeout_time_ms_ = rtt_.millis_() + timeout_ms;
697 }
698 }
699
700 bool pulse_edge(bool rising)
701 {
702 if (rising && (status_ == TRIGGERED))
703 {
704 status_ = ECHO_STARTED;
705 echo_start_ = rtt_.raw_time_();
706 return false;
707 }
708 if ((!rising) && (status_ == ECHO_STARTED))
709 {
710 status_ = READY;
711 echo_end_ = rtt_.raw_time_();
712 return true;
713 }
714 return false;
715 }
716
717 bool rtt_time_changed()
718 {
719 if ((status_ != READY) && (rtt_.millis_() >= timeout_time_ms_))
720 {
721 status_ = READY;
722 echo_start_ = echo_end_ = RAW_TIME::EMPTY_TIME;
723 return true;
724 }
725 return false;
726 }
728
729 private:
730 uint16_t echo_time_() const
731 {
732 return uint16_t((echo_end_.as_real_time() - echo_start_.as_real_time()).total_micros());
733 }
734
735 const RTT& rtt_;
736
737 static constexpr const uint8_t UNKNOWN = 0x00;
738 static constexpr const uint8_t TRIGGERED = 0x10;
739 static constexpr const uint8_t ECHO_STARTED = 0x11;
740 static constexpr const uint8_t READY = 0x20;
741
742 volatile uint8_t status_ = UNKNOWN;
743 uint32_t timeout_time_ms_ = 0UL;
744
745 RAW_TIME echo_start_ = RAW_TIME::EMPTY_TIME;
746 RAW_TIME echo_end_ = RAW_TIME::EMPTY_TIME;
747 };
748
754 template<board::Timer NTIMER_, board::DigitalPin TRIGGER_, board::DigitalPin ECHO_,
755 SonarType SONAR_TYPE_ = SonarType::BLOCKING>
756 class HCSR04 : public AbstractSonar<NTIMER_>
757 {
758 public:
762 static constexpr const board::DigitalPin TRIGGER = TRIGGER_;
764 static constexpr const board::DigitalPin ECHO = ECHO_;
766 static constexpr const SonarType SONAR_TYPE = SONAR_TYPE_;
767
768 private:
770 using ECHO_PIN_TRAIT = board_traits::DigitalPin_trait<ECHO>;
771 using ECHO_PORT_TRAIT = board_traits::Port_trait<ECHO_PIN_TRAIT::PORT>;
772 static_assert((SONAR_TYPE != SonarType::ASYNC_INT) || ECHO_PIN_TRAIT::IS_INT,
773 "SONAR_TYPE == ASYNC_INT but ECHO is not an INT pin");
774 static_assert((SONAR_TYPE != SonarType::ASYNC_PCINT) || (ECHO_PORT_TRAIT::PCINT != board_traits::PCI_NONE),
775 "SONAR_TYPE == ASYNC_PCINT but ECHO is not an PCI pin");
776
777 public:
783 static constexpr const uint16_t MAX_RANGE_M = 4;
784
794 static constexpr const uint16_t DEFAULT_TIMEOUT_MS = MAX_RANGE_M * 2 * ONE_MILLI_32 / SPEED_OF_SOUND + 1;
795
802 explicit HCSR04(const RTT& rtt) : PARENT{rtt}
803 {
806 }
807
822 uint16_t echo_us(uint16_t timeout_ms)
823 {
824 async_echo(timeout_ms);
825 return await_echo_us(timeout_ms);
826 }
827
850 void async_echo(uint16_t timeout_ms, bool trigger = true)
851 {
852 this->trigger_sent(timeout_ms);
853 if (trigger) this->trigger();
854 }
855
869 uint16_t await_echo_us(uint16_t timeout_ms)
870 {
872 return this->async_echo_us(timeout_ms);
873 else
874 return this->template blocking_echo_us<ECHO>(echo_, timeout_ms);
875 }
876
877 private:
878 bool on_pin_change()
879 {
881 "on_pin_change() must be called only with SonarType::ASYNC_INT or ASYNC_PCINT");
882 return this->pulse_edge(echo_.value());
883 }
884
885 bool on_rtt_change()
886 {
887 return this->rtt_time_changed();
888 }
889
890 void trigger()
891 {
892 // Pulse TRIGGER for 10us
893 trigger_.set();
894 time::delay_us(TRIGGER_PULSE_US);
895 trigger_.clear();
896 }
897
898 static constexpr const uint16_t TRIGGER_PULSE_US = 10;
899
902
903 // Make friends with all ISR handlers
904 friend struct isr_handler;
905 };
906
921 template<board::Timer NTIMER_, board::DigitalPin TRIGGER_, board::DigitalPin ECHO_>
923
937 template<board::Timer NTIMER_, board::DigitalPin TRIGGER_, board::ExternalInterruptPin ECHO_>
939
953 template<board::Timer NTIMER_, board::DigitalPin TRIGGER_, board::InterruptPin ECHO_>
955
973 template<board::Timer NTIMER_> struct SonarEvent
974 {
975 public:
977 SonarEvent(const SonarEvent&) = default;
978 SonarEvent& operator=(const SonarEvent&) = default;
980
986
992 using RAW_TIME = typename RTT::RAW_TIME;
993
1003
1010 bool timeout() const
1011 {
1012 return timeout_;
1013 }
1014
1025 uint8_t started() const
1026 {
1027 return started_;
1028 }
1029
1043 uint8_t ready() const
1044 {
1045 return ready_;
1046 }
1047
1056 {
1057 return time_;
1058 }
1059
1060 private:
1061 explicit SonarEvent(bool timeout) : timeout_{timeout} {}
1062 SonarEvent(uint8_t started, uint8_t ready, const RAW_TIME& time)
1063 : started_{started}, ready_{ready}, time_{time}
1064 {}
1065
1066 bool timeout_ = false;
1067 uint8_t started_ = 0;
1068 uint8_t ready_ = 0;
1069 RAW_TIME time_ = RAW_TIME::EMPTY_TIME;
1070
1071 template<board::Timer, board::DigitalPin, board::Port, uint8_t> friend class MultiHCSR04;
1072 };
1073
1106 template<board::Timer NTIMER_, board::DigitalPin TRIGGER_, board::Port ECHO_PORT_, uint8_t ECHO_MASK_>
1108 {
1109 public:
1111 static constexpr const board::DigitalPin TRIGGER = TRIGGER_;
1113 static constexpr const board::Port ECHO_PORT = ECHO_PORT_;
1115 static constexpr const uint8_t ECHO_MASK = ECHO_MASK_;
1116
1117 private:
1118 using PTRAIT = board_traits::Port_trait<ECHO_PORT>;
1119 static_assert(PTRAIT::PCINT != board_traits::PCI_NONE, "ECHO_PORT_ must support PCINT");
1120 static_assert((PTRAIT::DPIN_MASK & ECHO_MASK) == ECHO_MASK, "ECHO_MASK_ must contain available PORT pins");
1121
1122 public:
1124 MultiHCSR04(const MultiHCSR04&) = delete;
1125 MultiHCSR04& operator=(const MultiHCSR04&) = delete;
1127
1132
1138 static constexpr const uint16_t MAX_RANGE_M = 4;
1139
1147 static constexpr const uint16_t DEFAULT_TIMEOUT_MS = MAX_RANGE_M * 2 * ONE_MILLI_32 / SPEED_OF_SOUND + 1;
1148
1155 explicit MultiHCSR04(RTT& rtt) : rtt_{rtt}
1156 {
1158 }
1159
1177 void trigger(uint16_t timeout_ms)
1178 {
1179 started_ = 0;
1180 ready_ = 0;
1181 timeout_time_ms_ = rtt_.millis() + timeout_ms;
1182 active_ = true;
1183 // Pulse TRIGGER for 10us
1184 trigger_.set();
1185 time::delay_us(TRIGGER_PULSE_US);
1186 trigger_.clear();
1187 }
1188
1197 bool active() const
1198 {
1199 return active_;
1200 }
1201
1215 uint8_t ready() const
1216 {
1217 return ready_;
1218 }
1219
1226 bool all_ready() const
1227 {
1228 return ready_ == ECHO_MASK;
1229 }
1230
1237 {
1238 if (active_)
1239 {
1240 active_ = false;
1241 ready_ = ECHO_MASK;
1242 }
1243 }
1244
1245 private:
1246 EVENT on_pin_change()
1247 {
1248 if (!active_) return EVENT{};
1249 // Compute the newly started echoes
1250 uint8_t pins = echo_.get_PIN();
1251 uint8_t started = pins & bits::COMPL(started_);
1252 // Compute the newly finished echoes
1253 uint8_t ready = bits::COMPL(pins) & started_ & bits::COMPL(ready_);
1254 // Update status of all echo pins
1255 started_ |= started;
1256 ready_ |= ready;
1257 if (ready_ == ECHO_MASK) active_ = false;
1258 return EVENT{started, ready, rtt_.raw_time_()};
1259 }
1260
1261 EVENT on_rtt_change()
1262 {
1263 if (active_ && (rtt_.millis_() >= timeout_time_ms_))
1264 {
1265 active_ = false;
1266 return EVENT{true};
1267 }
1268 return EVENT{};
1269 }
1270
1271 static constexpr const uint16_t TRIGGER_PULSE_US = 10;
1272
1273 RTT& rtt_;
1274 volatile uint8_t started_ = 0;
1275 volatile uint8_t ready_ = 0;
1276 volatile bool active_ = false;
1277 uint32_t timeout_time_ms_ = 0UL;
1280
1281 // Make friends with all ISR handlers
1282 friend struct isr_handler;
1283 };
1284
1286 // All sonar-related methods called by pre-defined ISR are defined here
1287 struct isr_handler
1288 {
1289 template<uint8_t INT_NUM_, board::Timer TIMER_, board::DigitalPin TRIGGER_, board::ExternalInterruptPin ECHO_>
1290 static bool sonar_int()
1291 {
1292 timer::isr_handler::check_timer<TIMER_>();
1293 static_assert(board_traits::ExternalInterruptPin_trait<ECHO_>::INT == INT_NUM_,
1294 "ECHO INT number must match INT_NUM");
1295 using SONAR = ASYNC_INT_HCSR04<TIMER_, TRIGGER_, ECHO_>;
1296 return interrupt::HandlerHolder<SONAR>::handler()->on_pin_change();
1297 }
1298
1299 template<uint8_t INT_NUM_, board::Timer TIMER_, board::DigitalPin TRIGGER_, board::ExternalInterruptPin ECHO_,
1300 typename HANDLER_, void (HANDLER_::*CALLBACK_)()>
1301 static void sonar_int_method()
1302 {
1303 if (sonar_int<INT_NUM_, TIMER_, TRIGGER_, ECHO_>())
1304 interrupt::CallbackHandler<void (HANDLER_::*)(), CALLBACK_>::call();
1305 }
1306
1307 template<uint8_t INT_NUM_, board::Timer TIMER_, board::DigitalPin TRIGGER_, board::ExternalInterruptPin ECHO_,
1308 void (*CALLBACK_)()>
1309 static void sonar_int_function()
1310 {
1311 if (sonar_int<INT_NUM_, TIMER_, TRIGGER_, ECHO_>()) CALLBACK_();
1312 }
1313
1314 template<uint8_t PCI_NUM_, board::Timer TIMER_, board::DigitalPin TRIGGER_> static bool sonar_pci()
1315 {
1316 return false;
1317 }
1318
1319 template<uint8_t PCI_NUM_, board::Timer TIMER_, board::DigitalPin TRIGGER_, board::InterruptPin ECHO1_,
1320 board::InterruptPin... ECHOS_>
1321 static bool sonar_pci()
1322 {
1323 timer::isr_handler::check_timer<TIMER_>();
1324 // handle first echo pin
1325 interrupt::isr_handler_pci::check_pci_pins<PCI_NUM_, ECHO1_>();
1326 using SONAR = ASYNC_PCINT_HCSR04<TIMER_, TRIGGER_, ECHO1_>;
1327 bool result = interrupt::HandlerHolder<SONAR>::handler()->on_pin_change();
1328 // handle other echo pins
1329 return result || sonar_pci<PCI_NUM_, TIMER_, TRIGGER_, ECHOS_...>();
1330 }
1331
1332 template<bool DUMMY_> static bool sonar_rtt_change_helper()
1333 {
1334 return false;
1335 }
1336
1337 template<bool DUMMY_, typename SONAR1_, typename... SONARS_> static bool sonar_rtt_change_helper()
1338 {
1339 bool result = interrupt::HandlerHolder<SONAR1_>::handler()->on_rtt_change();
1340 // handle other sonars
1341 return result || sonar_rtt_change_helper<DUMMY_, SONARS_...>();
1342 }
1343
1344 template<uint8_t TIMER_NUM_, typename... SONARS_> static bool sonar_rtt_change()
1345 {
1346 // Update RTT time
1347 timer::isr_handler_rtt::rtt<TIMER_NUM_>();
1348 // Ask each sonar to check if timeout is elapsed
1349 return sonar_rtt_change_helper<false, SONARS_...>();
1350 }
1351
1352 template<uint8_t PCI_NUM_, board::Timer TIMER_, board::DigitalPin TRIGGER_, board::InterruptPin ECHO_,
1353 typename HANDLER_, void (HANDLER_::*CALLBACK_)()>
1354 static void sonar_pci_method()
1355 {
1356 if (sonar_pci<PCI_NUM_, TIMER_, TRIGGER_, ECHO_>())
1357 interrupt::CallbackHandler<void (HANDLER_::*)(), CALLBACK_>::call();
1358 }
1359
1360 template<uint8_t PCI_NUM_, board::Timer TIMER_, board::DigitalPin TRIGGER_, board::InterruptPin ECHO_,
1361 void (*CALLBACK_)()>
1362 static void sonar_pci_function()
1363 {
1364 if (sonar_pci<PCI_NUM_, TIMER_, TRIGGER_, ECHO_>()) CALLBACK_();
1365 }
1366
1367 template<board::DigitalPin TRIGGER_, board::InterruptPin ECHO_> struct TriggerEcho
1368 {
1369 static constexpr const board::DigitalPin TRIGGER = TRIGGER_;
1370 static constexpr const board::InterruptPin ECHO = ECHO_;
1371 };
1372
1373 template<uint8_t PCI_NUM_, board::Timer TIMER_> static bool sonar_distinct_pci()
1374 {
1375 return false;
1376 }
1377
1378 template<uint8_t PCI_NUM_, board::Timer TIMER_, board::DigitalPin TRIGGER_, board::InterruptPin ECHO_>
1379 static bool sonar_distinct_pci_one()
1380 {
1381 timer::isr_handler::check_timer<TIMER_>();
1382 // handle first echo pin
1383 interrupt::isr_handler_pci::check_pci_pins<PCI_NUM_, ECHO_>();
1384 using SONAR = ASYNC_PCINT_HCSR04<TIMER_, TRIGGER_, ECHO_>;
1385 return interrupt::HandlerHolder<SONAR>::handler()->on_pin_change();
1386 }
1387
1388 template<uint8_t PCI_NUM_, board::Timer TIMER_, typename TRIGGER_ECHO1_, typename ...TRIGGER_ECHOS_>
1389 static bool sonar_distinct_pci()
1390 {
1391 bool result = sonar_distinct_pci_one<PCI_NUM_, TIMER_, TRIGGER_ECHO1_::TRIGGER, TRIGGER_ECHO1_::ECHO>();
1392 // handle other echo pins
1393 return result || sonar_distinct_pci<PCI_NUM_, TIMER_, TRIGGER_ECHOS_...>();
1394 }
1395
1396 template<uint8_t PCI_NUM_, board::Timer TIMER_, board::DigitalPin TRIGGER_, board::Port ECHO_PORT_,
1397 uint8_t ECHO_MASK_, typename HANDLER_, void (HANDLER_::*CALLBACK_)(const SonarEvent<TIMER_>&)>
1398 static void multi_sonar_pci_method()
1399 {
1400 timer::isr_handler::check_timer<TIMER_>();
1401 using PTRAIT = board_traits::Port_trait<ECHO_PORT_>;
1402 static_assert(PTRAIT::PCINT == PCI_NUM_, "ECHO_PORT must match PCI_NUM");
1403 static_assert((PTRAIT::DPIN_MASK & ECHO_MASK_) == ECHO_MASK_, "ECHO_MASK must contain available PORT pins");
1404 using SONAR = MultiHCSR04<TIMER_, TRIGGER_, ECHO_PORT_, ECHO_MASK_>;
1405 SonarEvent<TIMER_> event = interrupt::HandlerHolder<SONAR>::handler()->on_pin_change();
1406 if ((event.ready() != 0) || (event.started() != 0))
1407 interrupt::CallbackHandler<void (HANDLER_::*)(const SonarEvent<TIMER_>&), CALLBACK_>::call(event);
1408 }
1409
1410 template<uint8_t PCI_NUM_, board::Timer TIMER_, board::DigitalPin TRIGGER_, board::Port ECHO_PORT_,
1411 uint8_t ECHO_MASK_, void (*CALLBACK_)(const SonarEvent<TIMER_>&)>
1412 static void multi_sonar_pci_function()
1413 {
1414 timer::isr_handler::check_timer<TIMER_>();
1415 using PTRAIT = board_traits::Port_trait<ECHO_PORT_>;
1416 static_assert(PTRAIT::PCINT == PCI_NUM_, "ECHO_PORT must match PCI_NUM");
1417 static_assert((PTRAIT::DPIN_MASK & ECHO_MASK_) == ECHO_MASK_, "ECHO_MASK must contain available PORT pins");
1418 using SONAR = MultiHCSR04<TIMER_, TRIGGER_, ECHO_PORT_, ECHO_MASK_>;
1419 SonarEvent<TIMER_> event = interrupt::HandlerHolder<SONAR>::handler()->on_pin_change();
1420 if (event.ready() || event.started()) CALLBACK_(event);
1421 }
1422
1423 template<uint8_t TIMER_NUM_, typename SONAR_, typename EVENT_> static EVENT_ multi_sonar_rtt_change()
1424 {
1425 // Update RTT time
1426 timer::isr_handler_rtt::rtt<TIMER_NUM_>();
1427 return interrupt::HandlerHolder<SONAR_>::handler()->on_rtt_change();
1428 }
1429 };
1431}
1432
1433#endif /* SONAR_H */
An abstract base class for some sonar classes defined as part of this API.
Definition: sonar.h:600
bool ready() const
Indicate if an echo pulse measure is ready to read.
Definition: sonar.h:614
timer::RTT< NTIMER_ > RTT
The type of timer::RTT used by this sonar instance.
Definition: sonar.h:603
uint16_t latest_echo_us() const
Get the latest measured echo pulse duration.
Definition: sonar.h:629
uint16_t echo_us(uint16_t timeout_ms)
Send a trigger pulse on this sonar and wait until an echo pulse is received, or timeout_ms has elapse...
Definition: sonar.h:822
static constexpr const SonarType SONAR_TYPE
The mode used by this class to calculate the echo pin pulse duration.
Definition: sonar.h:766
void async_echo(uint16_t timeout_ms, bool trigger=true)
Send a trigger pulse on this sonar and return immediately, without waiting for the echo pulse.
Definition: sonar.h:850
HCSR04(const RTT &rtt)
Construct a new a sonar sensor handler.
Definition: sonar.h:802
uint16_t await_echo_us(uint16_t timeout_ms)
Wait until an echo pulse is received, or timeout_ms has elapsed.
Definition: sonar.h:869
static constexpr const board::DigitalPin TRIGGER
The board::DigitalPin connected to the sensor trigger pin.
Definition: sonar.h:762
static constexpr const uint16_t MAX_RANGE_M
The approximate maximum range, in meters, that this sonar sensor supports.
Definition: sonar.h:783
static constexpr const board::DigitalPin ECHO
The board::DigitalPin connected to the sensor echo pin.
Definition: sonar.h:764
static constexpr const uint16_t DEFAULT_TIMEOUT_MS
The default timeout duration, in milliseconds, to use if you want to cover the maximum range of the s...
Definition: sonar.h:794
This template class supports up to 8 HC-SR04 sonars (or equivalent sensors), with their trigger pins ...
Definition: sonar.h:1108
void trigger(uint16_t timeout_ms)
Start ranging on all sonars connected to this MultiHCSR04.
Definition: sonar.h:1177
uint8_t ready() const
Tell, for which of the connected sonars, the latest ranging, started by trigger(),...
Definition: sonar.h:1215
SonarEvent< NTIMER_ > EVENT
The exact SonarEvent type produced by this MultiHCSR04 instance.
Definition: sonar.h:1131
MultiHCSR04(RTT &rtt)
Construct a new a multi-sonar sensors handler.
Definition: sonar.h:1155
static constexpr const uint16_t DEFAULT_TIMEOUT_MS
The default timeout duration, in milliseconds, to use if you want to cover the maximum range of the s...
Definition: sonar.h:1147
static constexpr const uint8_t ECHO_MASK
The mask determining which pins of ECHO_PORT are actually connected to a real sonar echo pin.
Definition: sonar.h:1115
static constexpr const board::Port ECHO_PORT
The MCU port to which all echo pins of sonars handled by this class are connected.
Definition: sonar.h:1113
static constexpr const uint16_t MAX_RANGE_M
The approximate maximum range, in meters, that this sonar sensor supports.
Definition: sonar.h:1138
bool all_ready() const
Tell if the latest ranging, started by trigger(), is finished for all connected sonars,...
Definition: sonar.h:1226
timer::RTT< NTIMER_ > RTT
The type of timer::RTT used by this MultiHCSR04 instance.
Definition: sonar.h:1129
void set_ready()
Force readiness of all connected sensors, ie the end of current ranging.
Definition: sonar.h:1236
static constexpr const board::DigitalPin TRIGGER
The board::DigitalPin connected to the sensors trigger pins.
Definition: sonar.h:1111
bool active() const
Tell if a ranging is under way on any sonar managed by this MultiHCSR04 instance.
Definition: sonar.h:1197
API that manipulates a part of a digital IO port.
Definition: gpio.h:380
uint8_t get_PIN() INLINE
Get the current 8-bit value of PIN register for this port, masked according to the bit mask provided ...
Definition: gpio.h:507
API to handle a real-time timer.
RAW_TIME raw_time() const
Elapsed time, in raw representation, since this timer has started.
uint32_t millis() const
Elapsed time, in milliseconds, since this timer has started.
uint32_t millis_() const
Elapsed time, in milliseconds, since this timer has started.
RTTRawTime< TYPE > RAW_TIME
The adequate RTTRawTime type for this RTT.
RAW_TIME raw_time_() const
Elapsed time, in raw representation, since this timer has started.
General Purpose (digital) Input Output API.
General API for handling External Interrupt pins.
static constexpr uint8_t COMPL(uint8_t value)
Return the uint8_t 2-complement of a byte.
Definition: bits.h:253
Port
Defines all available ports of the target MCU.
Definition: empty.h:49
DigitalPin
Defines all available digital input/output pins of the target MCU.
Definition: empty.h:56
InterruptPin
Defines all digital output pins of target MCU, usable as pin change interrupt (PCI) pins.
Definition: empty.h:98
Timer
Defines all timers available for target MCU.
Definition: empty.h:112
ExternalInterruptPin
Defines all digital output pins of target MCU, usable as direct external interrupt pins.
Definition: empty.h:91
Defines the API for sonar support.
Definition: sonar.h:497
static constexpr const uint32_t SPEED_OF_SOUND
The approximate speed of sound (and ultrasonic) waves, in the air, expressed in meters per second.
Definition: sonar.h:509
SonarType
This enum defines the different modes, supported by HCSR04, to calculate the echo pin pulse duration.
Definition: sonar.h:571
@ ASYNC_PCINT
In this mode, the echo pin is a board::InterruptPin and the HCSR04 will use interrupts to calculate t...
@ BLOCKING
In this mode, the HCSR04 will block until the echo pulse is received.
@ ASYNC_INT
In this mode, the echo pin is a board::ExternalInterruptPin and the HCSR04 will use interrupts to cal...
static constexpr uint16_t echo_us_to_distance_mm(uint16_t echo_us)
This method converts the echo duration, in microseconds, to the distance between the sensor and the r...
Definition: sonar.h:526
static constexpr uint16_t distance_mm_to_echo_us(uint16_t distance_mm)
This method converts the disatnce, in millimeters, between the sensor and a reflecting object,...
Definition: sonar.h:550
Defines all API for all external devices supported by FastArduino.
typename FastPinType< DPIN_ >::TYPE FAST_PIN
Useful alias type to the FastPin type matching a given board::DigitalPin.
Definition: gpio.h:694
@ OUTPUT
Digital pin is configured as output.
@ INPUT
Digital pin is configured as high-impedance (open drain) input.
void register_handler(Handler &handler)
Register a class instance containing methods that shall be called back by an ISR.
Definition: interrupts.h:185
Defines simple API to handle time and delays.
Definition: time.h:33
void delay_us(uint16_t us) INLINE
Delay program execution for the given amount of microseconds.
Definition: time.h:334
General API for handling Pin Change Interrupts.
Real-time Timer API.
This type holds information about events occurring within MultiHCSR04 handler.
Definition: sonar.h:974
typename RTT::RAW_TIME RAW_TIME
The timer::RTTRawTime type used by the MultiHCSR04 producing this SonarEvent.
Definition: sonar.h:992
bool timeout() const
Indicate if this event was produced by a timeout while waiting for echo pulses.
Definition: sonar.h:1010
uint8_t started() const
Indicate if this event was produced due to an echo pulse leading edge just received by the related Mu...
Definition: sonar.h:1025
RAW_TIME time() const
The timer::RTTRawTime at which this event occurred.
Definition: sonar.h:1055
uint8_t ready() const
Indicate if this event was produced tdue to an echo pulse trailing edge just received by the related ...
Definition: sonar.h:1043
SonarEvent()
Default constructor.
Definition: sonar.h:1002
Simple time utilities.
General utilities API that have broad application in programs.