CANClock.h 4.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165
  1. /*
  2. * The MIT License (MIT)
  3. *
  4. * Copyright (c) 2014 Pavel Kirienko
  5. *
  6. * Permission is hereby granted, free of charge, to any person obtaining a copy of
  7. * this software and associated documentation files (the "Software"), to deal in
  8. * the Software without restriction, including without limitation the rights to
  9. * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
  10. * the Software, and to permit persons to whom the Software is furnished to do so,
  11. * subject to the following conditions:
  12. *
  13. * The above copyright notice and this permission notice shall be included in all
  14. * copies or substantial portions of the Software.
  15. *
  16. * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
  17. * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
  18. * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
  19. * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
  20. * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
  21. * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
  22. */
  23. /*
  24. * This file is free software: you can redistribute it and/or modify it
  25. * under the terms of the GNU General Public License as published by the
  26. * Free Software Foundation, either version 3 of the License, or
  27. * (at your option) any later version.
  28. *
  29. * This file is distributed in the hope that it will be useful, but
  30. * WITHOUT ANY WARRANTY; without even the implied warranty of
  31. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  32. * See the GNU General Public License for more details.
  33. *
  34. * You should have received a copy of the GNU General Public License along
  35. * with this program. If not, see <http://www.gnu.org/licenses/>.
  36. *
  37. * Modified for Ardupilot by Siddharth Bharat Purohit
  38. */
  39. #pragma once
  40. #include "AP_HAL_ChibiOS.h"
  41. #if HAL_WITH_UAVCAN
  42. #include <uavcan/driver/system_clock.hpp>
  43. namespace ChibiOS_CAN {
  44. namespace clock {
  45. /**
  46. * Starts the clock.
  47. * Can be called multiple times, only the first call will be effective.
  48. */
  49. void init();
  50. /**
  51. * Returns current monotonic time since the moment when clock::init() was called.
  52. * This function is thread safe.
  53. */
  54. uavcan::MonotonicTime getMonotonic();
  55. /**
  56. * Sets the driver's notion of the system UTC. It should be called
  57. * at startup and any time the system clock is updated from an
  58. * external source that is not the UAVCAN Timesync master.
  59. * This function is thread safe.
  60. */
  61. void setUtc(uavcan::UtcTime time);
  62. /**
  63. * Returns UTC time if it has been set, otherwise returns zero time.
  64. * This function is thread safe.
  65. */
  66. uavcan::UtcTime getUtc();
  67. /**
  68. * Performs UTC phase and frequency adjustment.
  69. * The UTC time will be zero until first adjustment has been performed.
  70. * This function is thread safe.
  71. */
  72. void adjustUtc(uavcan::UtcDuration adjustment);
  73. /**
  74. * UTC clock synchronization parameters
  75. */
  76. struct UtcSyncParams {
  77. float offset_p; ///< PPM per one usec error
  78. float rate_i; ///< PPM per one PPM error for second
  79. float rate_error_corner_freq;
  80. float max_rate_correction_ppm;
  81. float lock_thres_rate_ppm;
  82. uavcan::UtcDuration lock_thres_offset;
  83. uavcan::UtcDuration min_jump; ///< Min error to jump rather than change rate
  84. UtcSyncParams()
  85. : offset_p(0.01F)
  86. , rate_i(0.02F)
  87. , rate_error_corner_freq(0.01F)
  88. , max_rate_correction_ppm(300.0F)
  89. , lock_thres_rate_ppm(2.0F)
  90. , lock_thres_offset(uavcan::UtcDuration::fromMSec(4))
  91. , min_jump(uavcan::UtcDuration::fromMSec(10))
  92. { }
  93. };
  94. /**
  95. * Clock rate error.
  96. * Positive if the hardware timer is slower than reference time.
  97. * This function is thread safe.
  98. */
  99. float getUtcRateCorrectionPPM();
  100. /**
  101. * Number of non-gradual adjustments performed so far.
  102. * Ideally should be zero.
  103. * This function is thread safe.
  104. */
  105. uavcan::uint32_t getUtcJumpCount();
  106. /**
  107. * Whether UTC is synchronized and locked.
  108. * This function is thread safe.
  109. */
  110. bool isUtcLocked();
  111. /**
  112. * UTC sync params get/set.
  113. * Both functions are thread safe.
  114. */
  115. UtcSyncParams getUtcSyncParams();
  116. void setUtcSyncParams(const UtcSyncParams& params);
  117. }
  118. /**
  119. * Adapter for uavcan::ISystemClock.
  120. */
  121. class SystemClock : public uavcan::ISystemClock, uavcan::Noncopyable {
  122. SystemClock() { }
  123. virtual void adjustUtc(uavcan::UtcDuration adjustment) override
  124. {
  125. clock::adjustUtc(adjustment);
  126. }
  127. public:
  128. virtual uavcan::MonotonicTime getMonotonic() const override
  129. {
  130. return clock::getMonotonic();
  131. }
  132. virtual uavcan::UtcTime getUtc() const override
  133. {
  134. return clock::getUtc();
  135. }
  136. /**
  137. * Calls clock::init() as needed.
  138. * This function is thread safe.
  139. */
  140. static SystemClock& get_singleton();
  141. };
  142. }
  143. #endif //HAL_WITH_UAVCAN