PX4 Firmware
PX4 Autopilot Software http://px4.io
heater.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2018 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file heater.h
36  *
37  * @author Mark Sauder <mcsauder@gmail.com>
38  * @author Alex Klimaj <alexklimaj@gmail.com>
39  * @author Jake Dahl <dahl.jakejacob@gmail.com>
40  */
41 
42 #pragma once
43 
44 #include <px4_platform_common/px4_config.h>
45 #include <px4_platform_common/getopt.h>
46 #include <px4_platform_common/module.h>
47 #include <px4_platform_common/module_params.h>
48 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
49 #include <uORB/Subscription.hpp>
52 
53 #include <mathlib/mathlib.h>
54 
55 #define CONTROLLER_PERIOD_DEFAULT 100000
56 
57 /**
58  * @brief IMU Heater Controller driver used to maintain consistent
59  * temparature at the IMU.
60  */
61 extern "C" __EXPORT int heater_main(int argc, char *argv[]);
62 
63 
64 class Heater : public ModuleBase<Heater>, public ModuleParams, public px4::ScheduledWorkItem
65 {
66 public:
67  Heater();
68 
69  virtual ~Heater();
70 
71  /**
72  * @see ModuleBase::custom_command().
73  * @brief main Main entry point to the module that should be
74  * called directly from the module's main method.
75  * @param argc The input argument count.
76  * @param argv Pointer to the input argument array.
77  * @return Returns 0 iff successful, -1 otherwise.
78  */
79  static int custom_command(int argc, char *argv[]);
80 
81  /**
82  * @see ModuleBase::print_usage().
83  * @brief Prints the module usage to the nuttshell console.
84  * @param reason The requested reason for printing to console.
85  */
86  static int print_usage(const char *reason = nullptr);
87 
88  /**
89  * @see ModuleBase::task_spawn().
90  * @brief Initializes the class in the same context as the work queue
91  * and starts the background listener.
92  * @param argv Pointer to the input argument array.
93  * @return Returns 0 iff successful, -1 otherwise.
94  */
95  static int task_spawn(int argc, char *argv[]);
96 
97  /**
98  * @brief Sets and/or reports the heater controller time period value in microseconds.
99  * @param argv Pointer to the input argument array.
100  * @return Returns 0 iff successful, -1 otherwise.
101  */
102  int controller_period(char *argv[]);
103 
104  /**
105  * @brief Sets and/or reports the heater controller integrator gain value.
106  * @param argv Pointer to the input argument array.
107  * @return Returns the heater integrator gain value iff successful, 0.0f otherwise.
108  */
109  float integrator(char *argv[]);
110 
111  /**
112  * @brief Sets and/or reports the heater controller proportional gain value.
113  * @param argv Pointer to the input argument array.
114  * @return Returns the heater proportional gain value iff successful, 0.0f otherwise.
115  */
116  float proportional(char *argv[]);
117 
118  /**
119  * @brief Reports the heater target sensor.
120  * @return Returns the id of the target sensor
121  */
122  uint32_t sensor_id();
123 
124  /**
125  * @brief Initiates the heater driver work queue, starts a new background task,
126  * and fails if it is already running.
127  * @return Returns 1 iff start was successful.
128  */
129  int start();
130 
131  /**
132  * @brief Reports curent status and diagnostic information about the heater driver.
133  * @return Returns 0 iff successful, -1 otherwise.
134  */
135  int print_status();
136 
137  /**
138  * @brief Sets and/or reports the heater target temperature.
139  * @param argv Pointer to the input argument array.
140  * @return Returns the heater target temperature value iff successful, -1.0f otherwise.
141  */
142  float temperature_setpoint(char *argv[]);
143 
144 protected:
145 
146  /**
147  * @brief Called once to initialize uORB topics.
148  */
149  void initialize_topics();
150 
151 private:
152 
153  /**
154  * @brief Calculates the heater element on/off time, carries out
155  * closed loop feedback and feedforward temperature control,
156  * and schedules the next cycle.
157  */
158  void Run() override;
159 
160  /**
161  * @brief Updates and checks for updated uORB parameters.
162  * @param force Boolean to determine if an update check should be forced.
163  */
164  void update_params(const bool force = false);
165 
166  /** Work queue struct for the RTOS scheduler. */
167  static struct work_s _work;
168 
170 
172 
173  bool _heater_on = false;
174 
175  float _integrator_value = 0.0f;
176 
178 
179  float _proportional_value = 0.0f;
180 
183 
184  float _sensor_temperature = 0.0f;
185 
186  /** @note Declare local parameters using defined parameters. */
187  DEFINE_PARAMETERS(
188  (ParamFloat<px4::params::SENS_IMU_TEMP_I>) _param_sens_imu_temp_i,
189  (ParamFloat<px4::params::SENS_IMU_TEMP_P>) _param_sens_imu_temp_p,
190  (ParamInt<px4::params::SENS_TEMP_ID>) _param_sens_temp_id,
191  (ParamFloat<px4::params::SENS_IMU_TEMP>) _param_sens_imu_temp
192  )
193 };
static int custom_command(int argc, char *argv[])
main Main entry point to the module that should be called directly from the module&#39;s main method...
Definition: heater.cpp:67
uORB::Subscription _sensor_accel_sub
Definition: heater.h:181
__EXPORT int heater_main(int argc, char *argv[])
IMU Heater Controller driver used to maintain consistent temparature at the IMU.
Definition: heater.cpp:233
uORB::Subscription _parameter_update_sub
Definition: heater.h:177
Definition: I2C.hpp:51
int controller_period(char *argv[])
Sets and/or reports the heater controller time period value in microseconds.
bool _heater_on
Definition: heater.h:173
float temperature_setpoint(char *argv[])
Sets and/or reports the heater target temperature.
int _controller_time_on_usec
Definition: heater.h:171
void initialize_topics()
Called once to initialize uORB topics.
Definition: heater.cpp:130
float proportional(char *argv[])
Sets and/or reports the heater controller proportional gain value.
int _controller_period_usec
Definition: heater.h:169
void Run() override
Calculates the heater element on/off time, carries out closed loop feedback and feedforward temperatu...
Definition: heater.cpp:78
virtual ~Heater()
Definition: heater.cpp:61
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
Heater()
Definition: heater.cpp:53
float _integrator_value
Definition: heater.h:175
float integrator(char *argv[])
Sets and/or reports the heater controller integrator gain value.
static int print_usage(const char *reason=nullptr)
Prints the module usage to the nuttshell console.
Definition: heater.cpp:209
uint32_t sensor_id()
Reports the heater target sensor.
int start()
Initiates the heater driver work queue, starts a new background task, and fails if it is already runn...
Definition: heater.cpp:169
float _proportional_value
Definition: heater.h:179
#define CONTROLLER_PERIOD_DEFAULT
Definition: heater.h:55
float _sensor_temperature
Definition: heater.h:184
static int task_spawn(int argc, char *argv[])
Initializes the class in the same context as the work queue and starts the background listener...
Definition: heater.cpp:179
int print_status()
Reports curent status and diagnostic information about the heater driver.
Definition: heater.cpp:158
sensor_accel_s _sensor_accel
Definition: heater.h:182
queue struct.
Definition: heater.h:64
void update_params(const bool force=false)
Updates and checks for updated uORB parameters.
Definition: heater.cpp:196