AP_HAL_Linux: fix include order

Sort include alphabetically and make them in order:

Main header
system headers
library headers
local headers

While reordering, change a include of endian.h to our sparse-endian.h
which is more reliant to toolchain changes.
This commit is contained in:
Lucas De Marchi 2016-05-17 23:26:57 -03:00
parent 45c6b750f2
commit 71e10c9132
46 changed files with 436 additions and 449 deletions

View File

@ -1,5 +1,3 @@
#include <AP_HAL/AP_HAL.h>
#include "AnalogIn.h"
using namespace Linux;

View File

@ -1,5 +1,3 @@
#include <AP_HAL/AP_HAL.h>
#include "AnalogIn_ADS1115.h"
AnalogSource_ADS1115::AnalogSource_ADS1115(int16_t pin):

View File

@ -1,9 +1,9 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL/AP_HAL.h>
#include "AnalogIn_IIO.h"
extern const AP_HAL::HAL& hal;
#include <AP_HAL/AP_HAL.h>
extern const AP_HAL::HAL &hal;
const char* AnalogSource_IIO::analog_sources[] = {
"in_voltage0_raw",

View File

@ -1,12 +1,12 @@
#include <AP_HAL/AP_HAL.h>
#include "AnalogIn_Navio2.h"
#include <cstdio>
#include <cstdlib>
#include <errno.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "AnalogIn_Navio2.h"
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
#define ADC_BASE_PATH "/sys/kernel/rcio/adc"

View File

@ -13,11 +13,11 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#include "GPIO.h"
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
#include "CameraSensor_Mt9v117.h"
#include "GPIO.h"
/* Cam sensor register definitions */
#define CHIP_ID 0x0

View File

@ -1,13 +1,14 @@
#include <errno.h>
#include <fcntl.h>
#include <stdio.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "ConsoleDevice.h"
#include <stdio.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
ConsoleDevice::ConsoleDevice()
ConsoleDevice::ConsoleDevice()
{
}
@ -54,10 +55,10 @@ void ConsoleDevice::set_blocking(bool blocking)
{
int rd_flags;
int wr_flags;
rd_flags = fcntl(_rd_fd, F_GETFL, 0);
wr_flags = fcntl(_wr_fd, F_GETFL, 0);
if (blocking) {
rd_flags = rd_flags & ~O_NONBLOCK;
wr_flags = wr_flags & ~O_NONBLOCK;

View File

@ -1,4 +1,5 @@
#include <AP_HAL/AP_HAL.h>
#include "GPIO.h"
using namespace Linux;

View File

@ -7,7 +7,7 @@ public:
DigitalSource(uint8_t v);
void mode(uint8_t output);
uint8_t read();
void write(uint8_t value);
void write(uint8_t value);
void toggle();
private:
uint8_t _v;

View File

@ -7,19 +7,18 @@
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2 || \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
#include "GPIO.h"
#include "Util_RPI.h"
#include <errno.h>
#include <fcntl.h>
#include <poll.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <unistd.h>
#include "GPIO.h"
#include "Util_RPI.h"
using namespace Linux;

View File

@ -1,8 +1,8 @@
#pragma once
#include "AP_HAL_Linux.h"
#include <AP_HAL/AP_HAL.h>
#include "AP_HAL_Linux.h"
#include "GPIO.h"
class Linux::DigitalSource_Sysfs : public AP_HAL::DigitalSource {

View File

@ -1,17 +1,16 @@
#include <assert.h>
#include "HAL_Linux_Class.h"
#include "AP_HAL_Linux_Private.h"
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/getopt_cpp.h>
#include <stdio.h>
#include <unistd.h>
#include <stdlib.h>
#include <AP_HAL_Empty/AP_HAL_Empty.h>
#include <AP_HAL_Empty/AP_HAL_Empty_Private.h>
#include "AP_HAL_Linux_Private.h"
#include "HAL_Linux_Class.h"
using namespace Linux;
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \
@ -230,11 +229,11 @@ void _usage(void)
printf("Usage: -A uartAPath -B uartBPath -C uartCPath -D uartDPath -E uartEPath -F uartFPath\n");
printf("Options:\n");
printf("\t-serial: -A /dev/ttyO4\n");
printf("\t -B /dev/ttyS1\n");
printf("\t -B /dev/ttyS1\n");
printf("\t-tcp: -C tcp:192.168.2.15:1243:wait\n");
printf("\t -A tcp:11.0.0.2:5678\n");
printf("\t -A udp:11.0.0.2:5678\n");
printf("\t-custom log path:\n");
printf("\t -A tcp:11.0.0.2:5678\n");
printf("\t -A udp:11.0.0.2:5678\n");
printf("\t-custom log path:\n");
printf("\t --log-directory /var/APM/logs\n");
printf("\t -l /var/APM/logs\n");
printf("\t-custom terrain path:\n");
@ -298,7 +297,7 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const
rcinDriver.set_device_path(gopt.optarg);
break;
#endif // CONFIG_HAL_BOARD_SUBTYPE
case 'l':
case 'l':
utilInstance.set_custom_log_directory(gopt.optarg);
break;
case 't':
@ -328,9 +327,9 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const
spi->init();
rcout->init();
rcin->init();
uartA->begin(115200);
uartE->begin(115200);
uartF->begin(115200);
uartA->begin(115200);
uartE->begin(115200);
uartF->begin(115200);
analogin->init();
utilInstance.init(argc+gopt.optind-1, &argv[gopt.optind-1]);

View File

@ -17,15 +17,16 @@
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
#include <stdio.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <linux/limits.h>
#include <string.h>
#include <cmath>
#include <fcntl.h>
#include <linux/limits.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include "Heat_Pwm.h"
extern const AP_HAL::HAL& hal;

View File

@ -1,24 +1,24 @@
#include <dirent.h>
#include <errno.h>
#include <fcntl.h>
#include <limits.h>
#include <linux/i2c-dev.h>
#ifndef I2C_SMBUS_BLOCK_MAX
#include <linux/i2c.h>
#endif
#include <stdio.h>
#include <stdlib.h>
#include <sys/ioctl.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "I2CDriver.h"
#include "Util.h"
#include <errno.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <dirent.h>
#include <fcntl.h>
#include <unistd.h>
#include <stdio.h>
#include <stdlib.h>
#include <limits.h>
#include <sys/ioctl.h>
#include <linux/i2c-dev.h>
#ifndef I2C_SMBUS_BLOCK_MAX
#include <linux/i2c.h>
#endif
extern const AP_HAL::HAL& hal;
extern const AP_HAL::HAL &hal;
using namespace Linux;
@ -68,14 +68,14 @@ bool I2CDriver::set_address(uint8_t addr)
return true;
}
void I2CDriver::setTimeout(uint16_t ms)
void I2CDriver::setTimeout(uint16_t ms)
{
// unimplemented
}
void I2CDriver::setHighSpeed(bool active)
void I2CDriver::setHighSpeed(bool active)
{
// unimplemented
// unimplemented
}
uint8_t I2CDriver::write(uint8_t addr, uint8_t len, uint8_t* data)
@ -105,7 +105,7 @@ uint8_t I2CDriver::writeRegisters(uint8_t addr, uint8_t reg,
this is a copy of i2c_smbus_access() from i2c-dev.h. We need it for
platforms with older headers
*/
static inline __s32 _i2c_smbus_access(int file, char read_write, __u8 command,
static inline __s32 _i2c_smbus_access(int file, char read_write, __u8 command,
int size, union i2c_smbus_data *data)
{
struct i2c_smbus_ioctl_data args;
@ -178,7 +178,7 @@ uint8_t I2CDriver::readRegisters(uint8_t addr, uint8_t reg,
uint8_t I2CDriver::readRegistersMultiple(uint8_t addr, uint8_t reg,
uint8_t len,
uint8_t len,
uint8_t count, uint8_t* data)
{
#ifdef I2C_RDRW_IOCTL_MAX_MSGS
@ -258,16 +258,13 @@ bool I2CDriver::do_transfer(uint8_t addr, const uint8_t *send,
if (send_len == 0 && recv_len) {
msg_rdwr.msgs = &i2cmsg[1];
msg_rdwr.nmsgs = 1;
}
else if (send_len && recv_len == 0) {
} else if (send_len && recv_len == 0) {
msg_rdwr.msgs = &i2cmsg[0];
msg_rdwr.nmsgs = 1;
}
else if (send_len && recv_len) {
}else if (send_len && recv_len) {
msg_rdwr.msgs = &i2cmsg[0];
msg_rdwr.nmsgs = 2;
}
else {
} else {
return false;
}
return ioctl(_fake_dev->get_fd(), I2C_RDWR, &msg_rdwr) == (int)msg_rdwr.nmsgs;

View File

@ -19,14 +19,14 @@
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
#include "OpticalFlow_Onboard.h"
#include <vector>
#include <stdio.h>
#include <pthread.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <linux/v4l2-mediabus.h>
#include <pthread.h>
#include <stdio.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <vector>
#include "CameraSensor_Mt9v117.h"
#include "GPIO.h"

View File

@ -15,8 +15,6 @@
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#include "PWM_Sysfs.h"
#include <errno.h>
@ -26,6 +24,7 @@
#include <stdlib.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();

View File

@ -15,14 +15,12 @@
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#if !defined(PERF_LTTNG)
#include <limits.h>
#include <time.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include "AP_HAL_Linux.h"

View File

@ -12,21 +12,22 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#pragma GCC diagnostic ignored "-Wcast-align"
#if defined(PERF_LTTNG)
#define TRACEPOINT_CREATE_PROBES
#define TRACEPOINT_DEFINE
#include "Perf_Lttng_TracePoints.h"
#include <string.h>
#include "Perf_Lttng.h"
#include <AP_HAL/AP_HAL.h>
#include "AP_HAL_Linux.h"
#include "Perf_Lttng_TracePoints.h"
#include "Perf_Lttng.h"
#include "Util.h"
#pragma GCC diagnostic ignored "-Wcast-align"
using namespace Linux;
Perf_Lttng::Perf_Lttng(AP_HAL::Util::perf_counter_type type, const char *name)

View File

@ -1,20 +1,20 @@
#include <stdio.h>
#include <sys/time.h>
#include <errno.h>
#include <fcntl.h>
#include <poll.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <stdint.h>
#include <sys/time.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/dsm.h>
#include "RCInput.h"
#include "sbus.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/dsm.h>
extern const AP_HAL::HAL& hal;
@ -30,17 +30,17 @@ void RCInput::init()
{
}
bool RCInput::new_input()
bool RCInput::new_input()
{
return new_rc_input;
}
uint8_t RCInput::num_channels()
uint8_t RCInput::num_channels()
{
return _num_channels;
}
uint16_t RCInput::read(uint8_t ch)
uint16_t RCInput::read(uint8_t ch)
{
new_rc_input = false;
if (_override[ch]) {
@ -52,7 +52,7 @@ uint16_t RCInput::read(uint8_t ch)
return _pwm_values[ch];
}
uint8_t RCInput::read(uint16_t* periods, uint8_t len)
uint8_t RCInput::read(uint16_t* periods, uint8_t len)
{
uint8_t i;
for (i=0; i<len; i++) {
@ -61,7 +61,7 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len)
return len;
}
bool RCInput::set_overrides(int16_t *overrides, uint8_t len)
bool RCInput::set_overrides(int16_t *overrides, uint8_t len)
{
bool res = false;
if(len > LINUX_RC_INPUT_NUM_CHANNELS){
@ -73,7 +73,7 @@ bool RCInput::set_overrides(int16_t *overrides, uint8_t len)
return res;
}
bool RCInput::set_override(uint8_t channel, int16_t override)
bool RCInput::set_override(uint8_t channel, int16_t override)
{
if (override < 0) return false; /* -1: no change. */
if (channel < LINUX_RC_INPUT_NUM_CHANNELS) {
@ -160,7 +160,7 @@ void RCInput::_process_sbus_pulse(uint16_t width_s0, uint16_t width_s1)
// invalid data
goto reset;
}
if (bits_s0+bit_ofs > 10) {
// invalid data as last two bits must be stop bits
goto reset;
@ -207,9 +207,9 @@ void RCInput::_process_sbus_pulse(uint16_t width_s0, uint16_t width_s1)
uint16_t values[LINUX_RC_INPUT_NUM_CHANNELS];
uint16_t num_values=0;
bool sbus_failsafe=false, sbus_frame_drop=false;
if (sbus_decode(bytes, values, &num_values,
&sbus_failsafe, &sbus_frame_drop,
LINUX_RC_INPUT_NUM_CHANNELS) &&
if (sbus_decode(bytes, values, &num_values,
&sbus_failsafe, &sbus_frame_drop,
LINUX_RC_INPUT_NUM_CHANNELS) &&
num_values >= 5) {
for (i=0; i<num_values; i++) {
_pwm_values[i] = values[i];
@ -224,7 +224,7 @@ void RCInput::_process_sbus_pulse(uint16_t width_s0, uint16_t width_s1)
}
return;
reset:
memset(&sbus_state, 0, sizeof(sbus_state));
memset(&sbus_state, 0, sizeof(sbus_state));
}
void RCInput::_process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
@ -242,7 +242,7 @@ void RCInput::_process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
byte_ofs = dsm_state.bit_ofs/10;
bit_ofs = dsm_state.bit_ofs%10;
if(byte_ofs > 15) {
// invalid data
goto reset;
@ -265,7 +265,7 @@ void RCInput::_process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
for (i=0; i<16; i++) {
// get raw data
uint16_t v = dsm_state.bytes[i];
// check start bit
if ((v & 1) != 0) {
goto reset;
@ -278,12 +278,12 @@ void RCInput::_process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
}
uint16_t values[8];
uint16_t num_values=0;
if (dsm_decode(AP_HAL::micros64(), bytes, values, &num_values, 8) &&
if (dsm_decode(AP_HAL::micros64(), bytes, values, &num_values, 8) &&
num_values >= 5) {
for (i=0; i<num_values; i++) {
_pwm_values[i] = values[i];
}
_num_channels = num_values;
_num_channels = num_values;
new_rc_input = true;
}
}
@ -302,7 +302,7 @@ void RCInput::_process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
dsm_state.bit_ofs += bits_s1;
return;
reset:
memset(&dsm_state, 0, sizeof(dsm_state));
memset(&dsm_state, 0, sizeof(dsm_state));
}
/*
@ -356,13 +356,13 @@ void RCInput::add_dsm_input(const uint8_t *bytes, size_t nbytes)
}
const uint8_t dsm_frame_size = sizeof(dsm.frame);
uint32_t now = AP_HAL::millis();
uint32_t now = AP_HAL::millis();
if (now - dsm.last_input_ms > 5) {
// resync based on time
dsm.partial_frame_count = 0;
}
dsm.last_input_ms = now;
while (nbytes > 0) {
size_t n = nbytes;
if (dsm.partial_frame_count + n > dsm_frame_size) {

View File

@ -14,18 +14,17 @@
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
#include <stdio.h>
#include <sys/time.h>
#include <errno.h>
#include <fcntl.h>
#include <poll.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <stdint.h>
#include <sys/time.h>
#include <unistd.h>
#include "RCInput.h"
#include "RCInput_AioPRU.h"

View File

@ -4,18 +4,17 @@
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD || \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
#include <stdio.h>
#include <sys/time.h>
#include <errno.h>
#include <fcntl.h>
#include <poll.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <stdint.h>
#include <sys/time.h>
#include <unistd.h>
#include "GPIO.h"
#include "RCInput.h"

View File

@ -4,28 +4,26 @@
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
#include <assert.h>
#include <errno.h>
#include <fcntl.h>
#include <pthread.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/ioctl.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <sys/time.h>
#include <sys/types.h>
#include <time.h>
#include <unistd.h>
#include "GPIO.h"
#include "RCInput_RPI.h"
#include "Util_RPI.h"
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
#include <fcntl.h>
#include <stdint.h>
#include <sys/ioctl.h>
#include <pthread.h>
#include <string.h>
#include <errno.h>
#include <stdint.h>
#include <time.h>
#include <sys/time.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <sys/mman.h>
#include <assert.h>
//Parametres
#define RCIN_RPI_BUFFER_LENGTH 8
#define RCIN_RPI_SAMPLE_FREQ 500

View File

@ -2,14 +2,14 @@
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
#include <stdio.h>
#include <errno.h>
#include <stdlib.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <assert.h>
#include <errno.h>
#include <fcntl.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include "RCInput_Raspilot.h"

View File

@ -1,5 +1,3 @@
#include <AP_HAL/AP_HAL.h>
#include "RCInput_UART.h"
#include <errno.h>
@ -11,6 +9,8 @@
#include <termios.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#define MAGIC 0x55AA
using namespace Linux;

View File

@ -1,7 +1,8 @@
#include <stdio.h>
#include <AP_HAL/AP_HAL.h>
#include "RCInput_UDP.h"
#include <stdio.h>
extern const AP_HAL::HAL& hal;

View File

@ -1,17 +1,16 @@
#include <AP_HAL/AP_HAL.h>
#include <stdio.h>
#include <sys/time.h>
#include <errno.h>
#include <fcntl.h>
#include <poll.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <stdint.h>
#include <sys/time.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "GPIO.h"
#include "RCInput.h"
@ -26,7 +25,7 @@ void RCInput_ZYNQ::init()
if (mem_fd == -1) {
AP_HAL::panic("Unable to open /dev/mem");
}
pulse_input = (volatile uint32_t*) mmap(0, 0x1000, PROT_READ|PROT_WRITE,
pulse_input = (volatile uint32_t*) mmap(0, 0x1000, PROT_READ|PROT_WRITE,
MAP_SHARED, mem_fd, RCIN_ZYNQ_PULSE_INPUT_BASE);
close(mem_fd);

View File

@ -8,19 +8,18 @@
// GNU General Public License for more details.
// You should have received a copy of the GNU General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.
#include "RCOutput_AioPRU.h"
#include <fcntl.h>
#include <signal.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/mman.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "RCOutput_AioPRU.h"
#include <fcntl.h>
#include <unistd.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <sys/mman.h>
#include <signal.h>
#include "../../Tools/Linux_HAL_Essentials/pru/aiopru/RcAioPRU_bin.h"
using namespace Linux;

View File

@ -1,15 +1,17 @@
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
#include <endian.h>
#include <stdio.h>
#include <sys/time.h>
#include <poll.h>
#include <unistd.h>
#include <stdlib.h>
#include <errno.h>
#include <sys/mman.h>
#include <poll.h>
#include <pthread.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/mman.h>
#include <sys/time.h>
#include <unistd.h>
#include <AP_HAL/utility/sparse-endian.h>
#include "RCOutput_Bebop.h"
#include "Util.h"

View File

@ -1,17 +1,18 @@
#include "RCOutput_PCA9685.h"
#include <cmath>
#include <dirent.h>
#include <fcntl.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "GPIO.h"
#include "RCOutput_PCA9685.h"
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <dirent.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <cmath>
#include "GPIO.h"
#define PCA9685_RA_MODE1 0x00
#define PCA9685_RA_MODE2 0x01
@ -243,6 +244,7 @@ uint16_t RCOutput_PCA9685::read(uint8_t ch)
void RCOutput_PCA9685::read(uint16_t* period_us, uint8_t len)
{
for (int i = 0; i < len; i++)
for (int i = 0; i < len; i++) {
period_us[i] = read(0 + i);
}
}

View File

@ -1,22 +1,22 @@
#include "RCOutput_PRU.h"
#include <dirent.h>
#include <fcntl.h>
#include <linux/spi/spidev.h>
#include <signal.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/ioctl.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "RCOutput_PRU.h"
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <dirent.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <sys/ioctl.h>
#include <linux/spi/spidev.h>
#include <sys/mman.h>
#include <signal.h>
using namespace Linux;
#define PWM_CHAN_COUNT 12
static const uint8_t chan_pru_map[]= {10,8,11,9,7,6,5,4,3,2,1,0}; //chan_pru_map[CHANNEL_NUM] = PRU_REG_R30/31_NUM;
@ -30,7 +30,7 @@ void RCOutput_PRU::init()
uint32_t mem_fd;
signal(SIGBUS,catch_sigbus);
mem_fd = open("/dev/mem", O_RDWR|O_SYNC);
sharedMem_cmd = (struct pwm_cmd *) mmap(0, 0x1000, PROT_READ|PROT_WRITE,
sharedMem_cmd = (struct pwm_cmd *) mmap(0, 0x1000, PROT_READ|PROT_WRITE,
MAP_SHARED, mem_fd, RCOUT_PRUSS_SHAREDRAM_BASE);
close(mem_fd);

View File

@ -1,20 +1,21 @@
#include <AP_HAL/AP_HAL.h>
#include "GPIO.h"
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
#include "RCOutput_Raspilot.h"
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <dirent.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <cmath>
#include <dirent.h>
#include <fcntl.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include "px4io_protocol.h"
#include "GPIO.h"
using namespace Linux;
@ -26,22 +27,22 @@ void RCOutput_Raspilot::init()
{
_spi = hal.spi->device(AP_HAL::SPIDevice_RASPIO);
_spi_sem = _spi->get_semaphore();
if (_spi_sem == NULL) {
AP_HAL::panic("PANIC: RCOutput_Raspilot did not get "
"valid SPI semaphore!");
return; // never reached
}
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&RCOutput_Raspilot::_update, void));
}
void RCOutput_Raspilot::set_freq(uint32_t chmask, uint16_t freq_hz)
{
{
if (!_spi_sem->take(10)) {
return;
}
struct IOPacket _dma_packet_tx, _dma_packet_rx;
uint16_t count = 1;
_dma_packet_tx.count_code = count | PKT_CODE_WRITE;
@ -51,9 +52,9 @@ void RCOutput_Raspilot::set_freq(uint32_t chmask, uint16_t freq_hz)
_dma_packet_tx.crc = 0;
_dma_packet_tx.crc = crc_packet(&_dma_packet_tx);
_spi->transaction((uint8_t *)&_dma_packet_tx, (uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_tx));
_frequency = freq_hz;
_spi_sem->give();
}
@ -64,7 +65,7 @@ uint16_t RCOutput_Raspilot::get_freq(uint8_t ch)
void RCOutput_Raspilot::enable_ch(uint8_t ch)
{
}
void RCOutput_Raspilot::disable_ch(uint8_t ch)
@ -73,11 +74,11 @@ void RCOutput_Raspilot::disable_ch(uint8_t ch)
}
void RCOutput_Raspilot::write(uint8_t ch, uint16_t period_us)
{
{
if(ch >= PWM_CHAN_COUNT){
return;
}
_period_us[ch] = period_us;
}
@ -86,26 +87,26 @@ uint16_t RCOutput_Raspilot::read(uint8_t ch)
if(ch >= PWM_CHAN_COUNT){
return 0;
}
return _period_us[ch];
}
void RCOutput_Raspilot::read(uint16_t* period_us, uint8_t len)
{
for (int i = 0; i < len; i++)
for (int i = 0; i < len; i++)
period_us[i] = read(0 + i);
}
void RCOutput_Raspilot::_update(void)
{
int i;
if (AP_HAL::micros() - _last_update_timestamp < 10000) {
return;
}
_last_update_timestamp = AP_HAL::micros();
if (!_spi_sem->take_nonblocking()) {
return;
}
@ -119,7 +120,7 @@ void RCOutput_Raspilot::_update(void)
_dma_packet_tx.crc = 0;
_dma_packet_tx.crc = crc_packet(&_dma_packet_tx);
_spi->transaction((uint8_t *)&_dma_packet_tx, (uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_tx));
count = 1;
_dma_packet_tx.count_code = count | PKT_CODE_WRITE;
_dma_packet_tx.page = 50;
@ -128,7 +129,7 @@ void RCOutput_Raspilot::_update(void)
_dma_packet_tx.crc = 0;
_dma_packet_tx.crc = crc_packet(&_dma_packet_tx);
_spi->transaction((uint8_t *)&_dma_packet_tx, (uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_tx));
count = PWM_CHAN_COUNT;
_dma_packet_tx.count_code = count | PKT_CODE_WRITE;
_dma_packet_tx.page = 54;
@ -139,7 +140,7 @@ void RCOutput_Raspilot::_update(void)
_dma_packet_tx.crc = 0;
_dma_packet_tx.crc = crc_packet(&_dma_packet_tx);
_spi->transaction((uint8_t *)&_dma_packet_tx, (uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_tx));
_spi_sem->give();
}

View File

@ -15,12 +15,10 @@
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#include "RCOutput_Sysfs.h"
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
namespace Linux {

View File

@ -2,18 +2,20 @@
#include <AP_HAL/AP_HAL.h>
#include "RCOutput_ZYNQ.h"
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <dirent.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <sys/ioctl.h>
#include <fcntl.h>
#include <linux/spi/spidev.h>
#include <sys/mman.h>
#include <signal.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/ioctl.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
using namespace Linux;
#define PWM_CHAN_COUNT 8 // FIXME

View File

@ -1,10 +1,9 @@
#include <AP_HAL/AP_HAL.h>
#include "RPIOUARTDriver.h"
#include <stdlib.h>
#include <cstdio>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/RingBuffer.h>
#include "px4io_protocol.h"
@ -21,8 +20,8 @@ extern const AP_HAL::HAL& hal;
#define debug(fmt, args ...) do {hal.console->printf("[RPIOUARTDriver]: %s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
#define error(fmt, args ...) do {fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
#else
#define debug(fmt, args ...)
#define error(fmt, args ...)
#define debug(fmt, args ...)
#define error(fmt, args ...)
#endif
using namespace Linux;
@ -58,7 +57,7 @@ bool RPIOUARTDriver::isExternal()
void RPIOUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
{
//hal.console->printf("[RPIOUARTDriver]: begin \n");
if (device_path != NULL) {
UARTDriver::begin(b,rxS,txS);
if ( is_initialized()) {
@ -73,7 +72,7 @@ void RPIOUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
if (txS < 1024) {
txS = 2048;
}
_initialised = false;
while (_in_timer) hal.scheduler->delay(1);
@ -110,13 +109,13 @@ void RPIOUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
}
_spi_sem = _spi->get_semaphore();
if (_spi_sem == NULL) {
AP_HAL::panic("PANIC: RASPIOUARTDriver did not get "
"valid SPI semaphore!");
return; // never reached
}
/* set baudrate */
_baudrate = b;
_need_set_baud = true;
@ -134,7 +133,7 @@ int RPIOUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
{
if (_external) {
return UARTDriver::_write_fd(buf, n);
}
}
return -1;
}
@ -144,7 +143,7 @@ int RPIOUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
if (_external) {
return UARTDriver::_read_fd(buf, n);
}
return -1;
}
@ -154,18 +153,18 @@ void RPIOUARTDriver::_timer_tick(void)
UARTDriver::_timer_tick();
return;
}
/* set the baudrate of raspilotio */
if (_need_set_baud) {
if (_baudrate != 0) {
if (!_spi_sem->take_nonblocking()) {
return;
}
struct IOPacket _dma_packet_tx, _dma_packet_rx;
_dma_packet_tx.count_code = 2 | PKT_CODE_WRITE;
_dma_packet_tx.page = PX4IO_PAGE_UART_BUFFER;
_dma_packet_tx.offset = 0;
@ -173,47 +172,47 @@ void RPIOUARTDriver::_timer_tick(void)
_dma_packet_tx.regs[1] = _baudrate >> 16;
_dma_packet_tx.crc = 0;
_dma_packet_tx.crc = crc_packet(&_dma_packet_tx);
_spi->transaction((uint8_t *)&_dma_packet_tx, (uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_tx));
hal.scheduler->delay(1);
_spi_sem->give();
}
_need_set_baud = false;
}
/* finish set */
if (!_initialised) return;
/* lower the update rate */
if (AP_HAL::micros() - _last_update_timestamp < RPIOUART_POLL_TIME_INTERVAL) {
return;
}
_in_timer = true;
if (!_spi_sem->take_nonblocking()) {
return;
}
struct IOPacket _dma_packet_tx, _dma_packet_rx;
/* get write_buf bytes */
uint16_t _tail;
uint16_t n = BUF_AVAILABLE(_writebuf);
if (n > PKT_MAX_REGS * 2) {
n = PKT_MAX_REGS * 2;
}
uint16_t _max_size = _baudrate / 10 / (1000000 / RPIOUART_POLL_TIME_INTERVAL);
if (n > _max_size) {
n = _max_size;
}
if (n > 0) {
uint16_t n1 = _writebuf_size - _writebuf_head;
if (n1 >= n) {
@ -224,22 +223,22 @@ void RPIOUARTDriver::_timer_tick(void)
memcpy( &((uint8_t *)_dma_packet_tx.regs)[0], &_writebuf[_writebuf_head], n1 );
memcpy( &((uint8_t *)_dma_packet_tx.regs)[n1], &_writebuf[0], n-n1 );
}
BUF_ADVANCEHEAD(_writebuf, n);
}
_dma_packet_tx.count_code = PKT_MAX_REGS | PKT_CODE_SPIUART;
_dma_packet_tx.page = PX4IO_PAGE_UART_BUFFER;
_dma_packet_tx.offset = n;
/* end get write_buf bytes */
_dma_packet_tx.crc = 0;
_dma_packet_tx.crc = crc_packet(&_dma_packet_tx);
/* set raspilotio to read uart data */
_spi->transaction((uint8_t *)&_dma_packet_tx, (uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_tx));
hal.scheduler->delay_microseconds(100);
/* get uart data from raspilotio */
_dma_packet_tx.count_code = 0 | PKT_CODE_READ;
_dma_packet_tx.page = 0;
@ -248,26 +247,26 @@ void RPIOUARTDriver::_timer_tick(void)
_dma_packet_tx.crc = 0;
_dma_packet_tx.crc = crc_packet(&_dma_packet_tx);
_spi->transaction((uint8_t *)&_dma_packet_tx, (uint8_t *)&_dma_packet_rx, sizeof(_dma_packet_tx));
hal.scheduler->delay_microseconds(100);
/* release sem */
_spi_sem->give();
/* add bytes to read buf */
uint16_t _head;
n = BUF_SPACE(_readbuf);
if (_dma_packet_rx.page == PX4IO_PAGE_UART_BUFFER) {
if (n > _dma_packet_rx.offset) {
n = _dma_packet_rx.offset;
}
if (n > PKT_MAX_REGS * 2) {
n = PKT_MAX_REGS * 2;
}
if (n > 0) {
uint16_t n1 = _readbuf_size - _readbuf_tail;
if (n1 >= n) {
@ -277,13 +276,13 @@ void RPIOUARTDriver::_timer_tick(void)
memcpy( &_readbuf[_readbuf_tail], &((uint8_t *)_dma_packet_rx.regs)[0], n1 );
memcpy( &_readbuf[0], &((uint8_t *)_dma_packet_rx.regs)[n1], n-n1 );
}
BUF_ADVANCETAIL(_readbuf, n);
}
}
_in_timer = false;
_last_update_timestamp = AP_HAL::micros();
}

View File

@ -1,16 +1,18 @@
#include "SPIDriver.h"
#include <errno.h>
#include <fcntl.h>
#include <linux/spi/spidev.h>
#include <stdint.h>
#include <stdio.h>
#include <sys/ioctl.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include "SPIDriver.h"
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <stdio.h>
#include <stdint.h>
#include <errno.h>
#include <sys/ioctl.h>
#include <linux/spi/spidev.h>
#include "GPIO.h"
using namespace Linux;

View File

@ -1,8 +1,9 @@
#include <AP_HAL/AP_HAL.h>
#include "SPIUARTDriver.h"
#include <stdlib.h>
#include <cstdio>
#include "SPIUARTDriver.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/RingBuffer.h>
extern const AP_HAL::HAL& hal;
@ -15,8 +16,8 @@ extern const AP_HAL::HAL& hal;
#define debug(fmt, args ...) do {hal.console->printf("[SPIUARTDriver]: %s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
#define error(fmt, args ...) do {fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
#else
#define debug(fmt, args ...)
#define error(fmt, args ...)
#define debug(fmt, args ...)
#define error(fmt, args ...)
#endif
using namespace Linux;
@ -123,7 +124,7 @@ void SPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
debug("%s: wrong baudrate (%u) for SPI-driven device. setting default speed", __func__, b);
break;
}
_initialised = true;
}
@ -131,7 +132,7 @@ int SPIUARTDriver::_write_fd(const uint8_t *buf, uint16_t size)
{
if (_external) {
return UARTDriver::_write_fd(buf,size);
}
}
if (!sem_take_nonblocking()) {
return 0;
@ -146,9 +147,9 @@ int SPIUARTDriver::_write_fd(const uint8_t *buf, uint16_t size)
uint16_t ret = size;
/* Since all SPI-transactions are transfers we need update
* the _readbuf. I do believe there is a way to encapsulate
* the _readbuf. I do believe there is a way to encapsulate
* this operation since it's the same as in the
* UARTDriver::write().
* UARTDriver::write().
*/
uint8_t *buffer = _buffer;
@ -188,7 +189,7 @@ int SPIUARTDriver::_write_fd(const uint8_t *buf, uint16_t size)
return ret;
}
static const uint8_t ff_stub[300] = {0xff};
@ -203,10 +204,10 @@ int SPIUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
}
/* Make SPI transactions shorter. It can save SPI bus from keeping too
* long. It's essential for NavIO as MPU9250 is on the same bus and
* long. It's essential for NavIO as MPU9250 is on the same bus and
* doesn't like to be waiting. Making transactions more frequent but shorter
* is a win.
*/
*/
if (n > 100) {
n = 100;

View File

@ -6,12 +6,12 @@ extern const AP_HAL::HAL& hal;
using namespace Linux;
bool Semaphore::give()
bool Semaphore::give()
{
return pthread_mutex_unlock(&_lock) == 0;
}
bool Semaphore::take(uint32_t timeout_ms)
bool Semaphore::take(uint32_t timeout_ms)
{
if (timeout_ms == 0) {
return pthread_mutex_lock(&_lock) == 0;
@ -29,7 +29,7 @@ bool Semaphore::take(uint32_t timeout_ms)
return false;
}
bool Semaphore::take_nonblocking()
bool Semaphore::take_nonblocking()
{
return pthread_mutex_trylock(&_lock) == 0;
}

View File

@ -1,9 +1,10 @@
#pragma once
#include <pthread.h>
#include <AP_HAL/AP_HAL_Boards.h>
#include "AP_HAL_Linux.h"
#include <pthread.h>
class Linux::Semaphore : public AP_HAL::Semaphore {
public:

View File

@ -1,14 +1,15 @@
#include <AP_HAL/AP_HAL.h>
#include "Storage.h"
#include <assert.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <errno.h>
#include <fcntl.h>
#include <stdio.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include "Storage.h"
using namespace Linux;
@ -108,7 +109,7 @@ void Storage::_mark_dirty(uint16_t loc, uint16_t length)
}
}
void Storage::read_block(void *dst, uint16_t loc, size_t n)
void Storage::read_block(void *dst, uint16_t loc, size_t n)
{
if (loc >= sizeof(_buffer)-(n-1)) {
return;
@ -117,7 +118,7 @@ void Storage::read_block(void *dst, uint16_t loc, size_t n)
memcpy(dst, &_buffer[loc], n);
}
void Storage::write_block(uint16_t loc, const void *src, size_t n)
void Storage::write_block(uint16_t loc, const void *src, size_t n)
{
if (loc >= sizeof(_buffer)-(n-1)) {
return;
@ -138,7 +139,7 @@ void Storage::_timer_tick(void)
if (_fd == -1) {
_fd = open(STORAGE_FILE, O_WRONLY);
if (_fd == -1) {
return;
return;
}
}
@ -156,11 +157,11 @@ void Storage::_timer_tick(void)
}
uint32_t write_mask = (1U<<i);
// see how many lines to write
for (n=1; (i+n) < LINUX_STORAGE_NUM_LINES &&
for (n=1; (i+n) < LINUX_STORAGE_NUM_LINES &&
n < (LINUX_STORAGE_MAX_WRITE>>LINUX_STORAGE_LINE_SHIFT); n++) {
if (!(_dirty_mask & (1<<(n+i)))) {
break;
}
}
// mark that line clean
write_mask |= (1<<(n+i));
}

View File

@ -1,13 +1,14 @@
#include <AP_HAL/AP_HAL.h>
#include <assert.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <errno.h>
#include <fcntl.h>
#include <inttypes.h>
#include <unistd.h>
#include <errno.h>
#include <stdio.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "Storage.h"
using namespace Linux;
@ -31,7 +32,7 @@ void Storage_FRAM::_storage_create(void)
int fd = open();
hal.console->println("Storage: FRAM is getting reset to default values");
if (fd == -1) {
AP_HAL::panic("Failed to load FRAM");
}
@ -62,7 +63,7 @@ void Storage_FRAM::_storage_open(void)
AP_HAL::panic("Failed to access FRAM");
}
}
if (read(fd, _buffer, sizeof(_buffer)) != sizeof(_buffer)) {
_storage_create();
fd = open();
@ -103,11 +104,11 @@ void Storage_FRAM::_timer_tick(void)
}
uint32_t write_mask = (1U<<i);
// see how many lines to write
for (n=1; (i+n) < LINUX_STORAGE_NUM_LINES &&
for (n=1; (i+n) < LINUX_STORAGE_NUM_LINES &&
n < (LINUX_STORAGE_MAX_WRITE>>LINUX_STORAGE_LINE_SHIFT); n++) {
if (!(_dirty_mask & (1<<(n+i)))) {
break;
}
}
// mark that line clean
write_mask |= (1<<(n+i));
}
@ -152,7 +153,7 @@ int8_t Storage_FRAM::open()
AP_HAL::panic("FRAM: Failed to receive Manufacturer ID 5 times");
}
}
while(j<4){
if(_register_read(j+4100,OPCODE_READ) == -1){
continue;
@ -184,12 +185,12 @@ int32_t Storage_FRAM::read(uint16_t fd, uint8_t *Buff, uint16_t NumBytes){
return -1;
}
}
fptr+=NumBytes;
return NumBytes;
fptr+=NumBytes;
return NumBytes;
}
uint32_t Storage_FRAM::lseek(uint16_t fd,uint32_t offset,uint16_t whence){
fptr = offset;
return offset;
return offset;
}
//FRAM I/O functions
@ -202,11 +203,11 @@ int8_t Storage_FRAM::_register_write( uint8_t* src, uint16_t addr, uint16_t len
tx = new uint8_t[len+3];
rx = new uint8_t[len+3];
_write_enable(true);
tx[0] = OPCODE_WRITE;
tx[1] = addr>>8;
tx[2] = addr;
for(i=0;i<len;i++){
tx[i+3] = src[i];
}
@ -233,14 +234,14 @@ int8_t Storage_FRAM::_write_enable(bool enable)
tx[1] = 0;
return transaction(tx, rx, 2);
}
}
int8_t Storage_FRAM::_register_read( uint16_t addr, uint8_t opcode )
{
uint8_t tx[4] = {opcode, (uint8_t)((addr >> 8U)), (uint8_t)(addr & 0xFF), 0};
uint8_t rx[4];
if(transaction(tx, rx, 4) == -1){
return -1;
}

View File

@ -1,12 +1,12 @@
#include <AP_HAL/AP_HAL.h>
#include <stdio.h>
#include <unistd.h>
#include <errno.h>
#include <stdlib.h>
#include "TCPServerDevice.h"
#include <errno.h>
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
extern const AP_HAL::HAL& hal;
TCPServerDevice::TCPServerDevice(const char *ip, uint16_t port, bool wait):

View File

@ -1,23 +1,23 @@
#include <AP_HAL/AP_HAL.h>
#include "ToneAlarm.h"
#include <stdio.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <stdlib.h>
#include <iostream>
#include <stdio.h>
#include <stdlib.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
using namespace Linux;
extern const AP_HAL::HAL& hal;
static uint16_t notes[] = { 0,
NOTE_C4, NOTE_CS4, NOTE_D4, NOTE_DS4, NOTE_E4, NOTE_F4, NOTE_FS4, NOTE_G4, NOTE_GS4, NOTE_A4, NOTE_AS4, NOTE_B4,
NOTE_C5, NOTE_CS5, NOTE_D5, NOTE_DS5, NOTE_E5, NOTE_F5, NOTE_FS5, NOTE_G5, NOTE_GS5, NOTE_A5, NOTE_AS5, NOTE_B5,
NOTE_C6, NOTE_CS6, NOTE_D6, NOTE_DS6, NOTE_E6, NOTE_F6, NOTE_FS6, NOTE_G6, NOTE_GS6, NOTE_A6, NOTE_AS6, NOTE_B6,
NOTE_C7, NOTE_CS7, NOTE_D7, NOTE_DS7, NOTE_E7, NOTE_F7, NOTE_FS7, NOTE_G7, NOTE_GS7, NOTE_A7, NOTE_AS7, NOTE_B7
NOTE_C4, NOTE_CS4, NOTE_D4, NOTE_DS4, NOTE_E4, NOTE_F4, NOTE_FS4, NOTE_G4, NOTE_GS4, NOTE_A4, NOTE_AS4, NOTE_B4,
NOTE_C5, NOTE_CS5, NOTE_D5, NOTE_DS5, NOTE_E5, NOTE_F5, NOTE_FS5, NOTE_G5, NOTE_GS5, NOTE_A5, NOTE_AS5, NOTE_B5,
NOTE_C6, NOTE_CS6, NOTE_D6, NOTE_DS6, NOTE_E6, NOTE_F6, NOTE_FS6, NOTE_G6, NOTE_GS6, NOTE_A6, NOTE_AS6, NOTE_B6,
NOTE_C7, NOTE_CS7, NOTE_D7, NOTE_DS7, NOTE_E7, NOTE_F7, NOTE_FS7, NOTE_G7, NOTE_GS7, NOTE_A7, NOTE_AS7, NOTE_B7
};
//List of RTTTL tones

View File

@ -1,29 +1,21 @@
#include <AP_HAL/AP_HAL.h>
#include <termios.h>
#include <stdio.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include "UARTDevice.h"
#include <termios.h>
#include <stdio.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include <stdio.h>
#include <termios.h>
#include <unistd.h>
UARTDevice::UARTDevice(const char *device_path):
#include <AP_HAL/AP_HAL.h>
UARTDevice::UARTDevice(const char *device_path):
_device_path(device_path)
{
}
UARTDevice::~UARTDevice()
{
}
bool UARTDevice::close()
@ -78,7 +70,7 @@ ssize_t UARTDevice::write(const uint8_t *buf, uint16_t n)
void UARTDevice::set_blocking(bool blocking)
{
int flags = fcntl(_fd, F_GETFL, 0);
if (blocking) {
flags = flags & ~O_NONBLOCK;
} else {

View File

@ -1,32 +1,31 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: -*- nil -*-
#include <AP_HAL/AP_HAL.h>
#include "UARTDriver.h"
#include <stdio.h>
#include <errno.h>
#include <termios.h>
#include <stdlib.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <poll.h>
#include <arpa/inet.h>
#include <assert.h>
#include <sys/ioctl.h>
#include <sys/socket.h>
#include <errno.h>
#include <fcntl.h>
#include <netinet/in.h>
#include <netinet/tcp.h>
#include <poll.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <arpa/inet.h>
#include <sys/ioctl.h>
#include <sys/socket.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <termios.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/RingBuffer.h>
#include "UARTDevice.h"
#include "UDPDevice.h"
#include "ConsoleDevice.h"
#include "TCPServerDevice.h"
#include "UARTDevice.h"
#include "UARTQFlight.h"
#include "UDPDevice.h"
extern const AP_HAL::HAL& hal;
@ -55,12 +54,12 @@ void UARTDriver::set_device_path(const char *path)
/*
open the tty
*/
void UARTDriver::begin(uint32_t b)
void UARTDriver::begin(uint32_t b)
{
begin(b, 0, 0);
}
void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
{
if (device_path == NULL && _console) {
_device = new ConsoleDevice();
@ -94,7 +93,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
break;
}
#endif
case DEVICE_SERIAL:
{
if (!_serial_start_connection()) {
@ -204,7 +203,7 @@ UARTDriver::device_type UARTDriver::_parseDevicePath(const char *arg)
} else if (strncmp(arg, "qflight:", 8) == 0) {
return DEVICE_QFLIGHT;
#endif
} else if (strncmp(arg, "tcp:", 4) != 0 &&
} else if (strncmp(arg, "tcp:", 4) != 0 &&
strncmp(arg, "udp:", 4) != 0) {
return DEVICE_UNKNOWN;
}
@ -307,7 +306,7 @@ void UARTDriver::_tcp_start_connection(void)
/*
shutdown a UART
*/
void UARTDriver::end()
void UARTDriver::end()
{
_initialised = false;
_connected = false;
@ -321,7 +320,7 @@ void UARTDriver::end()
}
void UARTDriver::flush()
void UARTDriver::flush()
{
// we are not doing any buffering, so flush is a no-op
}
@ -330,7 +329,7 @@ void UARTDriver::flush()
/*
return true if the UART is initialised
*/
bool UARTDriver::is_initialized()
bool UARTDriver::is_initialized()
{
return _initialised;
}
@ -339,7 +338,7 @@ bool UARTDriver::is_initialized()
/*
enable or disable blocking writes
*/
void UARTDriver::set_blocking_writes(bool blocking)
void UARTDriver::set_blocking_writes(bool blocking)
{
_nonblocking_writes = !blocking;
}
@ -348,16 +347,16 @@ void UARTDriver::set_blocking_writes(bool blocking)
/*
do we have any bytes pending transmission?
*/
bool UARTDriver::tx_pending()
{
bool UARTDriver::tx_pending()
{
return !BUF_EMPTY(_writebuf);
}
/*
return the number of bytes available to be read
*/
int16_t UARTDriver::available()
{
int16_t UARTDriver::available()
{
if (!_initialised) {
return 0;
}
@ -368,8 +367,8 @@ int16_t UARTDriver::available()
/*
how many bytes are available in the output buffer?
*/
int16_t UARTDriver::txspace()
{
int16_t UARTDriver::txspace()
{
if (!_initialised) {
return 0;
}
@ -377,8 +376,8 @@ int16_t UARTDriver::txspace()
return BUF_SPACE(_writebuf);
}
int16_t UARTDriver::read()
{
int16_t UARTDriver::read()
{
uint8_t c;
if (!_initialised || _readbuf == NULL) {
return -1;
@ -392,8 +391,8 @@ int16_t UARTDriver::read()
}
/* Linux implementations of Print virtual methods */
size_t UARTDriver::write(uint8_t c)
{
size_t UARTDriver::write(uint8_t c)
{
if (!_initialised) {
return 0;
}
@ -458,7 +457,7 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
assert(_writebuf_tail+n <= _writebuf_size);
memcpy(&_writebuf[_writebuf_tail], buffer, n);
BUF_ADVANCETAIL(_writebuf, n);
}
}
return size;
}
@ -479,7 +478,7 @@ int UARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
if (!_connected) {
return 0;
}
ret = _device->write(buf, n);
if (ret > 0) {
@ -501,7 +500,7 @@ int UARTDriver::_read_fd(uint8_t *buf, uint16_t n)
if (ret > 0) {
BUF_ADVANCETAIL(_readbuf, ret);
}
}
return ret;
}
@ -557,7 +556,7 @@ bool UARTDriver::_write_pending_bytes(void)
// are aligned on UDP boundaries)
n = len+8;
}
}
}
}
if (n > 0) {
@ -578,7 +577,7 @@ bool UARTDriver::_write_pending_bytes(void)
} else {
int ret = _write_fd(&_writebuf[_writebuf_head], n1);
if (ret == n1 && n > n1) {
_write_fd(&_writebuf[_writebuf_head], n - n1);
_write_fd(&_writebuf[_writebuf_head], n - n1);
}
}
}
@ -590,7 +589,7 @@ bool UARTDriver::_write_pending_bytes(void)
/*
push any pending bytes to/from the serial port. This is called at
1kHz in the timer thread. Doing it this way reduces the system call
overhead in the main task enormously.
overhead in the main task enormously.
*/
void UARTDriver::_timer_tick(void)
{
@ -619,7 +618,7 @@ void UARTDriver::_timer_tick(void)
int ret = _read_fd(&_readbuf[_readbuf_tail], n1);
if (ret == n1 && n > n1) {
assert(_readbuf_tail+(n-n1) <= _readbuf_size);
_read_fd(&_readbuf[_readbuf_tail], n - n1);
_read_fd(&_readbuf[_readbuf_tail], n - n1);
}
}
}

View File

@ -1,10 +1,10 @@
#include <AP_HAL/AP_HAL.h>
#include "UDPDevice.h"
#include <fcntl.h>
#include <stdio.h>
#include <sys/ioctl.h>
#include <fcntl.h>
#include "UDPDevice.h"
#include <AP_HAL/AP_HAL.h>
UDPDevice::UDPDevice(const char *ip, uint16_t port, bool bcast):
_ip(ip),

View File

@ -1,22 +1,21 @@
#include <errno.h>
#include <fcntl.h>
#include <stdarg.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/stat.h>
#include <time.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include <stdio.h>
#include <stdarg.h>
#include <sys/stat.h>
#include <unistd.h>
#include <stdlib.h>
#include <errno.h>
#include <time.h>
#include <fcntl.h>
extern const AP_HAL::HAL& hal;
#include "Heat_Pwm.h"
#include "ToneAlarm_Raspilot.h"
#include "Util.h"
#include "Heat_Pwm.h"
using namespace Linux;
extern const AP_HAL::HAL& hal;
static int state;
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT

View File

@ -38,8 +38,8 @@
#include <stdint.h>
#include <stdbool.h>
#include "sbus.h"
#include "sbus.h"
#define SBUS_FRAME_SIZE 25
#define SBUS_INPUT_CHANNELS 16
@ -96,7 +96,7 @@ static const struct sbus_bit_pick sbus_decoder[SBUS_INPUT_CHANNELS][3] = {
bool
sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values,
sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values,
bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values)
{
/* check frame boundary markers to avoid out-of-sync cases */
@ -172,9 +172,9 @@ sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values,
}
else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */
/* set a special warning flag
*
* Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
* condition as fail-safe greatly reduces the reliability and range of the radio link,
*
* Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
* condition as fail-safe greatly reduces the reliability and range of the radio link,
* e.g. by prematurely issuing return-to-launch!!! */
*sbus_failsafe = false;