forked from Archive/PX4-Autopilot
Merge branch 'master' of https://github.com/PX4/Firmware into fmuv2_bringup
This commit is contained in:
commit
dca9019f75
Binary file not shown.
Binary file not shown.
|
@ -28,7 +28,8 @@ MODULES += drivers/ms5611
|
|||
MODULES += drivers/mb12xx
|
||||
MODULES += drivers/gps
|
||||
MODULES += drivers/hil
|
||||
MODULES += drivers/hott_telemetry
|
||||
MODULES += drivers/hott/hott_telemetry
|
||||
MODULES += drivers/hott/hott_sensors
|
||||
MODULES += drivers/blinkm
|
||||
MODULES += drivers/mkblctrl
|
||||
MODULES += drivers/md25
|
||||
|
|
|
@ -109,7 +109,7 @@ int ar_multiplexing_init()
|
|||
{
|
||||
int fd;
|
||||
|
||||
fd = open(GPIO_DEVICE_PATH, 0);
|
||||
fd = open(PX4FMU_DEVICE_PATH, 0);
|
||||
|
||||
if (fd < 0) {
|
||||
warn("GPIO: open fail");
|
||||
|
|
|
@ -63,7 +63,8 @@
|
|||
* they also export GPIO-like things. This is always the GPIOs on the
|
||||
* main board.
|
||||
*/
|
||||
# define GPIO_DEVICE_PATH "/dev/px4fmu"
|
||||
# define PX4FMU_DEVICE_PATH "/dev/px4fmu"
|
||||
# define PX4IO_DEVICE_PATH "/dev/px4io"
|
||||
|
||||
#endif
|
||||
|
||||
|
@ -92,22 +93,17 @@
|
|||
* they also export GPIO-like things. This is always the GPIOs on the
|
||||
* main board.
|
||||
*/
|
||||
# define GPIO_DEVICE_PATH "/dev/px4fmu"
|
||||
# define PX4FMU_DEVICE_PATH "/dev/px4fmu"
|
||||
# define PX4IO_DEVICE_PATH "/dev/px4io"
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
|
||||
/* no GPIO driver on the PX4IOv1 board */
|
||||
# define GPIO_DEVICE_PATH "/nonexistent"
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
|
||||
/* no GPIO driver on the PX4IOv2 board */
|
||||
# define GPIO_DEVICE_PATH "/nonexistent"
|
||||
#endif
|
||||
|
||||
#ifndef GPIO_DEVICE_PATH
|
||||
# error No GPIO support for this board.
|
||||
#endif
|
||||
|
||||
/*
|
||||
|
|
|
@ -115,6 +115,15 @@ ORB_DECLARE(output_pwm);
|
|||
/** clear the 'ARM ok' bit, which deactivates the safety switch */
|
||||
#define PWM_SERVO_CLEAR_ARM_OK _IOC(_PWM_SERVO_BASE, 6)
|
||||
|
||||
/** start DSM bind */
|
||||
#define DSM_BIND_START _IOC(_PWM_SERVO_BASE, 7)
|
||||
|
||||
/** stop DSM bind */
|
||||
#define DSM_BIND_STOP _IOC(_PWM_SERVO_BASE, 8)
|
||||
|
||||
/** Power up DSM receiver */
|
||||
#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 9)
|
||||
|
||||
/** set a single servo to a specific value */
|
||||
#define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo)
|
||||
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -3,6 +3,7 @@
|
|||
* Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* Julian Oes <joes@student.ethz.ch>
|
||||
* Anton Babushkin <anton.babushkin@me.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -51,23 +52,23 @@
|
|||
|
||||
/* MessageIDs (the ones that are used) */
|
||||
#define UBX_MESSAGE_NAV_POSLLH 0x02
|
||||
#define UBX_MESSAGE_NAV_SOL 0x06
|
||||
#define UBX_MESSAGE_NAV_TIMEUTC 0x21
|
||||
//#define UBX_MESSAGE_NAV_DOP 0x04
|
||||
#define UBX_MESSAGE_NAV_SVINFO 0x30
|
||||
#define UBX_MESSAGE_NAV_SOL 0x06
|
||||
#define UBX_MESSAGE_NAV_VELNED 0x12
|
||||
//#define UBX_MESSAGE_RXM_SVSI 0x20
|
||||
#define UBX_MESSAGE_ACK_ACK 0x01
|
||||
#define UBX_MESSAGE_NAV_TIMEUTC 0x21
|
||||
#define UBX_MESSAGE_NAV_SVINFO 0x30
|
||||
#define UBX_MESSAGE_ACK_NAK 0x00
|
||||
#define UBX_MESSAGE_ACK_ACK 0x01
|
||||
#define UBX_MESSAGE_CFG_PRT 0x00
|
||||
#define UBX_MESSAGE_CFG_NAV5 0x24
|
||||
#define UBX_MESSAGE_CFG_MSG 0x01
|
||||
#define UBX_MESSAGE_CFG_RATE 0x08
|
||||
#define UBX_MESSAGE_CFG_NAV5 0x24
|
||||
|
||||
#define UBX_CFG_PRT_LENGTH 20
|
||||
#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< UART1 */
|
||||
#define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */
|
||||
#define UBX_CFG_PRT_PAYLOAD_BAUDRATE 38400 /**< always choose 38400 as GPS baudrate */
|
||||
#define UBX_CFG_PRT_PAYLOAD_BAUDRATE 38400 /**< choose 38400 as GPS baudrate */
|
||||
#define UBX_CFG_PRT_PAYLOAD_INPROTOMASK 0x01 /**< UBX in */
|
||||
#define UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK 0x01 /**< UBX out */
|
||||
|
||||
|
@ -298,44 +299,6 @@ struct ubx_cfg_msg_rate {
|
|||
// END the structures of the binary packets
|
||||
// ************
|
||||
|
||||
typedef enum {
|
||||
UBX_CONFIG_STATE_PRT = 0,
|
||||
UBX_CONFIG_STATE_PRT_NEW_BAUDRATE,
|
||||
UBX_CONFIG_STATE_RATE,
|
||||
UBX_CONFIG_STATE_NAV5,
|
||||
UBX_CONFIG_STATE_MSG_NAV_POSLLH,
|
||||
UBX_CONFIG_STATE_MSG_NAV_TIMEUTC,
|
||||
UBX_CONFIG_STATE_MSG_NAV_DOP,
|
||||
UBX_CONFIG_STATE_MSG_NAV_SVINFO,
|
||||
UBX_CONFIG_STATE_MSG_NAV_SOL,
|
||||
UBX_CONFIG_STATE_MSG_NAV_VELNED,
|
||||
// UBX_CONFIG_STATE_MSG_RXM_SVSI,
|
||||
UBX_CONFIG_STATE_CONFIGURED
|
||||
} ubx_config_state_t;
|
||||
|
||||
typedef enum {
|
||||
CLASS_UNKNOWN = 0,
|
||||
NAV = 1,
|
||||
RXM = 2,
|
||||
ACK = 3,
|
||||
CFG = 4
|
||||
} ubx_message_class_t;
|
||||
|
||||
typedef enum {
|
||||
//these numbers do NOT correspond to the message id numbers of the ubx protocol
|
||||
ID_UNKNOWN = 0,
|
||||
NAV_POSLLH,
|
||||
NAV_SOL,
|
||||
NAV_TIMEUTC,
|
||||
// NAV_DOP,
|
||||
NAV_SVINFO,
|
||||
NAV_VELNED,
|
||||
// RXM_SVSI,
|
||||
CFG_NAV5,
|
||||
ACK_ACK,
|
||||
ACK_NAK,
|
||||
} ubx_message_id_t;
|
||||
|
||||
typedef enum {
|
||||
UBX_DECODE_UNINIT = 0,
|
||||
UBX_DECODE_GOT_SYNC1,
|
||||
|
@ -401,17 +364,17 @@ private:
|
|||
|
||||
int _fd;
|
||||
struct vehicle_gps_position_s *_gps_position;
|
||||
ubx_config_state_t _config_state;
|
||||
bool _configured;
|
||||
bool _waiting_for_ack;
|
||||
uint8_t _clsID_needed;
|
||||
uint8_t _msgID_needed;
|
||||
uint8_t _message_class_needed;
|
||||
uint8_t _message_id_needed;
|
||||
ubx_decode_state_t _decode_state;
|
||||
uint8_t _rx_buffer[RECV_BUFFER_SIZE];
|
||||
unsigned _rx_count;
|
||||
uint8_t _rx_ck_a;
|
||||
uint8_t _rx_ck_b;
|
||||
ubx_message_class_t _message_class;
|
||||
ubx_message_id_t _message_id;
|
||||
uint8_t _message_class;
|
||||
uint8_t _message_id;
|
||||
unsigned _payload_size;
|
||||
uint8_t _disable_cmd_counter;
|
||||
};
|
||||
|
|
|
@ -0,0 +1,92 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file comms.c
|
||||
* @author Simon Wilks <sjwilks@gmail.com>
|
||||
*
|
||||
*/
|
||||
|
||||
#include "comms.h"
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <stdio.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <termios.h>
|
||||
|
||||
int
|
||||
open_uart(const char *device)
|
||||
{
|
||||
/* baud rate */
|
||||
static const speed_t speed = B19200;
|
||||
|
||||
/* open uart */
|
||||
const int uart = open(device, O_RDWR | O_NOCTTY);
|
||||
|
||||
if (uart < 0) {
|
||||
err(1, "Error opening port: %s", device);
|
||||
}
|
||||
|
||||
/* Back up the original uart configuration to restore it after exit */
|
||||
int termios_state;
|
||||
struct termios uart_config_original;
|
||||
if ((termios_state = tcgetattr(uart, &uart_config_original)) < 0) {
|
||||
close(uart);
|
||||
err(1, "Error getting baudrate / termios config for %s: %d", device, termios_state);
|
||||
}
|
||||
|
||||
/* Fill the struct for the new configuration */
|
||||
struct termios uart_config;
|
||||
tcgetattr(uart, &uart_config);
|
||||
|
||||
/* Clear ONLCR flag (which appends a CR for every LF) */
|
||||
uart_config.c_oflag &= ~ONLCR;
|
||||
|
||||
/* Set baud rate */
|
||||
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
|
||||
close(uart);
|
||||
err(1, "Error setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)",
|
||||
device, termios_state);
|
||||
}
|
||||
|
||||
if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
|
||||
close(uart);
|
||||
err(1, "Error setting baudrate / termios config for %s (tcsetattr)", device);
|
||||
}
|
||||
|
||||
/* Activate single wire mode */
|
||||
ioctl(uart, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED);
|
||||
|
||||
return uart;
|
||||
}
|
|
@ -0,0 +1,46 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file comms.h
|
||||
* @author Simon Wilks <sjwilks@gmail.com>
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifndef COMMS_H_
|
||||
#define COMMS_H
|
||||
|
||||
int open_uart(const char *device);
|
||||
|
||||
#endif /* COMMS_H_ */
|
|
@ -0,0 +1,238 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Simon Wilks <sjwilks@gmail.com>
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file hott_sensors.c
|
||||
* @author Simon Wilks <sjwilks@gmail.com>
|
||||
*
|
||||
* Graupner HoTT sensor driver implementation.
|
||||
*
|
||||
* Poll any sensors connected to the PX4 via the telemetry wire.
|
||||
*/
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <poll.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <unistd.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
#include "../comms.h"
|
||||
#include "../messages.h"
|
||||
|
||||
#define DEFAULT_UART "/dev/ttyS0"; /**< USART1 */
|
||||
|
||||
/* Oddly, ERROR is not defined for C++ */
|
||||
#ifdef ERROR
|
||||
# undef ERROR
|
||||
#endif
|
||||
static const int ERROR = -1;
|
||||
|
||||
static int thread_should_exit = false; /**< Deamon exit flag */
|
||||
static int thread_running = false; /**< Deamon status flag */
|
||||
static int deamon_task; /**< Handle of deamon task / thread */
|
||||
static const char daemon_name[] = "hott_sensors";
|
||||
static const char commandline_usage[] = "usage: hott_sensors start|status|stop [-d <device>]";
|
||||
|
||||
/**
|
||||
* Deamon management function.
|
||||
*/
|
||||
extern "C" __EXPORT int hott_sensors_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Mainloop of daemon.
|
||||
*/
|
||||
int hott_sensors_thread_main(int argc, char *argv[]);
|
||||
|
||||
static int recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t *id);
|
||||
static int send_poll(int uart, uint8_t *buffer, size_t size);
|
||||
|
||||
int
|
||||
send_poll(int uart, uint8_t *buffer, size_t size)
|
||||
{
|
||||
for (size_t i = 0; i < size; i++) {
|
||||
write(uart, &buffer[i], sizeof(buffer[i]));
|
||||
|
||||
/* Sleep before sending the next byte. */
|
||||
usleep(POST_WRITE_DELAY_IN_USECS);
|
||||
}
|
||||
|
||||
/* A hack the reads out what was written so the next read from the receiver doesn't get it. */
|
||||
/* TODO: Fix this!! */
|
||||
uint8_t dummy[size];
|
||||
read(uart, &dummy, size);
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int
|
||||
recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t *id)
|
||||
{
|
||||
static const int timeout_ms = 1000;
|
||||
|
||||
struct pollfd fds;
|
||||
fds.fd = uart;
|
||||
fds.events = POLLIN;
|
||||
|
||||
// XXX should this poll be inside the while loop???
|
||||
if (poll(&fds, 1, timeout_ms) > 0) {
|
||||
int i = 0;
|
||||
bool stop_byte_read = false;
|
||||
while (true) {
|
||||
read(uart, &buffer[i], sizeof(buffer[i]));
|
||||
|
||||
if (stop_byte_read) {
|
||||
// XXX process checksum
|
||||
*size = ++i;
|
||||
return OK;
|
||||
}
|
||||
// XXX can some other field not have the STOP BYTE value?
|
||||
if (buffer[i] == STOP_BYTE) {
|
||||
*id = buffer[1];
|
||||
stop_byte_read = true;
|
||||
}
|
||||
i++;
|
||||
}
|
||||
}
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
int
|
||||
hott_sensors_thread_main(int argc, char *argv[])
|
||||
{
|
||||
warnx("starting");
|
||||
|
||||
thread_running = true;
|
||||
|
||||
const char *device = DEFAULT_UART;
|
||||
|
||||
/* read commandline arguments */
|
||||
for (int i = 0; i < argc && argv[i]; i++) {
|
||||
if (strcmp(argv[i], "-d") == 0 || strcmp(argv[i], "--device") == 0) { //device set
|
||||
if (argc > i + 1) {
|
||||
device = argv[i + 1];
|
||||
|
||||
} else {
|
||||
thread_running = false;
|
||||
errx(1, "missing parameter to -d\n%s", commandline_usage);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* enable UART, writes potentially an empty buffer, but multiplexing is disabled */
|
||||
const int uart = open_uart(device);
|
||||
if (uart < 0) {
|
||||
errx(1, "Failed opening HoTT UART, exiting.");
|
||||
thread_running = false;
|
||||
}
|
||||
|
||||
init_pub_messages();
|
||||
|
||||
uint8_t buffer[MAX_MESSAGE_BUFFER_SIZE];
|
||||
size_t size = 0;
|
||||
uint8_t id = 0;
|
||||
while (!thread_should_exit) {
|
||||
// Currently we only support a General Air Module sensor.
|
||||
build_gam_request(&buffer[0], &size);
|
||||
send_poll(uart, buffer, size);
|
||||
|
||||
// The sensor will need a little time before it starts sending.
|
||||
usleep(5000);
|
||||
|
||||
recv_data(uart, &buffer[0], &size, &id);
|
||||
|
||||
// Determine which moduel sent it and process accordingly.
|
||||
if (id == GAM_SENSOR_ID) {
|
||||
publish_gam_message(buffer);
|
||||
} else {
|
||||
warnx("Unknown sensor ID: %d", id);
|
||||
}
|
||||
}
|
||||
|
||||
warnx("exiting");
|
||||
close(uart);
|
||||
thread_running = false;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Process command line arguments and start the daemon.
|
||||
*/
|
||||
int
|
||||
hott_sensors_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 1) {
|
||||
errx(1, "missing command\n%s", commandline_usage);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
if (thread_running) {
|
||||
warnx("deamon already running");
|
||||
exit(0);
|
||||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn_cmd(daemon_name,
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 40,
|
||||
1024,
|
||||
hott_sensors_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "stop")) {
|
||||
thread_should_exit = true;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
if (thread_running) {
|
||||
warnx("daemon is running");
|
||||
|
||||
} else {
|
||||
warnx("daemon not started");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
errx(1, "unrecognized command\n%s", commandline_usage);
|
||||
}
|
|
@ -0,0 +1,42 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2012, 2013 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Graupner HoTT Sensors application.
|
||||
#
|
||||
|
||||
MODULE_COMMAND = hott_sensors
|
||||
|
||||
SRCS = hott_sensors.cpp \
|
||||
../messages.cpp \
|
||||
../comms.cpp
|
|
@ -41,7 +41,6 @@
|
|||
* The HoTT receiver polls each device at a regular interval at which point
|
||||
* a data packet can be returned if necessary.
|
||||
*
|
||||
* TODO: Add support for at least the vario and GPS sensor data.
|
||||
*/
|
||||
|
||||
#include <fcntl.h>
|
||||
|
@ -50,13 +49,21 @@
|
|||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <termios.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <unistd.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
#include "messages.h"
|
||||
#include "../comms.h"
|
||||
#include "../messages.h"
|
||||
|
||||
#define DEFAULT_UART "/dev/ttyS0"; /**< USART1 */
|
||||
|
||||
/* Oddly, ERROR is not defined for C++ */
|
||||
#ifdef ERROR
|
||||
# undef ERROR
|
||||
#endif
|
||||
static const int ERROR = -1;
|
||||
|
||||
static int thread_should_exit = false; /**< Deamon exit flag */
|
||||
static int thread_running = false; /**< Deamon status flag */
|
||||
|
@ -67,7 +74,7 @@ static const char commandline_usage[] = "usage: hott_telemetry start|status|stop
|
|||
/**
|
||||
* Deamon management function.
|
||||
*/
|
||||
__EXPORT int hott_telemetry_main(int argc, char *argv[]);
|
||||
extern "C" __EXPORT int hott_telemetry_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Mainloop of daemon.
|
||||
|
@ -77,60 +84,18 @@ int hott_telemetry_thread_main(int argc, char *argv[]);
|
|||
static int recv_req_id(int uart, uint8_t *id);
|
||||
static int send_data(int uart, uint8_t *buffer, size_t size);
|
||||
|
||||
static int
|
||||
open_uart(const char *device, struct termios *uart_config_original)
|
||||
{
|
||||
/* baud rate */
|
||||
static const speed_t speed = B19200;
|
||||
|
||||
/* open uart */
|
||||
const int uart = open(device, O_RDWR | O_NOCTTY);
|
||||
|
||||
if (uart < 0) {
|
||||
err(1, "Error opening port: %s", device);
|
||||
}
|
||||
|
||||
/* Back up the original uart configuration to restore it after exit */
|
||||
int termios_state;
|
||||
if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
|
||||
close(uart);
|
||||
err(1, "Error getting baudrate / termios config for %s: %d", device, termios_state);
|
||||
}
|
||||
|
||||
/* Fill the struct for the new configuration */
|
||||
struct termios uart_config;
|
||||
tcgetattr(uart, &uart_config);
|
||||
|
||||
/* Clear ONLCR flag (which appends a CR for every LF) */
|
||||
uart_config.c_oflag &= ~ONLCR;
|
||||
|
||||
/* Set baud rate */
|
||||
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
|
||||
close(uart);
|
||||
err(1, "Error setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)",
|
||||
device, termios_state);
|
||||
}
|
||||
|
||||
if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
|
||||
close(uart);
|
||||
err(1, "Error setting baudrate / termios config for %s (tcsetattr)", device);
|
||||
}
|
||||
|
||||
/* Activate single wire mode */
|
||||
ioctl(uart, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED);
|
||||
|
||||
return uart;
|
||||
}
|
||||
|
||||
int
|
||||
recv_req_id(int uart, uint8_t *id)
|
||||
{
|
||||
static const int timeout_ms = 1000; // TODO make it a define
|
||||
struct pollfd fds[] = { { .fd = uart, .events = POLLIN } };
|
||||
|
||||
uint8_t mode;
|
||||
|
||||
struct pollfd fds;
|
||||
fds.fd = uart;
|
||||
fds.events = POLLIN;
|
||||
|
||||
if (poll(fds, 1, timeout_ms) > 0) {
|
||||
if (poll(&fds, 1, timeout_ms) > 0) {
|
||||
/* Get the mode: binary or text */
|
||||
read(uart, &mode, sizeof(mode));
|
||||
|
||||
|
@ -155,7 +120,6 @@ send_data(int uart, uint8_t *buffer, size_t size)
|
|||
usleep(POST_READ_DELAY_IN_USECS);
|
||||
|
||||
uint16_t checksum = 0;
|
||||
|
||||
for (size_t i = 0; i < size; i++) {
|
||||
if (i == size - 1) {
|
||||
/* Set the checksum: the first uint8_t is taken as the checksum. */
|
||||
|
@ -186,7 +150,7 @@ hott_telemetry_thread_main(int argc, char *argv[])
|
|||
|
||||
thread_running = true;
|
||||
|
||||
const char *device = "/dev/ttyS1"; /**< Default telemetry port: USART2 */
|
||||
const char *device = DEFAULT_UART;
|
||||
|
||||
/* read commandline arguments */
|
||||
for (int i = 0; i < argc && argv[i]; i++) {
|
||||
|
@ -202,22 +166,20 @@ hott_telemetry_thread_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
/* enable UART, writes potentially an empty buffer, but multiplexing is disabled */
|
||||
struct termios uart_config_original;
|
||||
const int uart = open_uart(device, &uart_config_original);
|
||||
|
||||
const int uart = open_uart(device);
|
||||
if (uart < 0) {
|
||||
errx(1, "Failed opening HoTT UART, exiting.");
|
||||
thread_running = false;
|
||||
}
|
||||
|
||||
messages_init();
|
||||
init_sub_messages();
|
||||
|
||||
uint8_t buffer[MESSAGE_BUFFER_SIZE];
|
||||
uint8_t buffer[MAX_MESSAGE_BUFFER_SIZE];
|
||||
size_t size = 0;
|
||||
uint8_t id = 0;
|
||||
bool connected = true;
|
||||
|
||||
while (!thread_should_exit) {
|
||||
// Listen for and serve poll from the receiver.
|
||||
if (recv_req_id(uart, &id) == OK) {
|
||||
if (!connected) {
|
||||
connected = true;
|
||||
|
@ -228,7 +190,9 @@ hott_telemetry_thread_main(int argc, char *argv[])
|
|||
case EAM_SENSOR_ID:
|
||||
build_eam_response(buffer, &size);
|
||||
break;
|
||||
|
||||
case GAM_SENSOR_ID:
|
||||
build_gam_response(buffer, &size);
|
||||
break;
|
||||
case GPS_SENSOR_ID:
|
||||
build_gps_response(buffer, &size);
|
||||
break;
|
||||
|
@ -254,7 +218,7 @@ hott_telemetry_thread_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
/**
|
||||
* Process command line arguments and tart the daemon.
|
||||
* Process command line arguments and start the daemon.
|
||||
*/
|
||||
int
|
||||
hott_telemetry_main(int argc, char *argv[])
|
|
@ -32,10 +32,11 @@
|
|||
############################################################################
|
||||
|
||||
#
|
||||
# Graupner HoTT Telemetry application.
|
||||
# Graupner HoTT Telemetry applications.
|
||||
#
|
||||
|
||||
MODULE_COMMAND = hott_telemetry
|
||||
|
||||
SRCS = hott_telemetry_main.c \
|
||||
messages.c
|
||||
SRCS = hott_telemetry.cpp \
|
||||
../messages.cpp \
|
||||
../comms.cpp
|
|
@ -46,6 +46,7 @@
|
|||
#include <unistd.h>
|
||||
#include <uORB/topics/airspeed.h>
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <uORB/topics/esc_status.h>
|
||||
#include <uORB/topics/home_position.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
|
@ -53,24 +54,75 @@
|
|||
/* The board is very roughly 5 deg warmer than the surrounding air */
|
||||
#define BOARD_TEMP_OFFSET_DEG 5
|
||||
|
||||
static int battery_sub = -1;
|
||||
static int gps_sub = -1;
|
||||
static int home_sub = -1;
|
||||
static int sensor_sub = -1;
|
||||
static int airspeed_sub = -1;
|
||||
static int _battery_sub = -1;
|
||||
static int _gps_sub = -1;
|
||||
static int _home_sub = -1;
|
||||
static int _sensor_sub = -1;
|
||||
static int _airspeed_sub = -1;
|
||||
static int _esc_sub = -1;
|
||||
|
||||
static bool home_position_set = false;
|
||||
static double home_lat = 0.0d;
|
||||
static double home_lon = 0.0d;
|
||||
static orb_advert_t _esc_pub;
|
||||
struct esc_status_s _esc;
|
||||
|
||||
static bool _home_position_set = false;
|
||||
static double _home_lat = 0.0d;
|
||||
static double _home_lon = 0.0d;
|
||||
|
||||
void
|
||||
messages_init(void)
|
||||
init_sub_messages(void)
|
||||
{
|
||||
battery_sub = orb_subscribe(ORB_ID(battery_status));
|
||||
gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
|
||||
home_sub = orb_subscribe(ORB_ID(home_position));
|
||||
sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
|
||||
airspeed_sub = orb_subscribe(ORB_ID(airspeed));
|
||||
_battery_sub = orb_subscribe(ORB_ID(battery_status));
|
||||
_gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
|
||||
_home_sub = orb_subscribe(ORB_ID(home_position));
|
||||
_sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
|
||||
_airspeed_sub = orb_subscribe(ORB_ID(airspeed));
|
||||
_esc_sub = orb_subscribe(ORB_ID(esc_status));
|
||||
}
|
||||
|
||||
void
|
||||
init_pub_messages(void)
|
||||
{
|
||||
memset(&_esc, 0, sizeof(_esc));
|
||||
_esc_pub = orb_advertise(ORB_ID(esc_status), &_esc);
|
||||
}
|
||||
|
||||
void
|
||||
build_gam_request(uint8_t *buffer, size_t *size)
|
||||
{
|
||||
struct gam_module_poll_msg msg;
|
||||
*size = sizeof(msg);
|
||||
memset(&msg, 0, *size);
|
||||
|
||||
msg.mode = BINARY_MODE_REQUEST_ID;
|
||||
msg.id = GAM_SENSOR_ID;
|
||||
|
||||
memcpy(buffer, &msg, *size);
|
||||
}
|
||||
|
||||
void
|
||||
publish_gam_message(const uint8_t *buffer)
|
||||
{
|
||||
struct gam_module_msg msg;
|
||||
size_t size = sizeof(msg);
|
||||
memset(&msg, 0, size);
|
||||
memcpy(&msg, buffer, size);
|
||||
|
||||
/* announce the esc if needed, just publish else */
|
||||
if (_esc_pub > 0) {
|
||||
orb_publish(ORB_ID(esc_status), _esc_pub, &_esc);
|
||||
} else {
|
||||
_esc_pub = orb_advertise(ORB_ID(esc_status), &_esc);
|
||||
}
|
||||
|
||||
// Publish it.
|
||||
_esc.esc_count = 1;
|
||||
_esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM;
|
||||
|
||||
_esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
|
||||
_esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
|
||||
_esc.esc[0].esc_temperature = msg.temperature1 - 20;
|
||||
_esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff));
|
||||
_esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff));
|
||||
}
|
||||
|
||||
void
|
||||
|
@ -79,12 +131,12 @@ build_eam_response(uint8_t *buffer, size_t *size)
|
|||
/* get a local copy of the current sensor values */
|
||||
struct sensor_combined_s raw;
|
||||
memset(&raw, 0, sizeof(raw));
|
||||
orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw);
|
||||
orb_copy(ORB_ID(sensor_combined), _sensor_sub, &raw);
|
||||
|
||||
/* get a local copy of the battery data */
|
||||
struct battery_status_s battery;
|
||||
memset(&battery, 0, sizeof(battery));
|
||||
orb_copy(ORB_ID(battery_status), battery_sub, &battery);
|
||||
orb_copy(ORB_ID(battery_status), _battery_sub, &battery);
|
||||
|
||||
struct eam_module_msg msg;
|
||||
*size = sizeof(msg);
|
||||
|
@ -92,7 +144,7 @@ build_eam_response(uint8_t *buffer, size_t *size)
|
|||
|
||||
msg.start = START_BYTE;
|
||||
msg.eam_sensor_id = EAM_SENSOR_ID;
|
||||
msg.sensor_id = EAM_SENSOR_TEXT_ID;
|
||||
msg.sensor_text_id = EAM_SENSOR_TEXT_ID;
|
||||
|
||||
msg.temperature1 = (uint8_t)(raw.baro_temp_celcius + 20);
|
||||
msg.temperature2 = msg.temperature1 - BOARD_TEMP_OFFSET_DEG;
|
||||
|
@ -106,12 +158,46 @@ build_eam_response(uint8_t *buffer, size_t *size)
|
|||
/* get a local copy of the airspeed data */
|
||||
struct airspeed_s airspeed;
|
||||
memset(&airspeed, 0, sizeof(airspeed));
|
||||
orb_copy(ORB_ID(airspeed), airspeed_sub, &airspeed);
|
||||
orb_copy(ORB_ID(airspeed), _airspeed_sub, &airspeed);
|
||||
|
||||
uint16_t speed = (uint16_t)(airspeed.indicated_airspeed_m_s * 3.6f);
|
||||
msg.speed_L = (uint8_t)speed & 0xff;
|
||||
msg.speed_H = (uint8_t)(speed >> 8) & 0xff;
|
||||
|
||||
|
||||
msg.stop = STOP_BYTE;
|
||||
memcpy(buffer, &msg, *size);
|
||||
}
|
||||
|
||||
void
|
||||
build_gam_response(uint8_t *buffer, size_t *size)
|
||||
{
|
||||
/* get a local copy of the ESC Status values */
|
||||
struct esc_status_s esc;
|
||||
memset(&esc, 0, sizeof(esc));
|
||||
orb_copy(ORB_ID(esc_status), _esc_sub, &esc);
|
||||
|
||||
struct gam_module_msg msg;
|
||||
*size = sizeof(msg);
|
||||
memset(&msg, 0, *size);
|
||||
|
||||
msg.start = START_BYTE;
|
||||
msg.gam_sensor_id = GAM_SENSOR_ID;
|
||||
msg.sensor_text_id = GAM_SENSOR_TEXT_ID;
|
||||
|
||||
msg.temperature1 = (uint8_t)(esc.esc[0].esc_temperature + 20);
|
||||
msg.temperature2 = 20; // 0 deg. C.
|
||||
|
||||
uint16_t voltage = (uint16_t)(esc.esc[0].esc_voltage);
|
||||
msg.main_voltage_L = (uint8_t)voltage & 0xff;
|
||||
msg.main_voltage_H = (uint8_t)(voltage >> 8) & 0xff;
|
||||
|
||||
uint16_t current = (uint16_t)(esc.esc[0].esc_current);
|
||||
msg.current_L = (uint8_t)current & 0xff;
|
||||
msg.current_H = (uint8_t)(current >> 8) & 0xff;
|
||||
|
||||
uint16_t rpm = (uint16_t)(esc.esc[0].esc_rpm * 0.1f);
|
||||
msg.rpm_L = (uint8_t)rpm & 0xff;
|
||||
msg.rpm_H = (uint8_t)(rpm >> 8) & 0xff;
|
||||
|
||||
msg.stop = STOP_BYTE;
|
||||
memcpy(buffer, &msg, *size);
|
||||
|
@ -123,14 +209,14 @@ build_gps_response(uint8_t *buffer, size_t *size)
|
|||
/* get a local copy of the current sensor values */
|
||||
struct sensor_combined_s raw;
|
||||
memset(&raw, 0, sizeof(raw));
|
||||
orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw);
|
||||
orb_copy(ORB_ID(sensor_combined), _sensor_sub, &raw);
|
||||
|
||||
/* get a local copy of the battery data */
|
||||
struct vehicle_gps_position_s gps;
|
||||
memset(&gps, 0, sizeof(gps));
|
||||
orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps);
|
||||
orb_copy(ORB_ID(vehicle_gps_position), _gps_sub, &gps);
|
||||
|
||||
struct gps_module_msg msg = { 0 };
|
||||
struct gps_module_msg msg;
|
||||
*size = sizeof(msg);
|
||||
memset(&msg, 0, *size);
|
||||
|
||||
|
@ -150,7 +236,7 @@ build_gps_response(uint8_t *buffer, size_t *size)
|
|||
msg.flight_direction = (uint8_t)(gps.cog_rad * M_RAD_TO_DEG_F);
|
||||
|
||||
/* GPS speed */
|
||||
uint16_t speed = (uint16_t)(gps.vel_m_s * 3.6);
|
||||
uint16_t speed = (uint16_t)(gps.vel_m_s * 3.6f);
|
||||
msg.gps_speed_L = (uint8_t)speed & 0xff;
|
||||
msg.gps_speed_H = (uint8_t)(speed >> 8) & 0xff;
|
||||
|
||||
|
@ -196,33 +282,33 @@ build_gps_response(uint8_t *buffer, size_t *size)
|
|||
msg.longitude_sec_H = (uint8_t)(lon_sec >> 8) & 0xff;
|
||||
|
||||
/* Altitude */
|
||||
uint16_t alt = (uint16_t)(gps.alt*1e-3 + 500.0f);
|
||||
uint16_t alt = (uint16_t)(gps.alt*1e-3f + 500.0f);
|
||||
msg.altitude_L = (uint8_t)alt & 0xff;
|
||||
msg.altitude_H = (uint8_t)(alt >> 8) & 0xff;
|
||||
|
||||
/* Get any (and probably only ever one) home_sub postion report */
|
||||
/* Get any (and probably only ever one) _home_sub postion report */
|
||||
bool updated;
|
||||
orb_check(home_sub, &updated);
|
||||
orb_check(_home_sub, &updated);
|
||||
if (updated) {
|
||||
/* get a local copy of the home position data */
|
||||
struct home_position_s home;
|
||||
memset(&home, 0, sizeof(home));
|
||||
orb_copy(ORB_ID(home_position), home_sub, &home);
|
||||
orb_copy(ORB_ID(home_position), _home_sub, &home);
|
||||
|
||||
home_lat = ((double)(home.lat))*1e-7d;
|
||||
home_lon = ((double)(home.lon))*1e-7d;
|
||||
home_position_set = true;
|
||||
_home_lat = ((double)(home.lat))*1e-7d;
|
||||
_home_lon = ((double)(home.lon))*1e-7d;
|
||||
_home_position_set = true;
|
||||
}
|
||||
|
||||
/* Distance from home */
|
||||
if (home_position_set) {
|
||||
uint16_t dist = (uint16_t)get_distance_to_next_waypoint(home_lat, home_lon, lat, lon);
|
||||
if (_home_position_set) {
|
||||
uint16_t dist = (uint16_t)get_distance_to_next_waypoint(_home_lat, _home_lon, lat, lon);
|
||||
|
||||
msg.distance_L = (uint8_t)dist & 0xff;
|
||||
msg.distance_H = (uint8_t)(dist >> 8) & 0xff;
|
||||
|
||||
/* Direction back to home */
|
||||
uint16_t bearing = (uint16_t)(get_bearing_to_next_waypoint(home_lat, home_lon, lat, lon) * M_RAD_TO_DEG_F);
|
||||
uint16_t bearing = (uint16_t)(get_bearing_to_next_waypoint(_home_lat, _home_lon, lat, lon) * M_RAD_TO_DEG_F);
|
||||
msg.home_direction = (uint8_t)bearing >> 1;
|
||||
}
|
||||
}
|
|
@ -60,19 +60,25 @@
|
|||
#define STOP_BYTE 0x7d
|
||||
#define TEMP_ZERO_CELSIUS 0x14
|
||||
|
||||
/* The GAM Module poll message. */
|
||||
struct gam_module_poll_msg {
|
||||
uint8_t mode;
|
||||
uint8_t id;
|
||||
};
|
||||
|
||||
/* Electric Air Module (EAM) constants. */
|
||||
#define EAM_SENSOR_ID 0x8e
|
||||
#define EAM_SENSOR_TEXT_ID 0xe0
|
||||
|
||||
/* The Electric Air Module message. */
|
||||
struct eam_module_msg {
|
||||
uint8_t start; /**< Start byte */
|
||||
uint8_t start; /**< Start byte */
|
||||
uint8_t eam_sensor_id; /**< EAM sensor */
|
||||
uint8_t warning;
|
||||
uint8_t sensor_id; /**< Sensor ID, why different? */
|
||||
uint8_t sensor_text_id;
|
||||
uint8_t alarm_inverse1;
|
||||
uint8_t alarm_inverse2;
|
||||
uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */
|
||||
uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */
|
||||
uint8_t cell2_L;
|
||||
uint8_t cell3_L;
|
||||
uint8_t cell4_L;
|
||||
|
@ -92,9 +98,9 @@ struct eam_module_msg {
|
|||
uint8_t batt2_voltage_H;
|
||||
uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */
|
||||
uint8_t temperature2;
|
||||
uint8_t altitude_L; /**< Attitude (meters) lower 8-bits. 500 = 0 meters */
|
||||
uint8_t altitude_L; /**< Attitude (meters) lower 8-bits. 500 = 0 meters */
|
||||
uint8_t altitude_H;
|
||||
uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */
|
||||
uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */
|
||||
uint8_t current_H;
|
||||
uint8_t main_voltage_L; /**< Main power voltage lower 8-bits in steps of 0.1V */
|
||||
uint8_t main_voltage_H;
|
||||
|
@ -103,35 +109,82 @@ struct eam_module_msg {
|
|||
uint8_t climbrate_L; /**< Climb rate in 0.01m/s. 0m/s = 30000 */
|
||||
uint8_t climbrate_H;
|
||||
uint8_t climbrate_3s; /**< Climb rate in m/3sec. 0m/3sec = 120 */
|
||||
uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */
|
||||
uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */
|
||||
uint8_t rpm_H;
|
||||
uint8_t electric_min; /**< Flight time in minutes. */
|
||||
uint8_t electric_sec; /**< Flight time in seconds. */
|
||||
uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */
|
||||
uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */
|
||||
uint8_t speed_H;
|
||||
uint8_t stop; /**< Stop byte */
|
||||
uint8_t checksum; /**< Lower 8-bits of all bytes summed. */
|
||||
uint8_t stop; /**< Stop byte */
|
||||
uint8_t checksum; /**< Lower 8-bits of all bytes summed. */
|
||||
};
|
||||
|
||||
/**
|
||||
* The maximum buffer size required to store a HoTT message.
|
||||
*/
|
||||
#define MESSAGE_BUFFER_SIZE sizeof(union { \
|
||||
struct eam_module_msg eam; \
|
||||
})
|
||||
|
||||
/* General Air Module (GAM) constants. */
|
||||
#define GAM_SENSOR_ID 0x8d
|
||||
#define GAM_SENSOR_TEXT_ID 0xd0
|
||||
|
||||
struct gam_module_msg {
|
||||
uint8_t start; // start byte constant value 0x7c
|
||||
uint8_t gam_sensor_id; // EAM sensort id. constat value 0x8d
|
||||
uint8_t warning_beeps; // 1=A 2=B ... 0x1a=Z 0 = no alarm
|
||||
uint8_t sensor_text_id; // constant value 0xd0
|
||||
uint8_t alarm_invers1; // alarm bitmask. Value is displayed inverted
|
||||
uint8_t alarm_invers2; // alarm bitmask. Value is displayed inverted
|
||||
uint8_t cell1; // cell 1 voltage lower value. 0.02V steps, 124=2.48V
|
||||
uint8_t cell2;
|
||||
uint8_t cell3;
|
||||
uint8_t cell4;
|
||||
uint8_t cell5;
|
||||
uint8_t cell6;
|
||||
uint8_t batt1_L; // battery 1 voltage LSB value. 0.1V steps. 50 = 5.5V
|
||||
uint8_t batt1_H;
|
||||
uint8_t batt2_L; // battery 2 voltage LSB value. 0.1V steps. 50 = 5.5V
|
||||
uint8_t batt2_H;
|
||||
uint8_t temperature1; // temperature 1. offset of 20. a value of 20 = 0°C
|
||||
uint8_t temperature2; // temperature 2. offset of 20. a value of 20 = 0°C
|
||||
uint8_t fuel_procent; // Fuel capacity in %. Values 0--100
|
||||
// graphical display ranges: 0-25% 50% 75% 100%
|
||||
uint8_t fuel_ml_L; // Fuel in ml scale. Full = 65535!
|
||||
uint8_t fuel_ml_H; //
|
||||
uint8_t rpm_L; // RPM in 10 RPM steps. 300 = 3000rpm
|
||||
uint8_t rpm_H; //
|
||||
uint8_t altitude_L; // altitude in meters. offset of 500, 500 = 0m
|
||||
uint8_t altitude_H; //
|
||||
uint8_t climbrate_L; // climb rate in 0.01m/s. Value of 30000 = 0.00 m/s
|
||||
uint8_t climbrate_H; //
|
||||
uint8_t climbrate3s; // climb rate in m/3sec. Value of 120 = 0m/3sec
|
||||
uint8_t current_L; // current in 0.1A steps
|
||||
uint8_t current_H; //
|
||||
uint8_t main_voltage_L; // Main power voltage using 0.1V steps
|
||||
uint8_t main_voltage_H; //
|
||||
uint8_t batt_cap_L; // used battery capacity in 10mAh steps
|
||||
uint8_t batt_cap_H; //
|
||||
uint8_t speed_L; // (air?) speed in km/h(?) we are using ground speed here per default
|
||||
uint8_t speed_H; //
|
||||
uint8_t min_cell_volt; // minimum cell voltage in 2mV steps. 124 = 2,48V
|
||||
uint8_t min_cell_volt_num; // number of the cell with the lowest voltage
|
||||
uint8_t rpm2_L; // RPM in 10 RPM steps. 300 = 3000rpm
|
||||
uint8_t rpm2_H; //
|
||||
uint8_t general_error_number; // Voice error == 12. TODO: more docu
|
||||
uint8_t pressure; // Pressure up to 16bar. 0,1bar scale. 20 = 2bar
|
||||
uint8_t version; // version number TODO: more info?
|
||||
uint8_t stop; // stop byte
|
||||
uint8_t checksum; // checksum
|
||||
};
|
||||
|
||||
/* GPS sensor constants. */
|
||||
#define GPS_SENSOR_ID 0x8A
|
||||
#define GPS_SENSOR_TEXT_ID 0xA0
|
||||
#define GPS_SENSOR_ID 0x8a
|
||||
#define GPS_SENSOR_TEXT_ID 0xa0
|
||||
|
||||
/**
|
||||
* The GPS sensor message
|
||||
* Struct based on: https://code.google.com/p/diy-hott-gps/downloads
|
||||
*/
|
||||
struct gps_module_msg {
|
||||
uint8_t start; /**< Start byte */
|
||||
uint8_t sensor_id; /**< GPS sensor ID*/
|
||||
uint8_t warning; /**< Byte 3: 0…= warning beeps */
|
||||
uint8_t start; /**< Start byte */
|
||||
uint8_t sensor_id; /**< GPS sensor ID*/
|
||||
uint8_t warning; /**< Byte 3: 0…= warning beeps */
|
||||
uint8_t sensor_text_id; /**< GPS Sensor text mode ID */
|
||||
uint8_t alarm_inverse1; /**< Byte 5: 01 inverse status */
|
||||
uint8_t alarm_inverse2; /**< Byte 6: 00 inverse status status 1 = no GPS Signal */
|
||||
|
@ -179,15 +232,15 @@ struct gps_module_msg {
|
|||
uint8_t checksum; /**< Byte 45: Parity Byte */
|
||||
};
|
||||
|
||||
/**
|
||||
* The maximum buffer size required to store a HoTT message.
|
||||
*/
|
||||
#define GPS_MESSAGE_BUFFER_SIZE sizeof(union { \
|
||||
struct gps_module_msg gps; \
|
||||
})
|
||||
// The maximum size of a message.
|
||||
#define MAX_MESSAGE_BUFFER_SIZE 45
|
||||
|
||||
void messages_init(void);
|
||||
void init_sub_messages(void);
|
||||
void init_pub_messages(void);
|
||||
void build_gam_request(uint8_t *buffer, size_t *size);
|
||||
void publish_gam_message(const uint8_t *buffer);
|
||||
void build_eam_response(uint8_t *buffer, size_t *size);
|
||||
void build_gam_response(uint8_t *buffer, size_t *size);
|
||||
void build_gps_response(uint8_t *buffer, size_t *size);
|
||||
float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
|
||||
void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec);
|
|
@ -195,7 +195,7 @@ PX4FMU *g_fmu;
|
|||
} // namespace
|
||||
|
||||
PX4FMU::PX4FMU() :
|
||||
CDev("fmuservo", "/dev/px4fmu"),
|
||||
CDev("fmuservo", PX4FMU_DEVICE_PATH),
|
||||
_mode(MODE_NONE),
|
||||
_pwm_default_rate(50),
|
||||
_pwm_alt_rate(50),
|
||||
|
|
|
@ -132,6 +132,16 @@ public:
|
|||
*/
|
||||
void print_status();
|
||||
|
||||
inline void set_dsm_vcc_ctl(bool enable)
|
||||
{
|
||||
_dsm_vcc_ctl = enable;
|
||||
};
|
||||
|
||||
inline bool get_dsm_vcc_ctl()
|
||||
{
|
||||
return _dsm_vcc_ctl;
|
||||
};
|
||||
|
||||
private:
|
||||
device::Device *_interface;
|
||||
|
||||
|
@ -178,6 +188,12 @@ private:
|
|||
float _battery_mamphour_total;
|
||||
uint64_t _battery_last_timestamp;
|
||||
|
||||
/**
|
||||
* Relay1 is dedicated to controlling DSM receiver power
|
||||
*/
|
||||
|
||||
bool _dsm_vcc_ctl;
|
||||
|
||||
/**
|
||||
* Trampoline to the worker task
|
||||
*/
|
||||
|
@ -319,7 +335,7 @@ PX4IO *g_dev;
|
|||
}
|
||||
|
||||
PX4IO::PX4IO(device::Device *interface) :
|
||||
CDev("px4io", "/dev/px4io"),
|
||||
CDev("px4io", PX4IO_DEVICE_PATH),
|
||||
_interface(interface),
|
||||
_hardware(0),
|
||||
_max_actuators(0),
|
||||
|
@ -346,7 +362,8 @@ PX4IO::PX4IO(device::Device *interface) :
|
|||
_battery_amp_per_volt(90.0f/5.0f), // this matches the 3DR current sensor
|
||||
_battery_amp_bias(0),
|
||||
_battery_mamphour_total(0),
|
||||
_battery_last_timestamp(0)
|
||||
_battery_last_timestamp(0),
|
||||
_dsm_vcc_ctl(false)
|
||||
{
|
||||
/* we need this potentially before it could be set in task_main */
|
||||
g_dev = this;
|
||||
|
@ -1264,13 +1281,14 @@ PX4IO::print_status()
|
|||
printf("%u bytes free\n",
|
||||
io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FREEMEM));
|
||||
uint16_t flags = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS);
|
||||
printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s%s\n",
|
||||
printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s%s%s\n",
|
||||
flags,
|
||||
((flags & PX4IO_P_STATUS_FLAGS_ARMED) ? " ARMED" : ""),
|
||||
((flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) ? " OVERRIDE" : ""),
|
||||
((flags & PX4IO_P_STATUS_FLAGS_RC_OK) ? " RC_OK" : " RC_FAIL"),
|
||||
((flags & PX4IO_P_STATUS_FLAGS_RC_PPM) ? " PPM" : ""),
|
||||
((flags & PX4IO_P_STATUS_FLAGS_RC_DSM) ? " DSM" : ""),
|
||||
(((flags & PX4IO_P_STATUS_FLAGS_RC_DSM) && (!(flags & PX4IO_P_STATUS_FLAGS_RC_DSM11))) ? " DSM10" : ""),
|
||||
(((flags & PX4IO_P_STATUS_FLAGS_RC_DSM) && (flags & PX4IO_P_STATUS_FLAGS_RC_DSM11)) ? " DSM11" : ""),
|
||||
((flags & PX4IO_P_STATUS_FLAGS_RC_SBUS) ? " SBUS" : ""),
|
||||
((flags & PX4IO_P_STATUS_FLAGS_FMU_OK) ? " FMU_OK" : " FMU_FAIL"),
|
||||
((flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) ? " RAW_PPM" : ""),
|
||||
|
@ -1373,7 +1391,8 @@ PX4IO::print_status()
|
|||
}
|
||||
|
||||
int
|
||||
PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
|
||||
PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
|
||||
/* Make it obvious that file * isn't used here */
|
||||
{
|
||||
int ret = OK;
|
||||
|
||||
|
@ -1425,6 +1444,26 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
|
|||
*(unsigned *)arg = _max_actuators;
|
||||
break;
|
||||
|
||||
case DSM_BIND_START:
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down);
|
||||
usleep(500000);
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out);
|
||||
usleep(1000);
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up);
|
||||
usleep(100000);
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4));
|
||||
break;
|
||||
|
||||
case DSM_BIND_STOP:
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down);
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart);
|
||||
usleep(500000);
|
||||
break;
|
||||
|
||||
case DSM_BIND_POWER_UP:
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up);
|
||||
break;
|
||||
|
||||
case PWM_SERVO_SET(0) ... PWM_SERVO_SET(PWM_OUTPUT_MAX_CHANNELS - 1): {
|
||||
|
||||
/* TODO: we could go lower for e.g. TurboPWM */
|
||||
|
@ -1467,18 +1506,31 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
|
|||
break;
|
||||
}
|
||||
|
||||
case GPIO_RESET:
|
||||
ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, 0);
|
||||
case GPIO_RESET: {
|
||||
uint32_t bits = (1 << _max_relays) - 1;
|
||||
/* don't touch relay1 if it's controlling RX vcc */
|
||||
if (_dsm_vcc_ctl)
|
||||
bits &= ~PX4IO_RELAY1;
|
||||
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, bits, 0);
|
||||
break;
|
||||
}
|
||||
|
||||
case GPIO_SET:
|
||||
arg &= ((1 << _max_relays) - 1);
|
||||
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, 0, arg);
|
||||
/* don't touch relay1 if it's controlling RX vcc */
|
||||
if (_dsm_vcc_ctl & (arg & PX4IO_RELAY1))
|
||||
ret = -EINVAL;
|
||||
else
|
||||
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, 0, arg);
|
||||
break;
|
||||
|
||||
case GPIO_CLEAR:
|
||||
arg &= ((1 << _max_relays) - 1);
|
||||
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, arg, 0);
|
||||
/* don't touch relay1 if it's controlling RX vcc */
|
||||
if (_dsm_vcc_ctl & (arg & PX4IO_RELAY1))
|
||||
ret = -EINVAL;
|
||||
else
|
||||
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, arg, 0);
|
||||
break;
|
||||
|
||||
case GPIO_GET:
|
||||
|
@ -1646,9 +1698,64 @@ start(int argc, char *argv[])
|
|||
errx(1, "driver init failed");
|
||||
}
|
||||
|
||||
int dsm_vcc_ctl;
|
||||
|
||||
if (param_get(param_find("RC_RL1_DSM_VCC"), &dsm_vcc_ctl) == OK) {
|
||||
if (dsm_vcc_ctl) {
|
||||
g_dev->set_dsm_vcc_ctl(true);
|
||||
g_dev->ioctl(nullptr, DSM_BIND_POWER_UP, 0);
|
||||
}
|
||||
}
|
||||
exit(0);
|
||||
}
|
||||
|
||||
void
|
||||
bind(int argc, char *argv[])
|
||||
{
|
||||
int pulses;
|
||||
|
||||
if (g_dev == nullptr)
|
||||
errx(1, "px4io must be started first");
|
||||
|
||||
if (!g_dev->get_dsm_vcc_ctl())
|
||||
errx(1, "DSM bind feature not enabled");
|
||||
|
||||
if (argc < 3)
|
||||
errx(0, "needs argument, use dsm2 or dsmx");
|
||||
|
||||
if (!strcmp(argv[2], "dsm2"))
|
||||
pulses = 3;
|
||||
else if (!strcmp(argv[2], "dsmx"))
|
||||
pulses = 7;
|
||||
else
|
||||
errx(1, "unknown parameter %s, use dsm2 or dsmx", argv[2]);
|
||||
|
||||
/* Open console directly to grab CTRL-C signal */
|
||||
int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY);
|
||||
if (!console)
|
||||
errx(1, "failed opening console");
|
||||
|
||||
warnx("This command will only bind DSM if satellite VCC (red wire) is controlled by relay 1.");
|
||||
warnx("Press CTRL-C or 'c' when done.");
|
||||
|
||||
g_dev->ioctl(nullptr, DSM_BIND_START, pulses);
|
||||
|
||||
for (;;) {
|
||||
usleep(500000L);
|
||||
/* Check if user wants to quit */
|
||||
char c;
|
||||
if (read(console, &c, 1) == 1) {
|
||||
if (c == 0x03 || c == 0x63) {
|
||||
warnx("Done\n");
|
||||
g_dev->ioctl(nullptr, DSM_BIND_STOP, 0);
|
||||
g_dev->ioctl(nullptr, DSM_BIND_POWER_UP, 0);
|
||||
close(console);
|
||||
exit(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
test(void)
|
||||
{
|
||||
|
@ -1658,7 +1765,7 @@ test(void)
|
|||
int direction = 1;
|
||||
int ret;
|
||||
|
||||
fd = open("/dev/px4io", O_WRONLY);
|
||||
fd = open(PX4IO_DEVICE_PATH, O_WRONLY);
|
||||
|
||||
if (fd < 0)
|
||||
err(1, "failed to open device");
|
||||
|
@ -1895,7 +2002,6 @@ px4io_main(int argc, char *argv[])
|
|||
* doesn't reference filp in ioctl()
|
||||
*/
|
||||
g_dev->ioctl(NULL, PX4IO_INAIR_RESTART_ENABLE, 1);
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
@ -1928,7 +2034,7 @@ px4io_main(int argc, char *argv[])
|
|||
/* we can cheat and call the driver directly, as it
|
||||
* doesn't reference filp in ioctl()
|
||||
*/
|
||||
int ret = g_dev->ioctl(NULL, PX4IO_SET_DEBUG, level);
|
||||
int ret = g_dev->ioctl(nullptr, PX4IO_SET_DEBUG, level);
|
||||
if (ret != 0) {
|
||||
printf("SET_DEBUG failed - %d\n", ret);
|
||||
exit(1);
|
||||
|
@ -1950,6 +2056,9 @@ px4io_main(int argc, char *argv[])
|
|||
if (!strcmp(argv[1], "monitor"))
|
||||
monitor();
|
||||
|
||||
out:
|
||||
errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug', 'recovery', 'limit', 'current', 'failsafe' or 'update'");
|
||||
if (!strcmp(argv[1], "bind"))
|
||||
bind(argc, argv);
|
||||
|
||||
out:
|
||||
errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug', 'recovery', 'limit', 'current', 'failsafe', 'bind', or 'update'");
|
||||
}
|
||||
|
|
|
@ -78,7 +78,7 @@ device::Device
|
|||
}
|
||||
|
||||
PX4IO_I2C::PX4IO_I2C(int bus, uint8_t address) :
|
||||
I2C("PX4IO_i2c", nullptr, bus, address, 400000)
|
||||
I2C("PX4IO_i2c", nullptr, bus, address, 320000)
|
||||
{
|
||||
_retries = 3;
|
||||
}
|
||||
|
|
|
@ -661,10 +661,10 @@ int KalmanNav::correctPos()
|
|||
Vector y(6);
|
||||
y(0) = _gps.vel_n_m_s - vN;
|
||||
y(1) = _gps.vel_e_m_s - vE;
|
||||
y(2) = double(_gps.lat) - lat * 1.0e7 * M_RAD_TO_DEG;
|
||||
y(3) = double(_gps.lon) - lon * 1.0e7 * M_RAD_TO_DEG;
|
||||
y(4) = double(_gps.alt) / 1.0e3 - alt;
|
||||
y(5) = double(_sensors.baro_alt_meter) - alt;
|
||||
y(2) = double(_gps.lat) - double(lat) * 1.0e7 * M_RAD_TO_DEG;
|
||||
y(3) = double(_gps.lon) - double(lon) * 1.0e7 * M_RAD_TO_DEG;
|
||||
y(4) = _gps.alt / 1.0e3f - alt;
|
||||
y(5) = _sensors.baro_alt_meter - alt;
|
||||
|
||||
// compute correction
|
||||
// http://en.wikipedia.org/wiki/Extended_Kalman_filter
|
||||
|
@ -698,7 +698,7 @@ int KalmanNav::correctPos()
|
|||
vD += xCorrect(VD);
|
||||
lat += double(xCorrect(LAT));
|
||||
lon += double(xCorrect(LON));
|
||||
alt += double(xCorrect(ALT));
|
||||
alt += xCorrect(ALT);
|
||||
|
||||
// update state covariance
|
||||
// http://en.wikipedia.org/wiki/Extended_Kalman_filter
|
||||
|
@ -710,7 +710,7 @@ int KalmanNav::correctPos()
|
|||
static int counter = 0;
|
||||
if (beta > _faultPos.get() && (counter % 10 == 0)) {
|
||||
warnx("fault in gps: beta = %8.4f", (double)beta);
|
||||
warnx("Y/N: vN: %8.4f, vE: %8.4f, lat: %8.4f, lon: %8.4f, alt: %8.4f",
|
||||
warnx("Y/N: vN: %8.4f, vE: %8.4f, lat: %8.4f, lon: %8.4f, alt: %8.4f, baro: %8.4f",
|
||||
double(y(0) / sqrtf(RPos(0, 0))),
|
||||
double(y(1) / sqrtf(RPos(1, 1))),
|
||||
double(y(2) / sqrtf(RPos(2, 2))),
|
||||
|
|
|
@ -1389,6 +1389,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
uint64_t start_time = hrt_absolute_time();
|
||||
uint64_t failsave_ll_start_time = 0;
|
||||
|
||||
enum VEHICLE_MANUAL_SAS_MODE manual_sas_mode;
|
||||
bool state_changed = true;
|
||||
bool param_init_forced = true;
|
||||
|
||||
|
@ -1828,8 +1829,9 @@ int commander_thread_main(int argc, char *argv[])
|
|||
|
||||
} else if (sp_man.manual_sas_switch < -STICK_ON_OFF_LIMIT) {
|
||||
|
||||
/* bottom stick position, set altitude hold */
|
||||
current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ALTITUDE;
|
||||
/* bottom stick position, set default */
|
||||
/* this MUST be mapped to extremal position to switch easy in case of emergency */
|
||||
current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS;
|
||||
|
||||
} else if (sp_man.manual_sas_switch > STICK_ON_OFF_LIMIT) {
|
||||
|
||||
|
@ -1837,8 +1839,14 @@ int commander_thread_main(int argc, char *argv[])
|
|||
current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_SIMPLE;
|
||||
|
||||
} else {
|
||||
/* center stick position, set default */
|
||||
current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS;
|
||||
/* center stick position, set altitude hold */
|
||||
current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ALTITUDE;
|
||||
}
|
||||
|
||||
if (current_status.manual_sas_mode != manual_sas_mode) {
|
||||
/* publish SAS mode changes immediately */
|
||||
manual_sas_mode = current_status.manual_sas_mode;
|
||||
state_changed = true;
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -1849,8 +1857,10 @@ int commander_thread_main(int argc, char *argv[])
|
|||
(current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
|
||||
(current_status.system_type == VEHICLE_TYPE_OCTOROTOR)
|
||||
) &&
|
||||
((sp_man.yaw < -STICK_ON_OFF_LIMIT)) &&
|
||||
(sp_man.throttle < STICK_THRUST_RANGE * 0.2f)) {
|
||||
current_status.flag_control_manual_enabled &&
|
||||
current_status.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS &&
|
||||
sp_man.yaw < -STICK_ON_OFF_LIMIT &&
|
||||
sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {
|
||||
if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
|
||||
update_state_machine_disarm(stat_pub, ¤t_status, mavlink_fd);
|
||||
stick_on_counter = 0;
|
||||
|
@ -1862,7 +1872,10 @@ int commander_thread_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
/* check if left stick is in lower right position --> arm */
|
||||
if (sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.2f) {
|
||||
if (current_status.flag_control_manual_enabled &&
|
||||
current_status.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS &&
|
||||
sp_man.yaw > STICK_ON_OFF_LIMIT &&
|
||||
sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {
|
||||
if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
|
||||
update_state_machine_arm(stat_pub, ¤t_status, mavlink_fd);
|
||||
stick_on_counter = 0;
|
||||
|
|
|
@ -53,11 +53,7 @@
|
|||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <poll.h>
|
||||
#include <drivers/drv_gpio.h>
|
||||
|
||||
#define PX4IO_RELAY1 (1<<0)
|
||||
#define PX4IO_RELAY2 (1<<1)
|
||||
#define PX4IO_ACC1 (1<<2)
|
||||
#define PX4IO_ACC2 (1<<3)
|
||||
#include <modules/px4iofirmware/protocol.h>
|
||||
|
||||
struct gpio_led_s {
|
||||
struct work_s work;
|
||||
|
@ -186,10 +182,9 @@ void gpio_led_start(FAR void *arg)
|
|||
char *gpio_dev;
|
||||
|
||||
if (priv->use_io) {
|
||||
gpio_dev = "/dev/px4io";
|
||||
|
||||
gpio_dev = PX4IO_DEVICE_PATH;
|
||||
} else {
|
||||
gpio_dev = "/dev/px4fmu";
|
||||
gpio_dev = PX4FMU_DEVICE_PATH;
|
||||
}
|
||||
|
||||
/* open GPIO device */
|
||||
|
@ -203,6 +198,7 @@ void gpio_led_start(FAR void *arg)
|
|||
}
|
||||
|
||||
/* configure GPIO pin */
|
||||
/* px4fmu only, px4io doesn't support GPIO_SET_OUTPUT and will ignore */
|
||||
ioctl(priv->gpio_fd, GPIO_SET_OUTPUT, priv->pin);
|
||||
|
||||
/* subscribe to vehicle status topic */
|
||||
|
@ -263,7 +259,6 @@ void gpio_led_cycle(FAR void *arg)
|
|||
|
||||
if (led_state_new) {
|
||||
ioctl(priv->gpio_fd, GPIO_SET, priv->pin);
|
||||
|
||||
} else {
|
||||
ioctl(priv->gpio_fd, GPIO_CLEAR, priv->pin);
|
||||
}
|
||||
|
|
|
@ -373,7 +373,7 @@ void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_
|
|||
dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, (float)global_pos->lat * 1e-7f, (float)global_pos->lon * 1e-7f, global_pos->alt);
|
||||
|
||||
} else if (coordinate_frame == (int)MAV_FRAME_GLOBAL_RELATIVE_ALT) {
|
||||
dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, global_pos->lat, global_pos->lon, global_pos->relative_alt);
|
||||
dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, (float)global_pos->lat * 1e-7f, (float)global_pos->lon * 1e-7f, global_pos->relative_alt);
|
||||
|
||||
} else if (coordinate_frame == (int)MAV_FRAME_LOCAL_ENU || coordinate_frame == (int)MAV_FRAME_LOCAL_NED) {
|
||||
dist = mavlink_wpm_distance_to_point_local(wpm->current_active_wp_id, local_pos->x, local_pos->y, local_pos->z);
|
||||
|
|
|
@ -95,9 +95,16 @@ controls_tick() {
|
|||
*/
|
||||
|
||||
perf_begin(c_gather_dsm);
|
||||
bool dsm_updated = dsm_input(r_raw_rc_values, &r_raw_rc_count);
|
||||
if (dsm_updated)
|
||||
uint16_t temp_count = r_raw_rc_count;
|
||||
bool dsm_updated = dsm_input(r_raw_rc_values, &temp_count);
|
||||
if (dsm_updated) {
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM;
|
||||
r_raw_rc_count = temp_count & 0x7fff;
|
||||
if (temp_count & 0x8000)
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM11;
|
||||
else
|
||||
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_RC_DSM11;
|
||||
}
|
||||
perf_end(c_gather_dsm);
|
||||
|
||||
perf_begin(c_gather_sbus);
|
||||
|
|
|
@ -40,6 +40,7 @@
|
|||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/arch.h>
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
|
@ -101,6 +102,41 @@ dsm_init(const char *device)
|
|||
return dsm_fd;
|
||||
}
|
||||
|
||||
void
|
||||
dsm_bind(uint16_t cmd, int pulses)
|
||||
{
|
||||
const uint32_t usart1RxAsOutp = GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN10;
|
||||
|
||||
if (dsm_fd < 0)
|
||||
return;
|
||||
|
||||
switch (cmd) {
|
||||
case dsm_bind_power_down:
|
||||
// power down DSM satellite
|
||||
POWER_RELAY1(0);
|
||||
break;
|
||||
case dsm_bind_power_up:
|
||||
POWER_RELAY1(1);
|
||||
dsm_guess_format(true);
|
||||
break;
|
||||
case dsm_bind_set_rx_out:
|
||||
stm32_configgpio(usart1RxAsOutp);
|
||||
break;
|
||||
case dsm_bind_send_pulses:
|
||||
for (int i = 0; i < pulses; i++) {
|
||||
stm32_gpiowrite(usart1RxAsOutp, false);
|
||||
up_udelay(50);
|
||||
stm32_gpiowrite(usart1RxAsOutp, true);
|
||||
up_udelay(50);
|
||||
}
|
||||
break;
|
||||
case dsm_bind_reinit_uart:
|
||||
// Restore USART rx pin
|
||||
stm32_configgpio(GPIO_USART1_RX);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
bool
|
||||
dsm_input(uint16_t *values, uint16_t *num_values)
|
||||
{
|
||||
|
@ -218,7 +254,7 @@ dsm_guess_format(bool reset)
|
|||
|
||||
/*
|
||||
* Iterate the set of sensible sniffed channel sets and see whether
|
||||
* decoding in 10 or 11-bit mode has yielded anything we recognise.
|
||||
* decoding in 10 or 11-bit mode has yielded anything we recognize.
|
||||
*
|
||||
* XXX Note that due to what seem to be bugs in the DSM2 high-resolution
|
||||
* stream, we may want to sniff for longer in some cases when we think we
|
||||
|
@ -349,6 +385,9 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
|
|||
values[channel] = value;
|
||||
}
|
||||
|
||||
if (channel_shift == 11)
|
||||
*num_values |= 0x8000;
|
||||
|
||||
/*
|
||||
* XXX Note that we may be in failsafe here; we need to work out how to detect that.
|
||||
*/
|
||||
|
|
|
@ -106,6 +106,7 @@
|
|||
#define PX4IO_P_STATUS_FLAGS_ARM_SYNC (1 << 9) /* the arming state between IO and FMU is in sync */
|
||||
#define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 10) /* initialisation of the IO completed without error */
|
||||
#define PX4IO_P_STATUS_FLAGS_FAILSAFE (1 << 11) /* failsafe is active */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_DSM11 (1 << 12) /* DSM input is 11 bit data */
|
||||
|
||||
#define PX4IO_P_STATUS_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */
|
||||
#define PX4IO_P_STATUS_ALARMS_VBATT_LOW (1 << 0) /* [1] VBatt is very close to regulator dropout */
|
||||
|
@ -169,7 +170,14 @@
|
|||
|
||||
#define PX4IO_P_SETUP_VBATT_SCALE 6 /* [1] battery voltage correction factor (float) */
|
||||
#define PX4IO_P_SETUP_VSERVO_SCALE 6 /* [2] servo voltage correction factor (float) */
|
||||
/* 7 */
|
||||
#define PX4IO_P_SETUP_DSM 7 /* DSM bind state */
|
||||
enum { /* DSM bind states */
|
||||
dsm_bind_power_down = 0,
|
||||
dsm_bind_power_up,
|
||||
dsm_bind_set_rx_out,
|
||||
dsm_bind_send_pulses,
|
||||
dsm_bind_reinit_uart
|
||||
};
|
||||
/* 8 */
|
||||
#define PX4IO_P_SETUP_SET_DEBUG 9 /* debug level for IO board */
|
||||
|
||||
|
|
|
@ -200,6 +200,7 @@ extern void controls_init(void);
|
|||
extern void controls_tick(void);
|
||||
extern int dsm_init(const char *device);
|
||||
extern bool dsm_input(uint16_t *values, uint16_t *num_values);
|
||||
extern void dsm_bind(uint16_t cmd, int pulses);
|
||||
extern int sbus_init(const char *device);
|
||||
extern bool sbus_input(uint16_t *values, uint16_t *num_values);
|
||||
|
||||
|
|
|
@ -360,16 +360,16 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
|
|||
value &= PX4IO_P_SETUP_RELAYS_VALID;
|
||||
r_setup_relays = value;
|
||||
#ifdef POWER_RELAY1
|
||||
POWER_RELAY1(value & (1 << 0) ? 1 : 0);
|
||||
POWER_RELAY1((value & PX4IO_P_SETUP_RELAYS_POWER1) ? 1 : 0);
|
||||
#endif
|
||||
#ifdef POWER_RELAY2
|
||||
POWER_RELAY2(value & (1 << 1) ? 1 : 0);
|
||||
POWER_RELAY2((value & PX4IO_P_SETUP_RELAYS_POWER2) ? 1 : 0);
|
||||
#endif
|
||||
#ifdef POWER_ACC1
|
||||
POWER_ACC1(value & (1 << 2) ? 1 : 0);
|
||||
POWER_ACC1((value & PX4IO_P_SETUP_RELAYS_ACC1) ? 1 : 0);
|
||||
#endif
|
||||
#ifdef POWER_ACC2
|
||||
POWER_ACC2(value & (1 << 3) ? 1 : 0);
|
||||
POWER_ACC2((value & PX4IO_P_SETUP_RELAYS_ACC2) ? 1 : 0);
|
||||
#endif
|
||||
break;
|
||||
|
||||
|
@ -382,6 +382,10 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
|
|||
isr_debug(0, "set debug %u\n", (unsigned)r_page_setup[PX4IO_P_SETUP_SET_DEBUG]);
|
||||
break;
|
||||
|
||||
case PX4IO_P_SETUP_DSM:
|
||||
dsm_bind(value & 0x0f, (value >> 4) & 7);
|
||||
break;
|
||||
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
|
|
@ -72,6 +72,7 @@
|
|||
#include <uORB/topics/vehicle_local_position.h>
|
||||
#include <uORB/topics/vehicle_local_position_setpoint.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_global_position_setpoint.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
#include <uORB/topics/vehicle_vicon_position.h>
|
||||
#include <uORB/topics/optical_flow.h>
|
||||
|
@ -615,7 +616,7 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
|
||||
/* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */
|
||||
/* number of messages */
|
||||
const ssize_t fdsc = 18;
|
||||
const ssize_t fdsc = 19;
|
||||
/* Sanity check variable and index */
|
||||
ssize_t fdsc_count = 0;
|
||||
/* file descriptors to wait for */
|
||||
|
@ -637,6 +638,7 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
struct vehicle_local_position_s local_pos;
|
||||
struct vehicle_local_position_setpoint_s local_pos_sp;
|
||||
struct vehicle_global_position_s global_pos;
|
||||
struct vehicle_global_position_setpoint_s global_pos_sp;
|
||||
struct vehicle_gps_position_s gps_pos;
|
||||
struct vehicle_vicon_position_s vicon_pos;
|
||||
struct optical_flow_s flow;
|
||||
|
@ -660,6 +662,7 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
int local_pos_sub;
|
||||
int local_pos_sp_sub;
|
||||
int global_pos_sub;
|
||||
int global_pos_sp_sub;
|
||||
int gps_pos_sub;
|
||||
int vicon_pos_sub;
|
||||
int flow_sub;
|
||||
|
@ -689,6 +692,7 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
struct log_ARSP_s log_ARSP;
|
||||
struct log_FLOW_s log_FLOW;
|
||||
struct log_GPOS_s log_GPOS;
|
||||
struct log_GPSP_s log_GPSP;
|
||||
struct log_ESC_s log_ESC;
|
||||
} body;
|
||||
} log_msg = {
|
||||
|
@ -775,6 +779,12 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
fds[fdsc_count].events = POLLIN;
|
||||
fdsc_count++;
|
||||
|
||||
/* --- GLOBAL POSITION SETPOINT--- */
|
||||
subs.global_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
|
||||
fds[fdsc_count].fd = subs.global_pos_sp_sub;
|
||||
fds[fdsc_count].events = POLLIN;
|
||||
fdsc_count++;
|
||||
|
||||
/* --- VICON POSITION --- */
|
||||
subs.vicon_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position));
|
||||
fds[fdsc_count].fd = subs.vicon_pos_sub;
|
||||
|
@ -1077,6 +1087,25 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
LOGBUFFER_WRITE_AND_COUNT(GPOS);
|
||||
}
|
||||
|
||||
/* --- GLOBAL POSITION SETPOINT --- */
|
||||
if (fds[ifds++].revents & POLLIN) {
|
||||
orb_copy(ORB_ID(vehicle_global_position_setpoint), subs.global_pos_sp_sub, &buf.global_pos_sp);
|
||||
log_msg.msg_type = LOG_GPSP_MSG;
|
||||
log_msg.body.log_GPSP.altitude_is_relative = buf.global_pos_sp.altitude_is_relative;
|
||||
log_msg.body.log_GPSP.lat = buf.global_pos_sp.lat;
|
||||
log_msg.body.log_GPSP.lon = buf.global_pos_sp.lon;
|
||||
log_msg.body.log_GPSP.altitude = buf.global_pos_sp.altitude;
|
||||
log_msg.body.log_GPSP.yaw = buf.global_pos_sp.yaw;
|
||||
log_msg.body.log_GPSP.loiter_radius = buf.global_pos_sp.loiter_radius;
|
||||
log_msg.body.log_GPSP.loiter_direction = buf.global_pos_sp.loiter_direction;
|
||||
log_msg.body.log_GPSP.nav_cmd = buf.global_pos_sp.nav_cmd;
|
||||
log_msg.body.log_GPSP.param1 = buf.global_pos_sp.param1;
|
||||
log_msg.body.log_GPSP.param2 = buf.global_pos_sp.param2;
|
||||
log_msg.body.log_GPSP.param3 = buf.global_pos_sp.param3;
|
||||
log_msg.body.log_GPSP.param4 = buf.global_pos_sp.param4;
|
||||
LOGBUFFER_WRITE_AND_COUNT(GPSP);
|
||||
}
|
||||
|
||||
/* --- VICON POSITION --- */
|
||||
if (fds[ifds++].revents & POLLIN) {
|
||||
orb_copy(ORB_ID(vehicle_vicon_position), subs.vicon_pos_sub, &buf.vicon_pos);
|
||||
|
|
|
@ -149,15 +149,15 @@ struct log_ATTC_s {
|
|||
/* --- STAT - VEHICLE STATE --- */
|
||||
#define LOG_STAT_MSG 10
|
||||
struct log_STAT_s {
|
||||
unsigned char state;
|
||||
unsigned char flight_mode;
|
||||
unsigned char manual_control_mode;
|
||||
unsigned char manual_sas_mode;
|
||||
unsigned char armed;
|
||||
uint8_t state;
|
||||
uint8_t flight_mode;
|
||||
uint8_t manual_control_mode;
|
||||
uint8_t manual_sas_mode;
|
||||
uint8_t armed;
|
||||
float battery_voltage;
|
||||
float battery_current;
|
||||
float battery_remaining;
|
||||
unsigned char battery_warning;
|
||||
uint8_t battery_warning;
|
||||
};
|
||||
|
||||
/* --- RC - RC INPUT CHANNELS --- */
|
||||
|
@ -210,13 +210,29 @@ struct log_GPOS_s {
|
|||
float vel_d;
|
||||
};
|
||||
|
||||
/* --- GPSP - GLOBAL POSITION SETPOINT --- */
|
||||
#define LOG_GPSP_MSG 17
|
||||
struct log_GPSP_s {
|
||||
uint8_t altitude_is_relative;
|
||||
int32_t lat;
|
||||
int32_t lon;
|
||||
float altitude;
|
||||
float yaw;
|
||||
float loiter_radius;
|
||||
int8_t loiter_direction;
|
||||
uint8_t nav_cmd;
|
||||
float param1;
|
||||
float param2;
|
||||
float param3;
|
||||
float param4;
|
||||
};
|
||||
|
||||
/* --- ESC - ESC STATE --- */
|
||||
#define LOG_ESC_MSG 64
|
||||
#define LOG_ESC_MSG 18
|
||||
struct log_ESC_s {
|
||||
uint16_t counter;
|
||||
uint8_t esc_count;
|
||||
uint8_t esc_connectiontype;
|
||||
|
||||
uint8_t esc_num;
|
||||
uint16_t esc_address;
|
||||
uint16_t esc_version;
|
||||
|
@ -227,6 +243,7 @@ struct log_ESC_s {
|
|||
float esc_setpoint;
|
||||
uint16_t esc_setpoint_raw;
|
||||
};
|
||||
|
||||
#pragma pack(pop)
|
||||
|
||||
/* construct list of all message formats */
|
||||
|
@ -248,6 +265,7 @@ static const struct log_format_s log_formats[] = {
|
|||
LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
|
||||
LOG_FORMAT(FLOW, "hhfffBB", "RawX,RawY,CompX,CompY,Dist,Q,SensID"),
|
||||
LOG_FORMAT(GPOS, "LLffff", "Lat,Lon,Alt,VelN,VelE,VelD"),
|
||||
LOG_FORMAT(GPSP, "BLLfffbBffff", "AltRel,Lat,Lon,Alt,Yaw,LoiterR,LoiterDir,NavCmd,P1,P2,P3,P4"),
|
||||
LOG_FORMAT(ESC, "HBBBHHHHHHfH", "Counter,NumESC,Conn,No,Version,Adr,Volt,Amp,RPM,Temp,SetP,SetPRAW"),
|
||||
};
|
||||
|
||||
|
|
|
@ -155,6 +155,7 @@ PARAM_DEFINE_FLOAT(RC14_REV, 1.0f);
|
|||
PARAM_DEFINE_FLOAT(RC14_DZ, 0.0f);
|
||||
|
||||
PARAM_DEFINE_INT32(RC_TYPE, 1); /** 1 = FUTABA, 2 = Spektrum, 3 = Graupner HoTT, 4 = Turnigy 9x */
|
||||
PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */
|
||||
|
||||
/* default is conversion factor for the PX4IO / PX4IOAR board, the factor for PX4FMU standalone is different */
|
||||
PARAM_DEFINE_FLOAT(BAT_V_SCALING, (3.3f * 52.0f / 5.0f / 4095.0f));
|
||||
|
|
|
@ -230,6 +230,8 @@ private:
|
|||
float rc_scale_flaps;
|
||||
|
||||
float battery_voltage_scaling;
|
||||
|
||||
int rc_rl1_DSM_VCC_control;
|
||||
} _parameters; /**< local copies of interesting parameters */
|
||||
|
||||
struct {
|
||||
|
@ -278,6 +280,8 @@ private:
|
|||
param_t rc_scale_flaps;
|
||||
|
||||
param_t battery_voltage_scaling;
|
||||
|
||||
param_t rc_rl1_DSM_VCC_control;
|
||||
} _parameter_handles; /**< handles for interesting parameters */
|
||||
|
||||
|
||||
|
@ -514,6 +518,9 @@ Sensors::Sensors() :
|
|||
|
||||
_parameter_handles.battery_voltage_scaling = param_find("BAT_V_SCALING");
|
||||
|
||||
/* DSM VCC relay control */
|
||||
_parameter_handles.rc_rl1_DSM_VCC_control = param_find("RC_RL1_DSM_VCC");
|
||||
|
||||
/* fetch initial parameter values */
|
||||
parameters_update();
|
||||
}
|
||||
|
@ -730,6 +737,11 @@ Sensors::parameters_update()
|
|||
warnx("Failed updating voltage scaling param");
|
||||
}
|
||||
|
||||
/* relay 1 DSM VCC control */
|
||||
if (param_get(_parameter_handles.rc_rl1_DSM_VCC_control, &(_parameters.rc_rl1_DSM_VCC_control)) != OK) {
|
||||
warnx("Failed updating relay 1 DSM VCC control");
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
|
|
|
@ -63,7 +63,8 @@
|
|||
|
||||
enum ESC_VENDOR {
|
||||
ESC_VENDOR_GENERIC = 0, /**< generic ESC */
|
||||
ESC_VENDOR_MIKROKOPTER /**< Mikrokopter */
|
||||
ESC_VENDOR_MIKROKOPTER, /**< Mikrokopter */
|
||||
ESC_VENDOR_GRAUPNER_HOTT /**< Graupner HoTT ESC */
|
||||
};
|
||||
|
||||
enum ESC_CONNECTION_TYPE {
|
||||
|
|
|
@ -66,7 +66,7 @@ struct vehicle_global_position_setpoint_s
|
|||
float altitude; /**< altitude in meters */
|
||||
float yaw; /**< in radians NED -PI..+PI */
|
||||
float loiter_radius; /**< loiter radius in meters, 0 for a VTOL to hover */
|
||||
uint8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
|
||||
int8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
|
||||
enum NAV_CMD nav_cmd; /**< true if loitering is enabled */
|
||||
float param1;
|
||||
float param2;
|
||||
|
|
|
@ -92,7 +92,7 @@ int test_gpio(int argc, char *argv[])
|
|||
int fd;
|
||||
int ret = 0;
|
||||
|
||||
fd = open(GPIO_DEVICE_PATH, 0);
|
||||
fd = open(PX4IO_DEVICE_PATH, 0);
|
||||
|
||||
if (fd < 0) {
|
||||
printf("GPIO: open fail\n");
|
||||
|
|
Loading…
Reference in New Issue