APM:Libraries
RCOutput_Bebop.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_HAL_Linux.h"
4 #include <AP_HAL/I2CDevice.h>
5 
6 struct bldc_info;
7 
8 namespace Linux {
9 
12 #if CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_DISCO
13  BEBOP_BLDC_MOTOR_2,
14  BEBOP_BLDC_MOTOR_3,
15  BEBOP_BLDC_MOTOR_4,
16 #endif
18 };
19 
25 };
26 
27 /* description of the bldc status */
28 #define BEBOP_BLDC_STATUS_INIT 0
29 #define BEBOP_BLDC_STATUS_IDLE 1
30 #define BEBOP_BLDC_STATUS_RAMPING 2
31 #define BEBOP_BLDC_STATUS_SPINNING_1 3
32 #define BEBOP_BLDC_STATUS_SPINNING_2 4
33 #define BEBOP_BLDC_STATUS_STOPPING 5
34 #define BEBOP_BLDC_STATUS_CRITICAL 6
35 
36 /* description of the bldc errno */
37 #define BEBOP_BLDC_ERRNO_EEPROM 1
38 #define BEBOP_BLDC_ERRNO_MOTOR_STALLED 2
39 #define BEBOP_BLDC_ERRNO_PROP_SECU 3
40 #define BEBOP_BLDC_ERRNO_COM_LOST 4
41 #define BEBOP_BLDC_ERRNO_BATT_LEVEL 9
42 #define BEBOP_BLDC_ERRNO_LIPO 10
43 #define BEBOP_BLDC_ERRNO_MOTOR_HW 11
44 
46 public:
49  uint16_t batt_mv;
50  uint8_t status;
51  uint8_t error;
52  uint8_t motors_err;
53  uint8_t temperature;
54 };
55 
57 public:
59 
61  return static_cast<RCOutput_Bebop*>(rcout);
62  }
63 
64  void init() override;
65  void set_freq(uint32_t chmask, uint16_t freq_hz) override;
66  uint16_t get_freq(uint8_t ch) override;
67  void enable_ch(uint8_t ch) override;
68  void disable_ch(uint8_t ch) override;
69  void write(uint8_t ch, uint16_t period_us) override;
70  void cork() override;
71  void push() override;
72  uint16_t read(uint8_t ch) override;
73  void read(uint16_t* period_us, uint8_t len) override;
74  void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override;
75  int read_obs_data(BebopBLDC_ObsData &data);
76  void play_note(uint8_t pwm, uint16_t period_us, uint16_t duration_ms);
77 
78 private:
80  uint16_t _request_period_us[BEBOP_BLDC_MOTORS_NUM];
81  uint16_t _period_us[BEBOP_BLDC_MOTORS_NUM];
82  uint16_t _rpm[BEBOP_BLDC_MOTORS_NUM];
83  uint16_t _frequency;
84  uint16_t _min_pwm;
85  uint16_t _max_pwm;
86  uint8_t _n_motors=4;
87  uint8_t _state;
88  bool _corking = false;
89  uint16_t _max_rpm;
90 
91  uint8_t _checksum(uint8_t *data, unsigned int len);
92  void _start_prop();
93  void _toggle_gpio(uint8_t mask);
94  void _set_ref_speed(uint16_t rpm[BEBOP_BLDC_MOTORS_NUM]);
95  bool _get_info(struct bldc_info *info);
96  void _stop_prop();
97  void _clear_error();
98  void _play_sound(uint8_t sound);
99  uint16_t _period_us_to_rpm(uint16_t period_us);
100 
101  /* thread related members */
102  pthread_t _thread;
103  pthread_mutex_t _mutex;
104  pthread_cond_t _cond;
105  void _run_rcout();
106  static void *_control_thread(void *arg);
107 };
108 
109 }
static RCOutput_Bebop * from(AP_HAL::RCOutput *rcout)
pthread_cond_t _cond
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
static uint16_t pwm
Definition: RCOutput.cpp:20
uint8_t rpm_saturated[BEBOP_BLDC_MOTORS_NUM]
bebop_bldc_motor
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
uint16_t rpm[BEBOP_BLDC_MOTORS_NUM]
bebop_bldc_sound
void init()
Generic board initialization function.
Definition: system.cpp:136
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
pthread_mutex_t _mutex