mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
HAL_Linux: fixed build for Disco with I2C changes
This commit is contained in:
parent
f5a20d28bc
commit
b69170febd
@ -180,7 +180,7 @@ static RCOutput_PCA9685 rcoutDriver(i2c_mgr_instance.get_device(i2c_devpaths, PC
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
|
||||
static RCOutput_QFLIGHT rcoutDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||
static RCOutput_Disco rcoutDriver;
|
||||
static RCOutput_Disco rcoutDriver(i2c_mgr_instance.get_device(HAL_RCOUT_DISCO_BLDC_I2C_BUS, HAL_RCOUT_DISCO_BLDC_I2C_ADDR));
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
|
||||
static RCOutput_Sysfs rcoutDriver(0, 0, 14);
|
||||
#else
|
||||
|
@ -14,6 +14,7 @@
|
||||
#include <utility>
|
||||
|
||||
#include <AP_HAL/utility/sparse-endian.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#include "Util.h"
|
||||
|
||||
@ -22,23 +23,7 @@
|
||||
#define BEBOP_BLDC_STARTPROP 0x40
|
||||
#define BEBOP_BLDC_SETREFSPEED 0x02
|
||||
|
||||
struct PACKED bldc_ref_speed_data {
|
||||
uint8_t cmd;
|
||||
uint16_t rpm[BEBOP_BLDC_MOTORS_NUM];
|
||||
uint8_t enable_security;
|
||||
uint8_t checksum;
|
||||
};
|
||||
|
||||
#define BEBOP_BLDC_GETOBSDATA 0x20
|
||||
struct PACKED bldc_obs_data {
|
||||
uint16_t rpm[BEBOP_BLDC_MOTORS_NUM];
|
||||
uint16_t batt_mv;
|
||||
uint8_t status;
|
||||
uint8_t error;
|
||||
uint8_t motors_err;
|
||||
uint8_t temp;
|
||||
uint8_t checksum;
|
||||
};
|
||||
|
||||
struct PACKED bldc_info {
|
||||
uint8_t version_maj;
|
||||
@ -524,7 +509,7 @@ void RCOutput_Bebop::_run_rcout()
|
||||
/* start propellers if the speed of the 4 motors is >= min speed
|
||||
* min speed set to min_pwm + 50*/
|
||||
for (i = 0; i < _n_motors; i++) {
|
||||
if (current_period_us[i] <= _min_pwm + 50)
|
||||
if (current_period_us[i] <= _min_pwm + 50) {
|
||||
break;
|
||||
}
|
||||
_rpm[bebop_bldc_channels[i]] = _period_us_to_rpm(current_period_us[i]);
|
||||
|
@ -29,6 +29,11 @@
|
||||
|
||||
namespace Linux {
|
||||
|
||||
RCOutput_Disco::RCOutput_Disco(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||
: bebop_out(std::move(dev))
|
||||
{
|
||||
}
|
||||
|
||||
void RCOutput_Disco::init()
|
||||
{
|
||||
sysfs_out.init();
|
||||
|
@ -6,7 +6,7 @@
|
||||
|
||||
class Linux::RCOutput_Disco : public AP_HAL::RCOutput {
|
||||
public:
|
||||
RCOutput_Disco(void) {}
|
||||
RCOutput_Disco(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
||||
~RCOutput_Disco() {}
|
||||
|
||||
static RCOutput_Bebop *from(AP_HAL::RCOutput *rcoutput)
|
||||
|
Loading…
Reference in New Issue
Block a user