APM:Libraries
Util.cpp
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  *
15  * Code by Andrew Tridgell and Siddharth Bharat Purohit
16  */
17 #include <AP_HAL/AP_HAL.h>
18 #include <AP_Math/AP_Math.h>
19 
20 #include "Util.h"
21 #include <chheap.h>
22 #include "ToneAlarm.h"
23 #include "RCOutput.h"
24 
25 #if HAL_WITH_IO_MCU
27 #include <AP_IOMCU/AP_IOMCU.h>
28 extern AP_IOMCU iomcu;
29 #endif
30 
31 extern const AP_HAL::HAL& hal;
32 
33 using namespace ChibiOS;
34 
35 #if CH_CFG_USE_HEAP == TRUE
36 
37 extern "C" {
38  size_t mem_available(void);
39  void *malloc_ccm(size_t size);
40 };
41 
45 uint32_t Util::available_memory(void)
46 {
47  // from malloc.c in hwdef
48  return mem_available();
49 }
50 
51 /*
52  Special Allocation Routines
53 */
54 
55 void* Util::malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type)
56 {
57  if (mem_type == AP_HAL::Util::MEM_FAST) {
58  return try_alloc_from_ccm_ram(size);
59  } else {
60  return calloc(1, size);
61  }
62 }
63 
64 void Util::free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type)
65 {
66  if (ptr != NULL) {
67  chHeapFree(ptr);
68  }
69 }
70 
71 
72 void* Util::try_alloc_from_ccm_ram(size_t size)
73 {
74  void *ret = malloc_ccm(size);
75  if (ret == nullptr) {
76  //we failed to allocate from CCM so we are going to try common SRAM
77  ret = calloc(1, size);
78  }
79  return ret;
80 }
81 
82 #endif // CH_CFG_USE_HEAP
83 
84 /*
85  get safety switch state
86  */
88 {
89 #if HAL_USE_PWM == TRUE
90  return ((RCOutput *)hal.rcout)->_safety_switch_state();
91 #else
92  return SAFETY_NONE;
93 #endif
94 }
95 
96 void Util::set_imu_temp(float current)
97 {
98 #if HAL_WITH_IO_MCU && HAL_HAVE_IMU_HEATER
99  if (!heater.target || *heater.target == -1 || !AP_BoardConfig::io_enabled()) {
100  return;
101  }
102 
103  // average over temperatures to remove noise
104  heater.count++;
105  heater.sum += current;
106 
107  // update once a second
108  uint32_t now = AP_HAL::millis();
109  if (now - heater.last_update_ms < 1000) {
110  return;
111  }
112  heater.last_update_ms = now;
113 
114  current = heater.sum / heater.count;
115  heater.sum = 0;
116  heater.count = 0;
117 
118  // experimentally tweaked for Pixhawk2
119  const float kI = 0.3f;
120  const float kP = 200.0f;
121  float target = (float)(*heater.target);
122 
123  // limit to 65 degrees to prevent damage
124  target = constrain_float(target, 0, 65);
125 
126  float err = target - current;
127 
128  heater.integrator += kI * err;
129  heater.integrator = constrain_float(heater.integrator, 0, 70);
130 
131  float output = constrain_float(kP * err + heater.integrator, 0, 100);
132 
133  // hal.console->printf("integrator %.1f out=%.1f temp=%.2f err=%.2f\n", heater.integrator, output, current, err);
134 
135  iomcu.set_heater_duty_cycle(output);
136 #endif // HAL_WITH_IO_MCU && HAL_HAVE_IMU_HEATER
137 }
138 
139 void Util::set_imu_target_temp(int8_t *target)
140 {
141 #if HAL_WITH_IO_MCU && HAL_HAVE_IMU_HEATER
142  heater.target = target;
143 #endif
144 }
145 
146 #ifdef HAL_PWM_ALARM
147 static int state;
148 ToneAlarm Util::_toneAlarm;
149 
151 {
152  return _toneAlarm.init();
153 }
154 
155 void Util::toneAlarm_set_tune(uint8_t tone)
156 {
157  _toneAlarm.set_tune(tone);
158 }
159 
160 // (state 0) if init_tune() -> (state 1) complete=false
161 // (state 1) if set_note -> (state 2) -> if play -> (state 3)
162 // play returns true if tune has changed or tune is complete (repeating tunes never complete)
163 // (state 3) -> (state 1)
164 // (on every tick) if (complete) -> (state 0)
166  if(state == 0) {
167  state = state + _toneAlarm.init_tune();
168  } else if (state == 1) {
169  state = state + _toneAlarm.set_note();
170  }
171  if (state == 2) {
172  state = state + _toneAlarm.play();
173  } else if (state == 3) {
174  state = 1;
175  }
176 
177  if (_toneAlarm.is_tune_comp()) {
178  state = 0;
179  }
180 
181 }
182 #endif // HAL_PWM_ALARM
183 
void * malloc_ccm(size_t size)
Definition: malloc.c:43
virtual void _toneAlarm_timer_tick()
Definition: Util.h:80
enum safety_state safety_switch_state(void) override
Definition: Util.cpp:87
void * try_alloc_from_ccm_ram(size_t size)
Definition: Util.cpp:72
void * malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type)
Definition: Util.cpp:55
void * calloc(size_t nmemb, size_t size)
Definition: malloc.c:76
static bool io_enabled(void)
virtual void toneAlarm_set_tune(uint8_t tune)
Definition: Util.h:79
uint32_t millis()
Definition: system.cpp:157
static int state
Definition: Util.cpp:20
size_t mem_available(void)
Definition: malloc.c:91
safety_state
Definition: Util.h:35
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define NULL
Definition: hal_types.h:59
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
void set_imu_target_temp(int8_t *target)
Definition: Util.cpp:139
AP_HAL::RCOutput * rcout
Definition: HAL.h:113
void set_imu_temp(float current)
Definition: Util.cpp:96
void free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type)
Definition: Util.cpp:64
uint32_t available_memory() override
Definition: Util.cpp:45
virtual bool toneAlarm_init()
Definition: Util.h:78