PX4 Firmware
PX4 Autopilot Software http://px4.io
mixer_module.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2019 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 #pragma once
35 
36 #include <board_config.h>
37 #include <drivers/drv_pwm_output.h>
38 #include <lib/mixer/MixerGroup.hpp>
39 #include <lib/perf/perf_counter.h>
41 #include <px4_platform_common/atomic.h>
42 #include <px4_platform_common/module_params.h>
43 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
44 #include <uORB/Publication.hpp>
46 #include <uORB/Subscription.hpp>
53 #include <uORB/topics/test_motor.h>
54 
55 /**
56  * @class OutputModuleInterface
57  * Base class for an output module.
58  */
59 class OutputModuleInterface : public px4::ScheduledWorkItem, public ModuleParams
60 {
61 public:
62  static constexpr int MAX_ACTUATORS = PWM_OUTPUT_MAX_CHANNELS;
63 
64  OutputModuleInterface(const char *name, const px4::wq_config_t &config)
65  : px4::ScheduledWorkItem(name, config), ModuleParams(nullptr) {}
66 
67  /**
68  * Callback to update the (physical) actuator outputs in the driver
69  * @param stop_motors if true, all motors must be stopped (if false, individual motors
70  * might still be stopped via outputs[i] == disarmed_value)
71  * @param outputs individual actuator outputs in range [min, max] or failsafe/disarmed value
72  * @param num_outputs number of outputs (<= max_num_outputs)
73  * @param num_control_groups_updated number of actuator_control groups updated
74  * @return if true, the update got handled, and actuator_outputs can be published
75  */
76  virtual bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
77  unsigned num_outputs, unsigned num_control_groups_updated) = 0;
78 
79  /** called whenever the mixer gets updated/reset */
80  virtual void mixerChanged() {};
81 };
82 
83 /**
84  * @class MixingOutput
85  * This handles the mixing, arming/disarming and all subscriptions required for that.
86  *
87  * It can also drive the scheduling of the OutputModuleInterface (via uORB callbacks
88  * to reduce output latency).
89  */
90 class MixingOutput : public ModuleParams
91 {
92 public:
94 
95  enum class SchedulingPolicy {
96  Disabled, ///< Do not drive scheduling (the module needs to call ScheduleOnInterval() for example)
97  Auto ///< Drive scheduling based on subscribed actuator controls topics (via uORB callbacks)
98  };
99 
100  /**
101  * Contructor
102  * @param max_num_outputs maximum number of supported outputs
103  * @param interface Parent module for scheduling, parameter updates and callbacks
104  * @param scheduling_policy
105  * @param support_esc_calibration true if the output module supports ESC calibration via max, then min setting
106  * @param ramp_up true if motor ramp up from disarmed to min upon arming is wanted
107  */
108  MixingOutput(uint8_t max_num_outputs, OutputModuleInterface &interface, SchedulingPolicy scheduling_policy,
109  bool support_esc_calibration, bool ramp_up = true);
110 
111  ~MixingOutput();
112 
113  void setDriverInstance(uint8_t instance) { _driver_instance = instance; }
114 
115  void printStatus() const;
116 
117  /**
118  * Call this regularly from Run(). It will call interface.updateOutputs().
119  * @return true if outputs were updated
120  */
121  bool update();
122 
123  /**
124  * Check for subscription updates (e.g. after a mixer is loaded).
125  * Call this at the very end of Run() if allow_wq_switch
126  * @param allow_wq_switch if true
127  * @return true if subscriptions got changed
128  */
129  bool updateSubscriptions(bool allow_wq_switch);
130 
131  /**
132  * unregister uORB subscription callbacks
133  */
134  void unregister();
135 
136  void setMaxTopicUpdateRate(unsigned max_topic_update_interval_us);
137 
138  /**
139  * Reset (unload) the complete mixer, called from another thread.
140  * This is thread-safe, as long as only one other thread at a time calls this.
141  */
142  void resetMixerThreadSafe();
143 
144  void resetMixer();
145 
146  /**
147  * Load (append) a new mixer from a buffer, called from another thread.
148  * This is thread-safe, as long as only one other thread at a time calls this.
149  * @return 0 on success, <0 error otherwise
150  */
151  int loadMixerThreadSafe(const char *buf, unsigned len);
152 
153  int loadMixer(const char *buf, unsigned len);
154 
155  const actuator_armed_s &armed() const { return _armed; }
156 
157  MixerGroup *mixers() const { return _mixers; }
158 
159  void setAllFailsafeValues(uint16_t value);
160  void setAllDisarmedValues(uint16_t value);
161  void setAllMinValues(uint16_t value);
162  void setAllMaxValues(uint16_t value);
163 
164  uint16_t &reverseOutputMask() { return _reverse_output_mask; }
165  uint16_t &failsafeValue(int index) { return _failsafe_value[index]; }
166  /** Disarmed values: disarmedValue < minValue needs to hold */
167  uint16_t &disarmedValue(int index) { return _disarmed_value[index]; }
168  uint16_t &minValue(int index) { return _min_value[index]; }
169  uint16_t &maxValue(int index) { return _max_value[index]; }
170 
171  /**
172  * Get the motor index that maps from PX4 convention to the configured one
173  * @param index motor index in [0, num_motors-1]
174  * @return reordered motor index. When out of range, the input index is returned
175  */
176  int reorderedMotorIndex(int index) const;
177 
178  void setIgnoreLockdown(bool ignore_lockdown) { _ignore_lockdown = ignore_lockdown; }
179 
180 protected:
181  void updateParams() override;
182 
183 private:
184  void handleCommands();
185 
186  bool armNoThrottle() const
187  {
189  }
190 
191  unsigned motorTest();
192 
193  void updateOutputSlewrate();
194  void setAndPublishActuatorOutputs(unsigned num_outputs, actuator_outputs_s &actuator_outputs);
195  void publishMixerStatus(const actuator_outputs_s &actuator_outputs);
196  void updateLatencyPerfCounter(const actuator_outputs_s &actuator_outputs);
197 
198  static int controlCallback(uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input);
199 
200  enum class MotorOrdering : int32_t {
201  PX4 = 0,
202  Betaflight = 1
203  };
204 
205  struct Command {
206  enum class Type : int {
207  None,
208  resetMixer,
209  loadMixer
210  };
211  px4::atomic<int> command{(int)Type::None};
212  const char *mixer_buf;
214  int result;
215  };
216  Command _command; ///< incoming commands (from another thread)
217 
218  /**
219  * Reorder outputs according to _param_mot_ordering
220  * @param values values to reorder
221  */
222  inline void reorderOutputs(uint16_t values[MAX_ACTUATORS]);
223 
224  void lock() { do {} while (px4_sem_wait(&_lock) != 0); }
225  void unlock() { px4_sem_post(&_lock); }
226 
227  px4_sem_t _lock; /**< lock to protect access to work queue changes (includes ScheduleNow calls from another thread) */
228 
229  uint16_t _failsafe_value[MAX_ACTUATORS] {};
230  uint16_t _disarmed_value[MAX_ACTUATORS] {};
231  uint16_t _min_value[MAX_ACTUATORS] {};
232  uint16_t _max_value[MAX_ACTUATORS] {};
233  uint16_t _current_output_value[MAX_ACTUATORS] {}; ///< current output values (reordered)
234  uint16_t _reverse_output_mask{0}; ///< reverses the interval [min, max] -> [max, min], NOT motor direction
236 
238  uORB::SubscriptionCallbackWorkItem _control_subs[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS];
239 
241  uORB::PublicationMulti<multirotor_motor_limits_s> _to_mixer_status{ORB_ID(multirotor_motor_limits), ORB_PRIO_DEFAULT}; ///< mixer status flags
242 
243  actuator_controls_s _controls[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS] {};
245 
246  hrt_abstime _time_last_mix{0};
247  unsigned _max_topic_update_interval_us{0}; ///< max _control_subs topic update interval (0=unlimited)
248 
249  bool _throttle_armed{false};
250  bool _ignore_lockdown{false}; ///< if true, ignore the _armed.lockdown flag (for HIL outputs)
251 
252  MixerGroup *_mixers{nullptr};
253  uint32_t _groups_required{0};
254  uint32_t _groups_subscribed{1u << 31}; ///< initialize to a different value than _groups_required and outside of (1 << NUM_ACTUATOR_CONTROL_GROUPS)
255 
258 
259  bool _wq_switched{false};
260  uint8_t _driver_instance{0}; ///< for boards that supports multiple outputs (e.g. PX4IO + FMU)
261  const uint8_t _max_num_outputs;
262 
263  struct MotorTest {
264  uORB::Subscription test_motor_sub{ORB_ID(test_motor)};
265  bool in_test_mode{false};
266  hrt_abstime timeout{0};
267  };
269 
271 
273 
274  DEFINE_PARAMETERS(
275  (ParamInt<px4::params::MC_AIRMODE>) _param_mc_airmode, ///< multicopter air-mode
276  (ParamFloat<px4::params::MOT_SLEW_MAX>) _param_mot_slew_max,
277  (ParamFloat<px4::params::THR_MDL_FAC>) _param_thr_mdl_fac, ///< thrust to motor control signal modelling factor
278  (ParamInt<px4::params::MOT_ORDERING>) _param_mot_ordering
279 
280  )
281 };
const actuator_armed_s & armed() const
perf_counter_t _control_latency_perf
actuator_controls_s _controls[1]
uint16_t & reverseOutputMask()
LidarLite * instance
Definition: ll40ls.cpp:65
const SchedulingPolicy _scheduling_policy
Command _command
incoming commands (from another thread)
static constexpr int MAX_ACTUATORS
void setIgnoreLockdown(bool ignore_lockdown)
bool in_esc_calibration_mode
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
uint16_t & maxValue(int index)
Header common to all counters.
OutputModuleInterface & _interface
OutputModuleInterface(const char *name, const px4::wq_config_t &config)
virtual void mixerChanged()
called whenever the mixer gets updated/reset
#define PWM_OUTPUT_MAX_CHANNELS
uint32_t _groups_required
Base class for an output module.
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
bool armNoThrottle() const
const char * name
Definition: tests_main.c:58
uint16_t & disarmedValue(int index)
Disarmed values: disarmedValue < minValue needs to hold.
px4_sem_t _lock
lock to protect access to work queue changes (includes ScheduleNow calls from another thread) ...
MotorTest _motor_test
void setDriverInstance(uint8_t instance)
Definition: bst.cpp:62
uint16_t & minValue(int index)
virtual bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs, unsigned num_control_groups_updated)=0
Callback to update the (physical) actuator outputs in the driver.
Group of mixers, built up from single mixers and processed in order when mixing.
Definition: MixerGroup.hpp:42
MixerGroup * mixers() const
uint32_t _groups_subscribed
const uint8_t _max_num_outputs
Library for output limiting (PWM for example)
This handles the mixing, arming/disarming and all subscriptions required for that.
output_limit_t _output_limit
const bool _support_esc_calibration
Performance measuring tools.
uint16_t & failsafeValue(int index)