mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
linux_pwm_out: move protocols to board-specific directories
This also removes the pca9685 output, which was unused, and there's also pca9685_pwm_out.
This commit is contained in:
parent
b0a5d431d3
commit
439fb00aed
@ -32,6 +32,7 @@
|
||||
############################################################################
|
||||
|
||||
add_library(drivers_board
|
||||
board_pwm_out.cpp
|
||||
i2c.cpp
|
||||
spi.cpp
|
||||
)
|
||||
|
||||
@ -31,7 +31,11 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include "ocpoc_mmap.h"
|
||||
#ifndef MODULE_NAME
|
||||
#define MODULE_NAME "ocpoc_pwm_out"
|
||||
#endif
|
||||
|
||||
#include "board_pwm_out.h"
|
||||
|
||||
#include <px4_platform_common/log.h>
|
||||
|
||||
@ -39,7 +43,7 @@
|
||||
#include <sys/mman.h>
|
||||
#include <unistd.h>
|
||||
|
||||
using namespace linux_pwm_out;
|
||||
using namespace pwm_out;
|
||||
|
||||
#define RCOUT_ZYNQ_PWM_BASE 0x43c00000
|
||||
static const int TICK_PER_US = 50;
|
||||
@ -33,9 +33,11 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "common.h"
|
||||
#include <px4_platform/pwm_out_base.h>
|
||||
|
||||
namespace linux_pwm_out
|
||||
#define BOARD_PWM_OUT_IMPL OcpocMmapPWMOut
|
||||
|
||||
namespace pwm_out
|
||||
{
|
||||
|
||||
/**
|
||||
@ -32,6 +32,7 @@
|
||||
############################################################################
|
||||
|
||||
px4_add_library(drivers_board
|
||||
board_pwm_out.cpp
|
||||
i2c.cpp
|
||||
init.cpp
|
||||
spi.cpp
|
||||
|
||||
@ -30,7 +30,10 @@
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
#ifdef CONFIG_ARCH_BOARD_BEAGLEBONE_BLUE
|
||||
|
||||
#ifndef MODULE_NAME
|
||||
#define MODULE_NAME "bbblue_pwm_out"
|
||||
#endif
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
@ -39,9 +42,9 @@
|
||||
#include <robotcontrol.h>
|
||||
#include <board_config.h>
|
||||
|
||||
#include "bbblue_pwm_rc.h"
|
||||
#include "board_pwm_out.h"
|
||||
|
||||
using namespace linux_pwm_out;
|
||||
using namespace pwm_out;
|
||||
|
||||
BBBlueRcPWMOut::BBBlueRcPWMOut(int max_num_outputs) : _num_outputs(max_num_outputs)
|
||||
{
|
||||
@ -79,4 +82,3 @@ int BBBlueRcPWMOut::send_output_pwm(const uint16_t *pwm, int num_outputs)
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif // CONFIG_ARCH_BOARD_BEAGLEBONE_BLUE
|
||||
@ -33,9 +33,11 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "common.h"
|
||||
#include <px4_platform/pwm_out_base.h>
|
||||
|
||||
namespace linux_pwm_out
|
||||
#define BOARD_PWM_OUT_IMPL BBBlueRcPWMOut
|
||||
|
||||
namespace pwm_out
|
||||
{
|
||||
|
||||
/**
|
||||
@ -32,6 +32,7 @@
|
||||
############################################################################
|
||||
|
||||
add_library(drivers_board
|
||||
board_pwm_out.cpp
|
||||
i2c.cpp
|
||||
spi.cpp
|
||||
)
|
||||
|
||||
@ -30,18 +30,22 @@
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
#ifndef MODULE_NAME
|
||||
#define MODULE_NAME "navio_sysfs_pwm_out"
|
||||
#endif
|
||||
|
||||
#include "navio_sysfs.h"
|
||||
#include "board_pwm_out.h"
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <unistd.h>
|
||||
#include <px4_platform_common/log.h>
|
||||
|
||||
using namespace linux_pwm_out;
|
||||
using namespace pwm_out;
|
||||
|
||||
NavioSysfsPWMOut::NavioSysfsPWMOut(const char *device, int max_num_outputs)
|
||||
: _device(device)
|
||||
const char NavioSysfsPWMOut::_device[] = "/sys/class/pwm/pwmchip0";
|
||||
|
||||
NavioSysfsPWMOut::NavioSysfsPWMOut(int max_num_outputs)
|
||||
{
|
||||
if (max_num_outputs > MAX_NUM_PWM) {
|
||||
PX4_WARN("number of outputs too large. Setting to %i", MAX_NUM_PWM);
|
||||
@ -33,9 +33,11 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "common.h"
|
||||
#include <px4_platform/pwm_out_base.h>
|
||||
|
||||
namespace linux_pwm_out
|
||||
#define BOARD_PWM_OUT_IMPL NavioSysfsPWMOut
|
||||
|
||||
namespace pwm_out
|
||||
{
|
||||
|
||||
/**
|
||||
@ -45,7 +47,7 @@ namespace linux_pwm_out
|
||||
class NavioSysfsPWMOut : public PWMOutBase
|
||||
{
|
||||
public:
|
||||
NavioSysfsPWMOut(const char *device, int max_num_outputs);
|
||||
NavioSysfsPWMOut(int max_num_outputs);
|
||||
virtual ~NavioSysfsPWMOut();
|
||||
|
||||
int init() override;
|
||||
@ -61,7 +63,7 @@ private:
|
||||
int _pwm_fd[MAX_NUM_PWM];
|
||||
int _pwm_num;
|
||||
|
||||
const char *_device;
|
||||
static const char _device[];
|
||||
};
|
||||
|
||||
}
|
||||
@ -23,7 +23,6 @@ px4_add_board(
|
||||
gps
|
||||
#imu # all available imu drivers
|
||||
imu/invensense/mpu9250
|
||||
linux_pwm_out
|
||||
#magnetometer # all available magnetometer drivers
|
||||
magnetometer/hmc5883
|
||||
pca9685_pwm_out
|
||||
|
||||
@ -35,7 +35,7 @@
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
namespace linux_pwm_out
|
||||
namespace pwm_out
|
||||
{
|
||||
|
||||
/**
|
||||
@ -54,4 +54,4 @@ public:
|
||||
};
|
||||
|
||||
|
||||
} /* namespace rpi_pwm_out */
|
||||
} /* namespace pwm_out */
|
||||
@ -83,8 +83,8 @@ sleep 1
|
||||
#rc_input start -d /dev/ttyS4
|
||||
|
||||
# default: etc/mixers/quad_x.main.mix, 8 output channels
|
||||
linux_pwm_out start -p bbblue_rc -m etc/mixers/quad_x.main.mix
|
||||
#linux_pwm_out start -p bbblue_rc -m etc/mixers/AETRFG.main.mix
|
||||
linux_pwm_out start -m etc/mixers/quad_x.main.mix
|
||||
#linux_pwm_out start -m etc/mixers/AETRFG.main.mix
|
||||
|
||||
logger start -t -b 200
|
||||
|
||||
|
||||
@ -78,8 +78,8 @@ sleep 1
|
||||
rc_input start -d /dev/ttyS4
|
||||
|
||||
# default: etc/mixers/quad_x.main.mix, 8 output channels
|
||||
#linux_pwm_out start -p bbblue_rc -m etc/mixers/quad_x.main.mix
|
||||
linux_pwm_out start -p bbblue_rc -m etc/mixers/AETRFG.main.mix
|
||||
#linux_pwm_out start -m etc/mixers/quad_x.main.mix
|
||||
linux_pwm_out start -m etc/mixers/AETRFG.main.mix
|
||||
|
||||
logger start -t -b 200
|
||||
|
||||
|
||||
@ -45,6 +45,6 @@ mavlink stream -d /dev/ttyPS1 -s ATTITUDE -r 50
|
||||
|
||||
rc_input start -d /dev/ttyS2
|
||||
|
||||
linux_pwm_out start -p ocpoc_mmap -m etc/mixers/quad_x.main.mix
|
||||
linux_pwm_out start -m etc/mixers/quad_x.main.mix
|
||||
logger start -t -b 200
|
||||
mavlink boot_complete
|
||||
|
||||
@ -36,11 +36,7 @@ px4_add_module(
|
||||
MAIN linux_pwm_out
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
PCA9685.cpp
|
||||
navio_sysfs.cpp
|
||||
linux_pwm_out.cpp
|
||||
ocpoc_mmap.cpp
|
||||
bbblue_pwm_rc.cpp
|
||||
DEPENDS
|
||||
output_limit
|
||||
)
|
||||
|
||||
@ -1,193 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2017 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
*
|
||||
* Original Author : Georgi Todorov
|
||||
* Edited by : Tord Wessman
|
||||
* Created on : Nov 22, 2013
|
||||
* Rewrite : Fan.zhang 421395590@qq.com
|
||||
* Updated on : Mar 2, 2017
|
||||
****************************************************************************/
|
||||
|
||||
#include <sys/stat.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <unistd.h>
|
||||
#include <linux/i2c-dev.h>
|
||||
#include <stdio.h> /* Standard I/O functions */
|
||||
#include <fcntl.h>
|
||||
#include <inttypes.h>
|
||||
#include <errno.h>
|
||||
#include <math.h>
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include "PCA9685.h"
|
||||
|
||||
#include <px4_platform_common/log.h>
|
||||
|
||||
using namespace linux_pwm_out;
|
||||
|
||||
int PCA9685::init(int bus, int address)
|
||||
{
|
||||
_fd = open_fd(bus, address);
|
||||
reset();
|
||||
|
||||
usleep(1000 * 100);
|
||||
/* 12BIT 精度输出下,好赢电调可以到200HZ刷新 */
|
||||
/* 200HZ for 12bit Resolution, supported by most of the esc's */
|
||||
setPWMFreq(200);
|
||||
usleep(1000 * 1000);
|
||||
return 0;
|
||||
}
|
||||
|
||||
int PCA9685::send_output_pwm(const uint16_t *pwm, int num_outputs)
|
||||
{
|
||||
if (num_outputs > 16) {
|
||||
num_outputs = 16;
|
||||
}
|
||||
|
||||
for (int i = 0; i < num_outputs; ++i) {
|
||||
setPWM(i, pwm[i]);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
PCA9685::PCA9685()
|
||||
{
|
||||
init(PCA9685_DEFAULT_I2C_BUS, PCA9685_DEFAULT_I2C_ADDR);
|
||||
}
|
||||
|
||||
PCA9685::PCA9685(int bus, int address)
|
||||
{
|
||||
init(bus, address);
|
||||
}
|
||||
|
||||
PCA9685::~PCA9685()
|
||||
{
|
||||
reset();
|
||||
|
||||
if (_fd >= 0) {
|
||||
close(_fd);
|
||||
}
|
||||
}
|
||||
|
||||
void PCA9685::reset()
|
||||
{
|
||||
if (_fd != -1) {
|
||||
write_byte(_fd, MODE1, 0x00); //Normal mode
|
||||
write_byte(_fd, MODE2, 0x04); //Normal mode
|
||||
}
|
||||
}
|
||||
|
||||
void PCA9685::setPWMFreq(int freq)
|
||||
{
|
||||
if (_fd != -1) {
|
||||
uint8_t prescale = (CLOCK_FREQ / MAX_PWM_RES / freq) - 1;
|
||||
//printf ("Setting prescale value to: %d\n", prescale);
|
||||
//printf ("Using Frequency: %d\n", freq);
|
||||
|
||||
uint8_t oldmode = read_byte(_fd, MODE1);
|
||||
uint8_t newmode = (oldmode & 0x7F) | 0x10; //sleep
|
||||
write_byte(_fd, MODE1, newmode); // go to sleep
|
||||
write_byte(_fd, PRE_SCALE, prescale);
|
||||
write_byte(_fd, MODE1, oldmode);
|
||||
usleep(10 * 1000);
|
||||
write_byte(_fd, MODE1, oldmode | 0x80);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void PCA9685::setPWM(uint8_t led, int value)
|
||||
{
|
||||
setPWM(led, 0, value);
|
||||
}
|
||||
|
||||
void PCA9685::setPWM(uint8_t led, int on_value, int off_value)
|
||||
{
|
||||
if (_fd != -1) {
|
||||
write_byte(_fd, LED0_ON_L + LED_MULTIPLYER * led, on_value & 0xFF);
|
||||
|
||||
write_byte(_fd, LED0_ON_H + LED_MULTIPLYER * led, on_value >> 8);
|
||||
|
||||
write_byte(_fd, LED0_OFF_L + LED_MULTIPLYER * led, off_value & 0xFF);
|
||||
|
||||
write_byte(_fd, LED0_OFF_H + LED_MULTIPLYER * led, off_value >> 8);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
uint8_t PCA9685::read_byte(int fd, uint8_t address)
|
||||
{
|
||||
|
||||
uint8_t buf[1];
|
||||
buf[0] = address;
|
||||
|
||||
if (write(fd, buf, 1) != 1) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (read(fd, buf, 1) != 1) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
return buf[0];
|
||||
}
|
||||
|
||||
void PCA9685::write_byte(int fd, uint8_t address, uint8_t data)
|
||||
{
|
||||
uint8_t buf[2];
|
||||
buf[0] = address;
|
||||
buf[1] = data;
|
||||
|
||||
if (write(fd, buf, sizeof(buf)) != sizeof(buf)) {
|
||||
PX4_ERR("Write failed (%i)", errno);
|
||||
}
|
||||
}
|
||||
|
||||
int PCA9685::open_fd(int bus, int address)
|
||||
{
|
||||
int fd;
|
||||
char bus_file[64];
|
||||
snprintf(bus_file, sizeof(bus_file), "/dev/i2c-%d", bus);
|
||||
|
||||
if ((fd = open(bus_file, O_RDWR)) < 0) {
|
||||
PX4_ERR("Couldn't open I2C Bus %d [open_fd():open %d]", bus, errno);
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (ioctl(fd, I2C_SLAVE, address) < 0) {
|
||||
PX4_ERR("I2C slave %d failed [open_fd():ioctl %d]", address, errno);
|
||||
return -1;
|
||||
}
|
||||
|
||||
return fd;
|
||||
}
|
||||
@ -1,143 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2017 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
*
|
||||
* Original Author : Georgi Todorov
|
||||
* Edited by : Tord Wessman
|
||||
* Created on : Nov 22, 2013
|
||||
* Rewrite : Fan.zhang 421395590@qq.com
|
||||
* Updated on : Mar 2, 2017
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
#include <inttypes.h>
|
||||
#include "common.h"
|
||||
|
||||
namespace linux_pwm_out
|
||||
{
|
||||
|
||||
// Register Definitions
|
||||
// 寄存器定义
|
||||
#define MODE1 0x00 //Mode register 1
|
||||
#define MODE2 0x01 //Mode register 2
|
||||
#define SUBADR1 0x02 //I2C-bus subaddress 1
|
||||
#define SUBADR2 0x03 //I2C-bus subaddress 2
|
||||
#define SUBADR3 0x04 //I2C-bus subaddress 3
|
||||
#define ALLCALLADR 0x05 //LED All Call I2C-bus address
|
||||
#define LED0 0x6 //LED0 start register
|
||||
#define LED0_ON_L 0x6 //LED0 output and brightness control byte 0
|
||||
#define LED0_ON_H 0x7 //LED0 output and brightness control byte 1
|
||||
#define LED0_OFF_L 0x8 //LED0 output and brightness control byte 2
|
||||
#define LED0_OFF_H 0x9 //LED0 output and brightness control byte 3
|
||||
#define LED_MULTIPLYER 4 // For the other 15 channels
|
||||
#define ALLLED_ON_L 0xFA //load all the LEDn_ON registers, byte 0 (turn 0-7 channels on)
|
||||
#define ALLLED_ON_H 0xFB //load all the LEDn_ON registers, byte 1 (turn 8-15 channels on)
|
||||
#define ALLLED_OFF_L 0xFC //load all the LEDn_OFF registers, byte 0 (turn 0-7 channels off)
|
||||
#define ALLLED_OFF_H 0xFD //load all the LEDn_OFF registers, byte 1 (turn 8-15 channels off)
|
||||
#define PRE_SCALE 0xFE //prescaler for output frequency
|
||||
#define MAX_PWM_RES 4096 //Resolution 4096=12bit 分辨率,按2的阶乘计算,12bit为4096
|
||||
#define CLOCK_FREQ 25000000.0 //25MHz default osc clock
|
||||
#define PCA9685_DEFAULT_I2C_ADDR 0x40 // default i2c address for pca9685 默认i2c地址为0x40
|
||||
#define PCA9685_DEFAULT_I2C_BUS 1 // default i2c bus for pca9685 默认为1
|
||||
|
||||
//! Main class that exports features for PCA9685 chip
|
||||
class PCA9685 : public PWMOutBase
|
||||
{
|
||||
public:
|
||||
|
||||
PCA9685();
|
||||
|
||||
/**
|
||||
* Constructor takes bus and address arguments
|
||||
* @param bus the bus to use in /dev/i2c-%d.
|
||||
* @param address the device address on bus
|
||||
*/
|
||||
PCA9685(int bus, int address);
|
||||
|
||||
int init() override { return _fd >= 0 ? 0 : -1; }
|
||||
|
||||
int send_output_pwm(const uint16_t *pwm, int num_outputs) override;
|
||||
|
||||
|
||||
int init(int bus, int address);
|
||||
virtual ~PCA9685();
|
||||
|
||||
/** Sets PCA9685 mode to 00 */
|
||||
void reset();
|
||||
|
||||
/**
|
||||
* Set the frequency of PWM
|
||||
* @param freq desired frequency. 40Hz to 1000Hz using internal 25MHz oscillator.
|
||||
*/
|
||||
void setPWMFreq(int freq);
|
||||
|
||||
/**
|
||||
* PWM a single channel with custom on time.
|
||||
* send pwm vale to led(channel)
|
||||
* @param channel
|
||||
* @param on_value 0-4095 value to turn on the pulse
|
||||
* @param off_value 0-4095 value to turn off the pulse
|
||||
*/
|
||||
void setPWM(uint8_t channel, int on_value, int off_value);
|
||||
|
||||
/**
|
||||
* send pwm value to led(channel),
|
||||
* value should be range of 0-4095
|
||||
*/
|
||||
void setPWM(uint8_t channel, int value);
|
||||
|
||||
private:
|
||||
int _fd = -1; ///< I2C device file descriptor
|
||||
|
||||
/**
|
||||
* Read a single byte from PCA9685
|
||||
* @param fd file descriptor for I/O
|
||||
* @param address register address to read from
|
||||
* @return read byte
|
||||
*/
|
||||
uint8_t read_byte(int fd, uint8_t address);
|
||||
|
||||
/**
|
||||
* Write a single byte to PCA9685
|
||||
* @param fd file descriptor for I/O
|
||||
* @param address register address to write to
|
||||
* @param data 8 bit data to write
|
||||
*/
|
||||
void write_byte(int fd, uint8_t address, uint8_t data);
|
||||
|
||||
/**
|
||||
* Open device file for PCA9685 I2C bus
|
||||
* @return fd returns the file descriptor number or -1 on error
|
||||
*/
|
||||
int open_fd(int bus, int address);
|
||||
};
|
||||
|
||||
}
|
||||
@ -58,22 +58,16 @@
|
||||
#include <output_limit/output_limit.h>
|
||||
#include <perf/perf_counter.h>
|
||||
|
||||
#include "common.h"
|
||||
#include "navio_sysfs.h"
|
||||
#include "PCA9685.h"
|
||||
#include "ocpoc_mmap.h"
|
||||
#include "bbblue_pwm_rc.h"
|
||||
#include <board_pwm_out.h>
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
namespace linux_pwm_out
|
||||
namespace pwm_out
|
||||
{
|
||||
static px4_task_t _task_handle = -1;
|
||||
volatile bool _task_should_exit = false;
|
||||
static bool _is_running = false;
|
||||
|
||||
static char _device[64] = "/sys/class/pwm/pwmchip0";
|
||||
static char _protocol[64] = "navio";
|
||||
static int _max_num_outputs = 8; ///< maximum number of outputs the driver should use
|
||||
static char _mixer_filename[64] = "etc/mixers/quad_x.main.mix";
|
||||
|
||||
@ -228,27 +222,7 @@ void task_main(int argc, char *argv[])
|
||||
return;
|
||||
}
|
||||
|
||||
PWMOutBase *pwm_out;
|
||||
|
||||
if (strcmp(_protocol, "pca9685") == 0) {
|
||||
PX4_INFO("Starting PWM output in PCA9685 mode");
|
||||
pwm_out = new PCA9685();
|
||||
|
||||
} else if (strcmp(_protocol, "ocpoc_mmap") == 0) {
|
||||
PX4_INFO("Starting PWM output in ocpoc_mmap mode");
|
||||
pwm_out = new OcpocMmapPWMOut(_max_num_outputs);
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_BEAGLEBONE_BLUE
|
||||
|
||||
} else if (strcmp(_protocol, "bbblue_rc") == 0) {
|
||||
PX4_INFO("Starting PWM output in bbblue_rc mode");
|
||||
pwm_out = new BBBlueRcPWMOut(_max_num_outputs);
|
||||
#endif
|
||||
|
||||
} else { /* navio */
|
||||
PX4_INFO("Starting PWM output in Navio mode");
|
||||
pwm_out = new NavioSysfsPWMOut(_device, _max_num_outputs);
|
||||
}
|
||||
PWMOutBase *pwm_out = new BOARD_PWM_OUT_IMPL(_max_num_outputs);
|
||||
|
||||
if (pwm_out->init() != 0) {
|
||||
PX4_ERR("PWM output init failed");
|
||||
@ -494,20 +468,16 @@ void stop()
|
||||
|
||||
void usage()
|
||||
{
|
||||
PX4_INFO("usage: pwm_out start [-d pwmdevice] [-m mixerfile] [-p protocol]");
|
||||
PX4_INFO(" -d pwmdevice : sysfs device for pwm generation (only for Navio)");
|
||||
PX4_INFO(" (default /sys/class/pwm/pwmchip0)");
|
||||
PX4_INFO("usage: linux_pwm_out start [-m mixerfile]");
|
||||
PX4_INFO(" -m mixerfile : path to mixerfile");
|
||||
PX4_INFO(" (default etc/mixers/quad_x.main.mix)");
|
||||
PX4_INFO(" -p protocol : driver output protocol (navio|pca9685|ocpoc_mmap|bbblue_rc)");
|
||||
PX4_INFO(" (default is navio)");
|
||||
PX4_INFO(" -n num_outputs : maximum number of outputs the driver should use");
|
||||
PX4_INFO(" (default is 8)");
|
||||
PX4_INFO(" pwm_out stop");
|
||||
PX4_INFO(" pwm_out status");
|
||||
PX4_INFO(" linux_pwm_out stop");
|
||||
PX4_INFO(" linux_pwm_out status");
|
||||
}
|
||||
|
||||
} // namespace linux_pwm_out
|
||||
} // namespace pwm_out
|
||||
|
||||
/* driver 'main' command */
|
||||
extern "C" __EXPORT int linux_pwm_out_main(int argc, char *argv[]);
|
||||
@ -527,18 +497,11 @@ int linux_pwm_out_main(int argc, char *argv[])
|
||||
return 1;
|
||||
}
|
||||
|
||||
while ((ch = px4_getopt(argc, argv, "d:m:p:n:", &myoptind, &myoptarg)) != EOF) {
|
||||
while ((ch = px4_getopt(argc, argv, "m:n:", &myoptind, &myoptarg)) != EOF) {
|
||||
switch (ch) {
|
||||
case 'd':
|
||||
strncpy(linux_pwm_out::_device, myoptarg, sizeof(linux_pwm_out::_device) - 1);
|
||||
break;
|
||||
|
||||
case 'm':
|
||||
strncpy(linux_pwm_out::_mixer_filename, myoptarg, sizeof(linux_pwm_out::_mixer_filename) - 1);
|
||||
break;
|
||||
|
||||
case 'p':
|
||||
strncpy(linux_pwm_out::_protocol, myoptarg, sizeof(linux_pwm_out::_protocol) - 1);
|
||||
strncpy(pwm_out::_mixer_filename, myoptarg, sizeof(pwm_out::_mixer_filename) - 1);
|
||||
break;
|
||||
|
||||
case 'n': {
|
||||
@ -552,44 +515,44 @@ int linux_pwm_out_main(int argc, char *argv[])
|
||||
max_num = actuator_outputs_s::NUM_ACTUATOR_OUTPUTS;
|
||||
}
|
||||
|
||||
linux_pwm_out::_max_num_outputs = max_num;
|
||||
pwm_out::_max_num_outputs = max_num;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/** gets the parameters for the esc's pwm */
|
||||
param_get(param_find("PWM_MAIN_DISARM"), &linux_pwm_out::_pwm_disarmed);
|
||||
param_get(param_find("PWM_MAIN_MIN"), &linux_pwm_out::_pwm_min);
|
||||
param_get(param_find("PWM_MAIN_MAX"), &linux_pwm_out::_pwm_max);
|
||||
param_get(param_find("PWM_MAIN_DISARM"), &pwm_out::_pwm_disarmed);
|
||||
param_get(param_find("PWM_MAIN_MIN"), &pwm_out::_pwm_min);
|
||||
param_get(param_find("PWM_MAIN_MAX"), &pwm_out::_pwm_max);
|
||||
|
||||
/*
|
||||
* Start/load the driver.
|
||||
*/
|
||||
if (!strcmp(verb, "start")) {
|
||||
if (linux_pwm_out::_is_running) {
|
||||
if (pwm_out::_is_running) {
|
||||
PX4_WARN("pwm_out already running");
|
||||
return 1;
|
||||
}
|
||||
|
||||
linux_pwm_out::start();
|
||||
pwm_out::start();
|
||||
}
|
||||
|
||||
else if (!strcmp(verb, "stop")) {
|
||||
if (!linux_pwm_out::_is_running) {
|
||||
if (!pwm_out::_is_running) {
|
||||
PX4_WARN("pwm_out is not running");
|
||||
return 1;
|
||||
}
|
||||
|
||||
linux_pwm_out::stop();
|
||||
pwm_out::stop();
|
||||
}
|
||||
|
||||
else if (!strcmp(verb, "status")) {
|
||||
PX4_WARN("pwm_out is %s", linux_pwm_out::_is_running ? "running" : "not running");
|
||||
PX4_WARN("pwm_out is %s", pwm_out::_is_running ? "running" : "not running");
|
||||
return 0;
|
||||
|
||||
} else {
|
||||
linux_pwm_out::usage();
|
||||
pwm_out::usage();
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user