mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Merged master into st24
This commit is contained in:
commit
4a8d20e2e5
@ -9,4 +9,3 @@ sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
set MIXER Viper
|
||||
|
||||
set FAILSAFE "-c567 -p 1000"
|
||||
|
||||
@ -21,6 +21,12 @@
|
||||
# Simulation setups
|
||||
#
|
||||
|
||||
if param compare SYS_AUTOSTART 901
|
||||
then
|
||||
sh /etc/init.d/901_bottle_drop_test.hil
|
||||
set MODE custom
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 1000
|
||||
then
|
||||
sh /etc/init.d/1000_rc_fw_easystar.hil
|
||||
|
||||
@ -13,3 +13,5 @@ ekf_att_pos_estimator start
|
||||
#
|
||||
fw_att_control start
|
||||
fw_pos_control_l1 start
|
||||
|
||||
bottle_drop start
|
||||
|
||||
@ -68,6 +68,11 @@ else
|
||||
fi
|
||||
fi
|
||||
|
||||
# Check for flow sensor
|
||||
if px4flow start
|
||||
then
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the sensor collection task.
|
||||
# IMPORTANT: this also loads param offsets
|
||||
|
||||
@ -52,21 +52,18 @@ M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 3 0 20000 -10000 -10000 10000
|
||||
|
||||
Gimbal / flaps / payload mixer for last four channels
|
||||
Inputs to the mixer come from channel group 2 (payload), channels 0
|
||||
(bay servo 1), 1 (bay servo 2) and 3 (drop release).
|
||||
-----------------------------------------------------
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 4 10000 10000 0 -10000 10000
|
||||
S: 2 0 10000 10000 0 -10000 10000
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 5 10000 10000 0 -10000 10000
|
||||
S: 2 1 10000 10000 0 -10000 10000
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 6 10000 10000 0 -10000 10000
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 7 10000 10000 0 -10000 10000
|
||||
S: 2 2 -10000 -10000 0 -10000 10000
|
||||
|
||||
@ -66,6 +66,6 @@ S: 2 1 10000 10000 0 -10000 10000
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 2 2 -10000 -10000 0 -10000 10000
|
||||
S: 2 2 -8000 -8000 0 -10000 10000
|
||||
|
||||
|
||||
|
||||
1
Tools/tests-host/.gitignore
vendored
1
Tools/tests-host/.gitignore
vendored
@ -1,5 +1,6 @@
|
||||
./obj/*
|
||||
mixer_test
|
||||
sf0x_test
|
||||
sbus2_test
|
||||
autodeclination_test
|
||||
st24_test
|
||||
|
||||
@ -3,7 +3,7 @@ CC=g++
|
||||
CFLAGS=-I. -I../../src/modules -I ../../src/include -I../../src/drivers \
|
||||
-I../../src -I../../src/lib -D__EXPORT="" -Dnullptr="0" -lm
|
||||
|
||||
all: mixer_test sbus2_test autodeclination_test st24_test
|
||||
all: mixer_test sbus2_test autodeclination_test st24_test sf0x_test
|
||||
|
||||
MIXER_FILES=../../src/systemcmds/tests/test_mixer.cpp \
|
||||
../../src/systemcmds/tests/test_conv.cpp \
|
||||
@ -24,6 +24,11 @@ ST24_FILES=../../src/lib/rc/st24.c \
|
||||
hrt.cpp \
|
||||
st24_test.cpp
|
||||
|
||||
SF0X_FILES= \
|
||||
hrt.cpp \
|
||||
sf0x_test.cpp \
|
||||
../../src/drivers/sf0x/sf0x_parser.cpp
|
||||
|
||||
AUTODECLINATION_FILES= ../../src/lib/geo_lookup/geo_mag_declination.c \
|
||||
hrt.cpp \
|
||||
autodeclination_test.cpp
|
||||
@ -34,6 +39,9 @@ mixer_test: $(MIXER_FILES)
|
||||
sbus2_test: $(SBUS2_FILES)
|
||||
$(CC) -o sbus2_test $(SBUS2_FILES) $(CFLAGS)
|
||||
|
||||
sf0x_test: $(SF0X_FILES)
|
||||
$(CC) -o sf0x_test $(SF0X_FILES) $(CFLAGS)
|
||||
|
||||
autodeclination_test: $(SBUS2_FILES)
|
||||
$(CC) -o autodeclination_test $(AUTODECLINATION_FILES) $(CFLAGS)
|
||||
|
||||
@ -43,4 +51,4 @@ st24_test: $(ST24_FILES)
|
||||
.PHONY: clean
|
||||
|
||||
clean:
|
||||
rm -f $(ODIR)/*.o *~ core $(INCDIR)/*~ mixer_test sbus2_test autodeclination_test st24_test
|
||||
rm -f $(ODIR)/*.o *~ core $(INCDIR)/*~ mixer_test sbus2_test autodeclination_test st24_test sf0x_test
|
||||
|
||||
65
Tools/tests-host/sf0x_test.cpp
Normal file
65
Tools/tests-host/sf0x_test.cpp
Normal file
@ -0,0 +1,65 @@
|
||||
|
||||
#include <unistd.h>
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include <drivers/sf0x/sf0x_parser.h>
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
warnx("SF0X test started");
|
||||
|
||||
int ret = 0;
|
||||
|
||||
const char LINE_MAX = 20;
|
||||
char _linebuf[LINE_MAX];
|
||||
_linebuf[0] = '\0';
|
||||
|
||||
const char *lines[] = {"0.01\r\n",
|
||||
"0.02\r\n",
|
||||
"0.03\r\n",
|
||||
"0.04\r\n",
|
||||
"0",
|
||||
".",
|
||||
"0",
|
||||
"5",
|
||||
"\r",
|
||||
"\n",
|
||||
"0",
|
||||
"3\r",
|
||||
"\n"
|
||||
"\r\n",
|
||||
"0.06",
|
||||
"\r\n"
|
||||
};
|
||||
|
||||
enum SF0X_PARSE_STATE state = SF0X_PARSE_STATE0_UNSYNC;
|
||||
float dist_m;
|
||||
char _parserbuf[LINE_MAX];
|
||||
unsigned _parsebuf_index = 0;
|
||||
|
||||
for (unsigned l = 0; l < sizeof(lines) / sizeof(lines[0]); l++) {
|
||||
|
||||
printf("\n%s", _linebuf);
|
||||
|
||||
int parse_ret;
|
||||
|
||||
for (int i = 0; i < strlen(lines[l]); i++) {
|
||||
parse_ret = sf0x_parser(lines[l][i], _parserbuf, &_parsebuf_index, &state, &dist_m);
|
||||
|
||||
if (parse_ret == 0) {
|
||||
printf("\nparsed: %f %s\n", dist_m, (parse_ret == 0) ? "OK" : "");
|
||||
}
|
||||
}
|
||||
|
||||
printf("%s", lines[l]);
|
||||
|
||||
}
|
||||
|
||||
warnx("test finished");
|
||||
|
||||
return ret;
|
||||
}
|
||||
@ -128,6 +128,11 @@ MODULES += lib/geo_lookup
|
||||
MODULES += lib/conversion
|
||||
MODULES += lib/launchdetection
|
||||
|
||||
#
|
||||
# OBC challenge
|
||||
#
|
||||
MODULES += modules/bottle_drop
|
||||
|
||||
#
|
||||
# Demo apps
|
||||
#
|
||||
|
||||
@ -189,6 +189,18 @@ UBX::configure(unsigned &baudrate)
|
||||
return 1;
|
||||
}
|
||||
|
||||
#ifdef UBX_CONFIGURE_SBAS
|
||||
/* send a SBAS message to set the SBAS options */
|
||||
memset(&_buf.payload_tx_cfg_sbas, 0, sizeof(_buf.payload_tx_cfg_sbas));
|
||||
_buf.payload_tx_cfg_sbas.mode = UBX_TX_CFG_SBAS_MODE;
|
||||
|
||||
send_message(UBX_MSG_CFG_SBAS, _buf.raw, sizeof(_buf.payload_tx_cfg_sbas));
|
||||
|
||||
if (wait_for_ack(UBX_MSG_CFG_SBAS, UBX_CONFIG_TIMEOUT, true) < 0) {
|
||||
return 1;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* configure message rates */
|
||||
/* the last argument is divisor for measurement rate (set by CFG RATE), i.e. 1 means 5Hz */
|
||||
|
||||
|
||||
@ -73,6 +73,7 @@
|
||||
#define UBX_ID_CFG_MSG 0x01
|
||||
#define UBX_ID_CFG_RATE 0x08
|
||||
#define UBX_ID_CFG_NAV5 0x24
|
||||
#define UBX_ID_CFG_SBAS 0x16
|
||||
#define UBX_ID_MON_VER 0x04
|
||||
#define UBX_ID_MON_HW 0x09
|
||||
|
||||
@ -89,6 +90,7 @@
|
||||
#define UBX_MSG_CFG_MSG ((UBX_CLASS_CFG) | UBX_ID_CFG_MSG << 8)
|
||||
#define UBX_MSG_CFG_RATE ((UBX_CLASS_CFG) | UBX_ID_CFG_RATE << 8)
|
||||
#define UBX_MSG_CFG_NAV5 ((UBX_CLASS_CFG) | UBX_ID_CFG_NAV5 << 8)
|
||||
#define UBX_MSG_CFG_SBAS ((UBX_CLASS_CFG) | UBX_ID_CFG_SBAS << 8)
|
||||
#define UBX_MSG_MON_HW ((UBX_CLASS_MON) | UBX_ID_MON_HW << 8)
|
||||
#define UBX_MSG_MON_VER ((UBX_CLASS_MON) | UBX_ID_MON_VER << 8)
|
||||
|
||||
@ -128,6 +130,11 @@
|
||||
#define UBX_TX_CFG_NAV5_DYNMODEL 7 /**< 0 Portable, 2 Stationary, 3 Pedestrian, 4 Automotive, 5 Sea, 6 Airborne <1g, 7 Airborne <2g, 8 Airborne <4g */
|
||||
#define UBX_TX_CFG_NAV5_FIXMODE 2 /**< 1 2D only, 2 3D only, 3 Auto 2D/3D */
|
||||
|
||||
/* TX CFG-SBAS message contents */
|
||||
#define UBX_TX_CFG_SBAS_MODE_ENABLED 1 /**< SBAS enabled */
|
||||
#define UBX_TX_CFG_SBAS_MODE_DISABLED 0 /**< SBAS disabled */
|
||||
#define UBX_TX_CFG_SBAS_MODE UBX_TX_CFG_SBAS_MODE_DISABLED /**< SBAS enabled or disabled */
|
||||
|
||||
/* TX CFG-MSG message contents */
|
||||
#define UBX_TX_CFG_MSG_RATE1_5HZ 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
|
||||
#define UBX_TX_CFG_MSG_RATE1_1HZ 0x05 /**< {0x00, 0x05, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
|
||||
@ -383,6 +390,15 @@ typedef struct {
|
||||
uint32_t reserved4;
|
||||
} ubx_payload_tx_cfg_nav5_t;
|
||||
|
||||
/* tx cfg-sbas */
|
||||
typedef struct {
|
||||
uint8_t mode;
|
||||
uint8_t usage;
|
||||
uint8_t maxSBAS;
|
||||
uint8_t scanmode2;
|
||||
uint32_t scanmode1;
|
||||
} ubx_payload_tx_cfg_sbas_t;
|
||||
|
||||
/* Tx CFG-MSG */
|
||||
typedef struct {
|
||||
union {
|
||||
@ -413,6 +429,7 @@ typedef union {
|
||||
ubx_payload_tx_cfg_prt_t payload_tx_cfg_prt;
|
||||
ubx_payload_tx_cfg_rate_t payload_tx_cfg_rate;
|
||||
ubx_payload_tx_cfg_nav5_t payload_tx_cfg_nav5;
|
||||
ubx_payload_tx_cfg_sbas_t payload_tx_cfg_sbas;
|
||||
ubx_payload_tx_cfg_msg_t payload_tx_cfg_msg;
|
||||
uint8_t raw[];
|
||||
} ubx_buf_t;
|
||||
|
||||
@ -392,7 +392,8 @@ HIL::task_main()
|
||||
if (fds[0].revents & POLLIN) {
|
||||
|
||||
/* get controls - must always do this to avoid spinning */
|
||||
orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _t_actuators, &_controls);
|
||||
orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
|
||||
ORB_ID(actuator_controls_1), _t_actuators, &_controls);
|
||||
|
||||
/* can we mix? */
|
||||
if (_mixers != nullptr) {
|
||||
|
||||
@ -37,6 +37,7 @@
|
||||
|
||||
MODULE_COMMAND = sf0x
|
||||
|
||||
SRCS = sf0x.cpp
|
||||
SRCS = sf0x.cpp \
|
||||
sf0x_parser.cpp
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
@ -72,6 +72,8 @@
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#include "sf0x_parser.h"
|
||||
|
||||
/* Configuration Constants */
|
||||
|
||||
/* oddly, ERROR is not defined for c++ */
|
||||
@ -120,6 +122,7 @@ private:
|
||||
int _fd;
|
||||
char _linebuf[10];
|
||||
unsigned _linebuf_index;
|
||||
enum SF0X_PARSE_STATE _parse_state;
|
||||
hrt_abstime _last_read;
|
||||
|
||||
orb_advert_t _range_finder_topic;
|
||||
@ -186,6 +189,7 @@ SF0X::SF0X(const char *port) :
|
||||
_collect_phase(false),
|
||||
_fd(-1),
|
||||
_linebuf_index(0),
|
||||
_parse_state(SF0X_PARSE_STATE0_UNSYNC),
|
||||
_last_read(0),
|
||||
_range_finder_topic(-1),
|
||||
_consecutive_fail_count(0),
|
||||
@ -200,12 +204,6 @@ SF0X::SF0X(const char *port) :
|
||||
warnx("FAIL: laser fd");
|
||||
}
|
||||
|
||||
/* tell it to stop auto-triggering */
|
||||
char stop_auto = ' ';
|
||||
(void)::write(_fd, &stop_auto, 1);
|
||||
usleep(100);
|
||||
(void)::write(_fd, &stop_auto, 1);
|
||||
|
||||
struct termios uart_config;
|
||||
|
||||
int termios_state;
|
||||
@ -520,20 +518,15 @@ SF0X::collect()
|
||||
/* clear buffer if last read was too long ago */
|
||||
uint64_t read_elapsed = hrt_elapsed_time(&_last_read);
|
||||
|
||||
/* timed out - retry */
|
||||
if (read_elapsed > (SF0X_CONVERSION_INTERVAL * 2)) {
|
||||
_linebuf_index = 0;
|
||||
}
|
||||
|
||||
/* the buffer for read chars is buflen minus null termination */
|
||||
unsigned readlen = sizeof(_linebuf) - 1;
|
||||
char readbuf[sizeof(_linebuf)];
|
||||
unsigned readlen = sizeof(readbuf) - 1;
|
||||
|
||||
/* read from the sensor (uart buffer) */
|
||||
ret = ::read(_fd, &_linebuf[_linebuf_index], readlen - _linebuf_index);
|
||||
ret = ::read(_fd, &readbuf[0], readlen);
|
||||
|
||||
if (ret < 0) {
|
||||
_linebuf[sizeof(_linebuf) - 1] = '\0';
|
||||
debug("read err: %d lbi: %d buf: %s", ret, (int)_linebuf_index, _linebuf);
|
||||
debug("read err: %d", ret);
|
||||
perf_count(_comms_errors);
|
||||
perf_end(_sample_perf);
|
||||
|
||||
@ -548,84 +541,23 @@ SF0X::collect()
|
||||
return -EAGAIN;
|
||||
}
|
||||
|
||||
/* let the write pointer point to the next free entry */
|
||||
_linebuf_index += ret;
|
||||
|
||||
_last_read = hrt_absolute_time();
|
||||
|
||||
/* require a reasonable amount of minimum bytes */
|
||||
if (_linebuf_index < 6) {
|
||||
/* we need at this format: x.xx\r\n */
|
||||
return -EAGAIN;
|
||||
|
||||
} else if (_linebuf[_linebuf_index - 2] != '\r' || _linebuf[_linebuf_index - 1] != '\n') {
|
||||
|
||||
if (_linebuf_index == readlen) {
|
||||
/* we have a full buffer, but no line ending - abort */
|
||||
_linebuf_index = 0;
|
||||
perf_count(_comms_errors);
|
||||
return -ENOMEM;
|
||||
} else {
|
||||
/* incomplete read, reschedule ourselves */
|
||||
return -EAGAIN;
|
||||
float si_units;
|
||||
bool valid = false;
|
||||
|
||||
for (unsigned i = 0; i < ret; i++) {
|
||||
if (OK == sf0x_parser(readbuf[i], _linebuf, &_linebuf_index, &_parse_state, &si_units)) {
|
||||
valid = true;
|
||||
}
|
||||
}
|
||||
|
||||
char *end;
|
||||
float si_units;
|
||||
bool valid;
|
||||
|
||||
/* enforce line ending */
|
||||
_linebuf[_linebuf_index] = '\0';
|
||||
|
||||
if (_linebuf[0] == '-' && _linebuf[1] == '-' && _linebuf[2] == '.') {
|
||||
si_units = -1.0f;
|
||||
valid = false;
|
||||
|
||||
} else {
|
||||
|
||||
/* we need to find a dot in the string, as we're missing the meters part else */
|
||||
valid = false;
|
||||
|
||||
/* wipe out partially read content from last cycle(s), check for dot */
|
||||
for (unsigned i = 0; i < (_linebuf_index - 2); i++) {
|
||||
if (_linebuf[i] == '\n') {
|
||||
/* wipe out any partial measurements */
|
||||
for (unsigned j = 0; j <= i; j++) {
|
||||
_linebuf[j] = ' ';
|
||||
}
|
||||
}
|
||||
|
||||
/* we need a digit before the dot and a dot for a valid number */
|
||||
if (i > 0 && ((_linebuf[i - 1] >= '0') && (_linebuf[i - 1] <= '9')) && (_linebuf[i] == '.')) {
|
||||
valid = true;
|
||||
}
|
||||
}
|
||||
|
||||
if (valid) {
|
||||
si_units = strtod(_linebuf, &end);
|
||||
|
||||
/* we require at least four characters for a valid number */
|
||||
if (end > _linebuf + 3) {
|
||||
valid = true;
|
||||
} else {
|
||||
si_units = -1.0f;
|
||||
valid = false;
|
||||
}
|
||||
}
|
||||
if (!valid) {
|
||||
return -EAGAIN;
|
||||
}
|
||||
|
||||
debug("val (float): %8.4f, raw: %s, valid: %s", (double)si_units, _linebuf, ((valid) ? "OK" : "NO"));
|
||||
|
||||
/* done with this chunk, resetting - even if invalid */
|
||||
_linebuf_index = 0;
|
||||
|
||||
/* if its invalid, there is no reason to forward the value */
|
||||
if (!valid) {
|
||||
perf_count(_comms_errors);
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
struct range_finder_report report;
|
||||
|
||||
/* this should be fairly close to the end of the measurement, so the best approximation of the time */
|
||||
|
||||
155
src/drivers/sf0x/sf0x_parser.cpp
Normal file
155
src/drivers/sf0x/sf0x_parser.cpp
Normal file
@ -0,0 +1,155 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2014 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 sf0x_parser.cpp
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* Driver for the Lightware SF0x laser rangefinder series
|
||||
*/
|
||||
|
||||
#include "sf0x_parser.h"
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
//#define SF0X_DEBUG
|
||||
|
||||
#ifdef SF0X_DEBUG
|
||||
#include <stdio.h>
|
||||
|
||||
const char *parser_state[] = {
|
||||
"0_UNSYNC",
|
||||
"1_SYNC",
|
||||
"2_GOT_DIGIT0",
|
||||
"3_GOT_DOT",
|
||||
"4_GOT_DIGIT1",
|
||||
"5_GOT_DIGIT2",
|
||||
"6_GOT_CARRIAGE_RETURN"
|
||||
};
|
||||
#endif
|
||||
|
||||
int sf0x_parser(char c, char *parserbuf, unsigned *parserbuf_index, enum SF0X_PARSE_STATE *state, float *dist)
|
||||
{
|
||||
int ret = -1;
|
||||
char *end;
|
||||
|
||||
switch (*state) {
|
||||
case SF0X_PARSE_STATE0_UNSYNC:
|
||||
if (c == '\n') {
|
||||
*state = SF0X_PARSE_STATE1_SYNC;
|
||||
(*parserbuf_index) = 0;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case SF0X_PARSE_STATE1_SYNC:
|
||||
if (c >= '0' && c <= '9') {
|
||||
*state = SF0X_PARSE_STATE2_GOT_DIGIT0;
|
||||
parserbuf[*parserbuf_index] = c;
|
||||
(*parserbuf_index)++;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case SF0X_PARSE_STATE2_GOT_DIGIT0:
|
||||
if (c >= '0' && c <= '9') {
|
||||
*state = SF0X_PARSE_STATE2_GOT_DIGIT0;
|
||||
parserbuf[*parserbuf_index] = c;
|
||||
(*parserbuf_index)++;
|
||||
|
||||
} else if (c == '.') {
|
||||
*state = SF0X_PARSE_STATE3_GOT_DOT;
|
||||
parserbuf[*parserbuf_index] = c;
|
||||
(*parserbuf_index)++;
|
||||
|
||||
} else {
|
||||
*state = SF0X_PARSE_STATE0_UNSYNC;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case SF0X_PARSE_STATE3_GOT_DOT:
|
||||
if (c >= '0' && c <= '9') {
|
||||
*state = SF0X_PARSE_STATE4_GOT_DIGIT1;
|
||||
parserbuf[*parserbuf_index] = c;
|
||||
(*parserbuf_index)++;
|
||||
|
||||
} else {
|
||||
*state = SF0X_PARSE_STATE0_UNSYNC;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case SF0X_PARSE_STATE4_GOT_DIGIT1:
|
||||
if (c >= '0' && c <= '9') {
|
||||
*state = SF0X_PARSE_STATE5_GOT_DIGIT2;
|
||||
parserbuf[*parserbuf_index] = c;
|
||||
(*parserbuf_index)++;
|
||||
|
||||
} else {
|
||||
*state = SF0X_PARSE_STATE0_UNSYNC;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case SF0X_PARSE_STATE5_GOT_DIGIT2:
|
||||
if (c == '\r') {
|
||||
*state = SF0X_PARSE_STATE6_GOT_CARRIAGE_RETURN;
|
||||
|
||||
} else {
|
||||
*state = SF0X_PARSE_STATE0_UNSYNC;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case SF0X_PARSE_STATE6_GOT_CARRIAGE_RETURN:
|
||||
if (c == '\n') {
|
||||
parserbuf[*parserbuf_index] = '\0';
|
||||
*dist = strtod(parserbuf, &end);
|
||||
*state = SF0X_PARSE_STATE1_SYNC;
|
||||
*parserbuf_index = 0;
|
||||
ret = 0;
|
||||
|
||||
} else {
|
||||
*state = SF0X_PARSE_STATE0_UNSYNC;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
#ifdef SF0X_DEBUG
|
||||
printf("state: SF0X_PARSE_STATE%s\n", parser_state[*state]);
|
||||
#endif
|
||||
|
||||
return ret;
|
||||
}
|
||||
@ -1,4 +1,4 @@
|
||||
/***************************************************************************
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
@ -30,43 +30,22 @@
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file offboard.h
|
||||
* @file sf0x_parser.cpp
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* Helper class for offboard commands
|
||||
*
|
||||
* @author Julian Oes <julian@oes.ch>
|
||||
* Declarations of parser for the Lightware SF0x laser rangefinder series
|
||||
*/
|
||||
|
||||
#ifndef NAVIGATOR_OFFBOARD_H
|
||||
#define NAVIGATOR_OFFBOARD_H
|
||||
|
||||
#include <controllib/blocks.hpp>
|
||||
#include <controllib/block/BlockParam.hpp>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/offboard_control_setpoint.h>
|
||||
|
||||
#include "navigator_mode.h"
|
||||
|
||||
class Navigator;
|
||||
|
||||
class Offboard : public NavigatorMode
|
||||
{
|
||||
public:
|
||||
Offboard(Navigator *navigator, const char *name);
|
||||
|
||||
~Offboard();
|
||||
|
||||
virtual void on_inactive();
|
||||
|
||||
virtual void on_activation();
|
||||
|
||||
virtual void on_active();
|
||||
private:
|
||||
void update_offboard_control_setpoint();
|
||||
|
||||
struct offboard_control_setpoint_s _offboard_control_sp;
|
||||
enum SF0X_PARSE_STATE {
|
||||
SF0X_PARSE_STATE0_UNSYNC = 0,
|
||||
SF0X_PARSE_STATE1_SYNC,
|
||||
SF0X_PARSE_STATE2_GOT_DIGIT0,
|
||||
SF0X_PARSE_STATE3_GOT_DOT,
|
||||
SF0X_PARSE_STATE4_GOT_DIGIT1,
|
||||
SF0X_PARSE_STATE5_GOT_DIGIT2,
|
||||
SF0X_PARSE_STATE6_GOT_CARRIAGE_RETURN
|
||||
};
|
||||
|
||||
#endif
|
||||
int sf0x_parser(char c, char *parserbuf, unsigned *parserbuf_index, enum SF0X_PARSE_STATE *state, float *dist);
|
||||
@ -236,9 +236,9 @@ void TECS::_update_height_demand(float demand, float state)
|
||||
// // _hgt_rate_dem);
|
||||
|
||||
_hgt_dem_adj = demand;//0.025f * demand + 0.975f * _hgt_dem_adj_last;
|
||||
_hgt_rate_dem = (_hgt_dem_adj-state)*_heightrate_p + _heightrate_ff * (_hgt_dem_adj - _hgt_dem_adj_last)/_DT;
|
||||
_hgt_dem_adj_last = _hgt_dem_adj;
|
||||
|
||||
_hgt_rate_dem = (_hgt_dem_adj-state)*_heightrate_p + _heightrate_ff * (_hgt_dem_adj - _hgt_dem_adj_last)/_DT;
|
||||
// Limit height rate of change
|
||||
if (_hgt_rate_dem > _maxClimbRate) {
|
||||
_hgt_rate_dem = _maxClimbRate;
|
||||
|
||||
907
src/modules/bottle_drop/bottle_drop.cpp
Normal file
907
src/modules/bottle_drop/bottle_drop.cpp
Normal file
@ -0,0 +1,907 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013, 2014 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 bottle_drop.cpp
|
||||
*
|
||||
* Bottle drop module for Outback Challenge 2014, Team Swiss Fang
|
||||
*
|
||||
* @author Dominik Juchli <juchlid@ethz.ch>
|
||||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <math.h>
|
||||
#include <poll.h>
|
||||
#include <time.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <drivers/device/device.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_command.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/wind_estimate.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <geo/geo.h>
|
||||
#include <dataman/dataman.h>
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <mavlink/mavlink_log.h>
|
||||
|
||||
|
||||
/**
|
||||
* bottle_drop app start / stop handling function
|
||||
*
|
||||
* @ingroup apps
|
||||
*/
|
||||
extern "C" __EXPORT int bottle_drop_main(int argc, char *argv[]);
|
||||
|
||||
class BottleDrop
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Constructor
|
||||
*/
|
||||
BottleDrop();
|
||||
|
||||
/**
|
||||
* Destructor, also kills task.
|
||||
*/
|
||||
~BottleDrop();
|
||||
|
||||
/**
|
||||
* Start the task.
|
||||
*
|
||||
* @return OK on success.
|
||||
*/
|
||||
int start();
|
||||
|
||||
/**
|
||||
* Display status.
|
||||
*/
|
||||
void status();
|
||||
|
||||
void open_bay();
|
||||
void close_bay();
|
||||
void drop();
|
||||
void lock_release();
|
||||
|
||||
private:
|
||||
bool _task_should_exit; /**< if true, task should exit */
|
||||
int _main_task; /**< handle for task */
|
||||
int _mavlink_fd;
|
||||
|
||||
int _command_sub;
|
||||
int _wind_estimate_sub;
|
||||
struct vehicle_command_s _command;
|
||||
struct vehicle_global_position_s _global_pos;
|
||||
map_projection_reference_s ref;
|
||||
|
||||
orb_advert_t _actuator_pub;
|
||||
struct actuator_controls_s _actuators;
|
||||
|
||||
bool _drop_approval;
|
||||
hrt_abstime _doors_opened;
|
||||
hrt_abstime _drop_time;
|
||||
|
||||
float _alt_clearance;
|
||||
|
||||
struct position_s {
|
||||
double lat; ///< degrees
|
||||
double lon; ///< degrees
|
||||
float alt; ///< m
|
||||
} _target_position, _drop_position;
|
||||
|
||||
enum DROP_STATE {
|
||||
DROP_STATE_INIT = 0,
|
||||
DROP_STATE_TARGET_VALID,
|
||||
DROP_STATE_TARGET_SET,
|
||||
DROP_STATE_BAY_OPEN,
|
||||
DROP_STATE_DROPPED,
|
||||
DROP_STATE_BAY_CLOSED
|
||||
} _drop_state;
|
||||
|
||||
struct mission_s _onboard_mission;
|
||||
orb_advert_t _onboard_mission_pub;
|
||||
|
||||
void task_main();
|
||||
|
||||
void handle_command(struct vehicle_command_s *cmd);
|
||||
|
||||
void answer_command(struct vehicle_command_s *cmd, enum VEHICLE_CMD_RESULT result);
|
||||
|
||||
/**
|
||||
* Set the actuators
|
||||
*/
|
||||
int actuators_publish();
|
||||
|
||||
/**
|
||||
* Shim for calling task_main from task_create.
|
||||
*/
|
||||
static void task_main_trampoline(int argc, char *argv[]);
|
||||
};
|
||||
|
||||
namespace bottle_drop
|
||||
{
|
||||
BottleDrop *g_bottle_drop;
|
||||
}
|
||||
|
||||
BottleDrop::BottleDrop() :
|
||||
|
||||
_task_should_exit(false),
|
||||
_main_task(-1),
|
||||
_mavlink_fd(-1),
|
||||
_command_sub(-1),
|
||||
_wind_estimate_sub(-1),
|
||||
_command {},
|
||||
_global_pos {},
|
||||
ref {},
|
||||
_actuator_pub(-1),
|
||||
_actuators {},
|
||||
_drop_approval(false),
|
||||
_doors_opened(0),
|
||||
_drop_time(0),
|
||||
_alt_clearance(70.0f),
|
||||
_target_position {},
|
||||
_drop_position {},
|
||||
_drop_state(DROP_STATE_INIT),
|
||||
_onboard_mission {},
|
||||
_onboard_mission_pub(-1)
|
||||
{
|
||||
}
|
||||
|
||||
BottleDrop::~BottleDrop()
|
||||
{
|
||||
if (_main_task != -1) {
|
||||
|
||||
/* task wakes up every 100ms or so at the longest */
|
||||
_task_should_exit = true;
|
||||
|
||||
/* wait for a second for the task to quit at our request */
|
||||
unsigned i = 0;
|
||||
|
||||
do {
|
||||
/* wait 20ms */
|
||||
usleep(20000);
|
||||
|
||||
/* if we have given up, kill it */
|
||||
if (++i > 50) {
|
||||
task_delete(_main_task);
|
||||
break;
|
||||
}
|
||||
} while (_main_task != -1);
|
||||
}
|
||||
|
||||
bottle_drop::g_bottle_drop = nullptr;
|
||||
}
|
||||
|
||||
int
|
||||
BottleDrop::start()
|
||||
{
|
||||
ASSERT(_main_task == -1);
|
||||
|
||||
/* start the task */
|
||||
_main_task = task_spawn_cmd("bottle_drop",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT + 15,
|
||||
2048,
|
||||
(main_t)&BottleDrop::task_main_trampoline,
|
||||
nullptr);
|
||||
|
||||
if (_main_task < 0) {
|
||||
warn("task start failed");
|
||||
return -errno;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
BottleDrop::status()
|
||||
{
|
||||
warnx("drop state: %d", _drop_state);
|
||||
}
|
||||
|
||||
void
|
||||
BottleDrop::open_bay()
|
||||
{
|
||||
_actuators.control[0] = -1.0f;
|
||||
_actuators.control[1] = 1.0f;
|
||||
|
||||
if (_doors_opened == 0) {
|
||||
_doors_opened = hrt_absolute_time();
|
||||
}
|
||||
warnx("open doors");
|
||||
|
||||
actuators_publish();
|
||||
|
||||
usleep(500 * 1000);
|
||||
}
|
||||
|
||||
void
|
||||
BottleDrop::close_bay()
|
||||
{
|
||||
// closed door and locked survival kit
|
||||
_actuators.control[0] = 1.0f;
|
||||
_actuators.control[1] = -1.0f;
|
||||
|
||||
_doors_opened = 0;
|
||||
|
||||
actuators_publish();
|
||||
|
||||
// delay until the bay is closed
|
||||
usleep(500 * 1000);
|
||||
}
|
||||
|
||||
void
|
||||
BottleDrop::drop()
|
||||
{
|
||||
|
||||
// update drop actuator, wait 0.5s until the doors are open before dropping
|
||||
hrt_abstime starttime = hrt_absolute_time();
|
||||
|
||||
// force the door open if we have to
|
||||
if (_doors_opened == 0) {
|
||||
open_bay();
|
||||
warnx("bay not ready, forced open");
|
||||
}
|
||||
|
||||
while (hrt_elapsed_time(&_doors_opened) < 500 * 1000 && hrt_elapsed_time(&starttime) < 2000000) {
|
||||
usleep(50000);
|
||||
warnx("delayed by door!");
|
||||
}
|
||||
|
||||
_actuators.control[2] = 1.0f;
|
||||
|
||||
_drop_time = hrt_absolute_time();
|
||||
actuators_publish();
|
||||
|
||||
warnx("dropping now");
|
||||
|
||||
// Give it time to drop
|
||||
usleep(1000 * 1000);
|
||||
}
|
||||
|
||||
void
|
||||
BottleDrop::lock_release()
|
||||
{
|
||||
_actuators.control[2] = -1.0f;
|
||||
actuators_publish();
|
||||
|
||||
warnx("closing release");
|
||||
}
|
||||
|
||||
int
|
||||
BottleDrop::actuators_publish()
|
||||
{
|
||||
_actuators.timestamp = hrt_absolute_time();
|
||||
|
||||
// lazily publish _actuators only once available
|
||||
if (_actuator_pub > 0) {
|
||||
return orb_publish(ORB_ID(actuator_controls_2), _actuator_pub, &_actuators);
|
||||
|
||||
} else {
|
||||
_actuator_pub = orb_advertise(ORB_ID(actuator_controls_2), &_actuators);
|
||||
if (_actuator_pub > 0) {
|
||||
return OK;
|
||||
} else {
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
BottleDrop::task_main()
|
||||
{
|
||||
|
||||
_mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
|
||||
mavlink_log_info(_mavlink_fd, "[bottle_drop] started");
|
||||
|
||||
_command_sub = orb_subscribe(ORB_ID(vehicle_command));
|
||||
_wind_estimate_sub = orb_subscribe(ORB_ID(wind_estimate));
|
||||
|
||||
bool updated = false;
|
||||
|
||||
float z_0; // ground properties
|
||||
float turn_radius; // turn radius of the UAV
|
||||
float precision; // Expected precision of the UAV
|
||||
|
||||
float ground_distance = _alt_clearance; // Replace by closer estimate in loop
|
||||
|
||||
// constant
|
||||
float g = CONSTANTS_ONE_G; // constant of gravity [m/s^2]
|
||||
float m = 0.5f; // mass of bottle [kg]
|
||||
float rho = 1.2f; // air density [kg/m^3]
|
||||
float A = ((0.063f * 0.063f) / 4.0f * M_PI_F); // Bottle cross section [m^2]
|
||||
float dt_freefall_prediction = 0.01f; // step size of the free fall prediction [s]
|
||||
|
||||
// Has to be estimated by experiment
|
||||
float cd = 0.86f; // Drag coefficient for a cylinder with a d/l ratio of 1/3 []
|
||||
float t_signal =
|
||||
0.084f; // Time span between sending the signal and the bottle top reaching level height with the bottom of the plane [s]
|
||||
float t_door =
|
||||
0.7f; // The time the system needs to open the door + safety, is also the time the palyload needs to safely escape the shaft [s]
|
||||
|
||||
|
||||
// Definition
|
||||
float h_0; // height over target
|
||||
float az; // acceleration in z direction[m/s^2]
|
||||
float vz; // velocity in z direction [m/s]
|
||||
float z; // fallen distance [m]
|
||||
float h; // height over target [m]
|
||||
float ax; // acceleration in x direction [m/s^2]
|
||||
float vx; // ground speed in x direction [m/s]
|
||||
float x; // traveled distance in x direction [m]
|
||||
float vw; // wind speed [m/s]
|
||||
float vrx; // relative velocity in x direction [m/s]
|
||||
float v; // relative speed vector [m/s]
|
||||
float Fd; // Drag force [N]
|
||||
float Fdx; // Drag force in x direction [N]
|
||||
float Fdz; // Drag force in z direction [N]
|
||||
float x_drop, y_drop; // coordinates of the drop point in reference to the target (projection of NED)
|
||||
float x_t, y_t; // coordinates of the target in reference to the target x_t = 0, y_t = 0 (projection of NED)
|
||||
float x_l, y_l; // local position in projected coordinates
|
||||
float x_f, y_f; // to-be position of the UAV after dt_runs seconds in projected coordinates
|
||||
double x_f_NED, y_f_NED; // to-be position of the UAV after dt_runs seconds in NED
|
||||
float distance_open_door; // The distance the UAV travels during its doors open [m]
|
||||
float approach_error = 0.0f; // The error in radians between current ground vector and desired ground vector
|
||||
float distance_real = 0; // The distance between the UAVs position and the drop point [m]
|
||||
float future_distance = 0; // The distance between the UAVs to-be position and the drop point [m]
|
||||
|
||||
unsigned counter = 0;
|
||||
|
||||
param_t param_gproperties = param_find("BD_GPROPERTIES");
|
||||
param_t param_turn_radius = param_find("BD_TURNRADIUS");
|
||||
param_t param_precision = param_find("BD_PRECISION");
|
||||
param_t param_cd = param_find("BD_OBJ_CD");
|
||||
param_t param_mass = param_find("BD_OBJ_MASS");
|
||||
param_t param_surface = param_find("BD_OBJ_SURFACE");
|
||||
|
||||
|
||||
param_get(param_precision, &precision);
|
||||
param_get(param_turn_radius, &turn_radius);
|
||||
param_get(param_gproperties, &z_0);
|
||||
param_get(param_cd, &cd);
|
||||
param_get(param_mass, &m);
|
||||
param_get(param_surface, &A);
|
||||
|
||||
int vehicle_global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position));
|
||||
|
||||
struct parameter_update_s update;
|
||||
memset(&update, 0, sizeof(update));
|
||||
int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
|
||||
|
||||
struct mission_item_s flight_vector_s {};
|
||||
struct mission_item_s flight_vector_e {};
|
||||
|
||||
flight_vector_s.nav_cmd = NAV_CMD_WAYPOINT;
|
||||
flight_vector_s.acceptance_radius = 50; // TODO: make parameter
|
||||
flight_vector_s.autocontinue = true;
|
||||
flight_vector_s.altitude_is_relative = false;
|
||||
|
||||
flight_vector_e.nav_cmd = NAV_CMD_WAYPOINT;
|
||||
flight_vector_e.acceptance_radius = 50; // TODO: make parameter
|
||||
flight_vector_e.autocontinue = true;
|
||||
flight_vector_s.altitude_is_relative = false;
|
||||
|
||||
struct wind_estimate_s wind;
|
||||
|
||||
// wakeup source(s)
|
||||
struct pollfd fds[1];
|
||||
|
||||
// Setup of loop
|
||||
fds[0].fd = _command_sub;
|
||||
fds[0].events = POLLIN;
|
||||
|
||||
// Whatever state the bay is in, we want it closed on startup
|
||||
lock_release();
|
||||
close_bay();
|
||||
|
||||
while (!_task_should_exit) {
|
||||
|
||||
/* wait for up to 100ms for data */
|
||||
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 50);
|
||||
|
||||
/* this is undesirable but not much we can do - might want to flag unhappy status */
|
||||
if (pret < 0) {
|
||||
warn("poll error %d, %d", pret, errno);
|
||||
continue;
|
||||
}
|
||||
|
||||
/* vehicle commands updated */
|
||||
if (fds[0].revents & POLLIN) {
|
||||
orb_copy(ORB_ID(vehicle_command), _command_sub, &_command);
|
||||
handle_command(&_command);
|
||||
}
|
||||
|
||||
orb_check(vehicle_global_position_sub, &updated);
|
||||
if (updated) {
|
||||
/* copy global position */
|
||||
orb_copy(ORB_ID(vehicle_global_position), vehicle_global_position_sub, &_global_pos);
|
||||
}
|
||||
|
||||
if (_global_pos.timestamp == 0) {
|
||||
continue;
|
||||
}
|
||||
|
||||
const unsigned sleeptime_us = 9500;
|
||||
|
||||
hrt_abstime last_run = hrt_absolute_time();
|
||||
float dt_runs = sleeptime_us / 1e6f;
|
||||
|
||||
// switch to faster updates during the drop
|
||||
while (_drop_state > DROP_STATE_INIT) {
|
||||
|
||||
// Get wind estimate
|
||||
orb_check(_wind_estimate_sub, &updated);
|
||||
if (updated) {
|
||||
orb_copy(ORB_ID(wind_estimate), _wind_estimate_sub, &wind);
|
||||
}
|
||||
|
||||
// Get vehicle position
|
||||
orb_check(vehicle_global_position_sub, &updated);
|
||||
if (updated) {
|
||||
// copy global position
|
||||
orb_copy(ORB_ID(vehicle_global_position), vehicle_global_position_sub, &_global_pos);
|
||||
}
|
||||
|
||||
// Get parameter updates
|
||||
orb_check(parameter_update_sub, &updated);
|
||||
if (updated) {
|
||||
// copy global position
|
||||
orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update);
|
||||
|
||||
// update all parameters
|
||||
param_get(param_gproperties, &z_0);
|
||||
param_get(param_turn_radius, &turn_radius);
|
||||
param_get(param_precision, &precision);
|
||||
}
|
||||
|
||||
orb_check(_command_sub, &updated);
|
||||
if (updated) {
|
||||
orb_copy(ORB_ID(vehicle_command), _command_sub, &_command);
|
||||
handle_command(&_command);
|
||||
}
|
||||
|
||||
|
||||
float windspeed_norm = sqrtf(wind.windspeed_north * wind.windspeed_north + wind.windspeed_east * wind.windspeed_east);
|
||||
float groundspeed_body = sqrtf(_global_pos.vel_n * _global_pos.vel_n + _global_pos.vel_e * _global_pos.vel_e);
|
||||
ground_distance = _global_pos.alt - _target_position.alt;
|
||||
|
||||
// Distance to drop position and angle error to approach vector
|
||||
// are relevant in all states greater than target valid (which calculates these positions)
|
||||
if (_drop_state > DROP_STATE_TARGET_VALID) {
|
||||
distance_real = fabsf(get_distance_to_next_waypoint(_global_pos.lat, _global_pos.lon, _drop_position.lat, _drop_position.lon));
|
||||
|
||||
float ground_direction = atan2f(_global_pos.vel_e, _global_pos.vel_n);
|
||||
float approach_direction = get_bearing_to_next_waypoint(flight_vector_s.lat, flight_vector_s.lon, flight_vector_e.lat, flight_vector_e.lon);
|
||||
|
||||
approach_error = _wrap_pi(ground_direction - approach_direction);
|
||||
|
||||
if (counter % 90 == 0) {
|
||||
mavlink_log_info(_mavlink_fd, "drop distance %u, heading error %u", (unsigned)distance_real, (unsigned)math::degrees(approach_error));
|
||||
}
|
||||
}
|
||||
|
||||
switch (_drop_state) {
|
||||
|
||||
case DROP_STATE_TARGET_VALID:
|
||||
{
|
||||
|
||||
az = g; // acceleration in z direction[m/s^2]
|
||||
vz = 0; // velocity in z direction [m/s]
|
||||
z = 0; // fallen distance [m]
|
||||
h_0 = _global_pos.alt - _target_position.alt; // height over target at start[m]
|
||||
h = h_0; // height over target [m]
|
||||
ax = 0; // acceleration in x direction [m/s^2]
|
||||
vx = groundspeed_body;// XXX project // ground speed in x direction [m/s]
|
||||
x = 0; // traveled distance in x direction [m]
|
||||
vw = 0; // wind speed [m/s]
|
||||
vrx = 0; // relative velocity in x direction [m/s]
|
||||
v = groundspeed_body; // relative speed vector [m/s]
|
||||
Fd = 0; // Drag force [N]
|
||||
Fdx = 0; // Drag force in x direction [N]
|
||||
Fdz = 0; // Drag force in z direction [N]
|
||||
|
||||
|
||||
// Compute the distance the bottle will travel after it is dropped in body frame coordinates --> x
|
||||
while (h > 0.05f) {
|
||||
// z-direction
|
||||
vz = vz + az * dt_freefall_prediction;
|
||||
z = z + vz * dt_freefall_prediction;
|
||||
h = h_0 - z;
|
||||
|
||||
// x-direction
|
||||
vw = windspeed_norm * logf(h / z_0) / logf(ground_distance / z_0);
|
||||
vx = vx + ax * dt_freefall_prediction;
|
||||
x = x + vx * dt_freefall_prediction;
|
||||
vrx = vx + vw;
|
||||
|
||||
// drag force
|
||||
v = sqrtf(vz * vz + vrx * vrx);
|
||||
Fd = 0.5f * rho * A * cd * (v * v);
|
||||
Fdx = Fd * vrx / v;
|
||||
Fdz = Fd * vz / v;
|
||||
|
||||
// acceleration
|
||||
az = g - Fdz / m;
|
||||
ax = -Fdx / m;
|
||||
}
|
||||
|
||||
// compute drop vector
|
||||
x = groundspeed_body * t_signal + x;
|
||||
|
||||
x_t = 0.0f;
|
||||
y_t = 0.0f;
|
||||
|
||||
float wind_direction_n, wind_direction_e;
|
||||
|
||||
if (windspeed_norm < 0.5f) { // If there is no wind, an arbitrarily direction is chosen
|
||||
wind_direction_n = 1.0f;
|
||||
wind_direction_e = 0.0f;
|
||||
|
||||
} else {
|
||||
wind_direction_n = wind.windspeed_north / windspeed_norm;
|
||||
wind_direction_e = wind.windspeed_east / windspeed_norm;
|
||||
}
|
||||
|
||||
x_drop = x_t + x * wind_direction_n;
|
||||
y_drop = y_t + x * wind_direction_e;
|
||||
map_projection_reproject(&ref, x_drop, y_drop, &_drop_position.lat, &_drop_position.lon);
|
||||
_drop_position.alt = _target_position.alt + _alt_clearance;
|
||||
|
||||
// Compute flight vector
|
||||
map_projection_reproject(&ref, x_drop + 2 * turn_radius * wind_direction_n, y_drop + 2 * turn_radius * wind_direction_e,
|
||||
&(flight_vector_s.lat), &(flight_vector_s.lon));
|
||||
flight_vector_s.altitude = _drop_position.alt;
|
||||
map_projection_reproject(&ref, x_drop - turn_radius * wind_direction_n, y_drop - turn_radius * wind_direction_e,
|
||||
&flight_vector_e.lat, &flight_vector_e.lon);
|
||||
flight_vector_e.altitude = _drop_position.alt;
|
||||
|
||||
// Save WPs in datamanager
|
||||
const ssize_t len = sizeof(struct mission_item_s);
|
||||
|
||||
if (dm_write(DM_KEY_WAYPOINTS_ONBOARD, 0, DM_PERSIST_IN_FLIGHT_RESET, &flight_vector_s, len) != len) {
|
||||
warnx("ERROR: could not save onboard WP");
|
||||
}
|
||||
|
||||
if (dm_write(DM_KEY_WAYPOINTS_ONBOARD, 1, DM_PERSIST_IN_FLIGHT_RESET, &flight_vector_e, len) != len) {
|
||||
warnx("ERROR: could not save onboard WP");
|
||||
}
|
||||
|
||||
_onboard_mission.count = 2;
|
||||
_onboard_mission.current_seq = 0;
|
||||
|
||||
if (_onboard_mission_pub > 0) {
|
||||
orb_publish(ORB_ID(onboard_mission), _onboard_mission_pub, &_onboard_mission);
|
||||
|
||||
} else {
|
||||
_onboard_mission_pub = orb_advertise(ORB_ID(onboard_mission), &_onboard_mission);
|
||||
}
|
||||
|
||||
float approach_direction = get_bearing_to_next_waypoint(flight_vector_s.lat, flight_vector_s.lon, flight_vector_e.lat, flight_vector_e.lon);
|
||||
mavlink_log_critical(_mavlink_fd, "position set, approach heading: %u", (unsigned)distance_real, (unsigned)math::degrees(approach_direction + M_PI_F));
|
||||
|
||||
_drop_state = DROP_STATE_TARGET_SET;
|
||||
}
|
||||
break;
|
||||
|
||||
case DROP_STATE_TARGET_SET:
|
||||
{
|
||||
float distance_wp2 = get_distance_to_next_waypoint(_global_pos.lat, _global_pos.lon, flight_vector_e.lat, flight_vector_e.lon);
|
||||
|
||||
if (distance_wp2 < distance_real) {
|
||||
_onboard_mission.current_seq = 0;
|
||||
orb_publish(ORB_ID(onboard_mission), _onboard_mission_pub, &_onboard_mission);
|
||||
} else {
|
||||
|
||||
// We're close enough - open the bay
|
||||
distance_open_door = math::max(10.0f, 3.0f * fabsf(t_door * groundspeed_body));
|
||||
|
||||
if (isfinite(distance_real) && distance_real < distance_open_door &&
|
||||
fabsf(approach_error) < math::radians(20.0f)) {
|
||||
open_bay();
|
||||
_drop_state = DROP_STATE_BAY_OPEN;
|
||||
mavlink_log_info(_mavlink_fd, "#audio: opening bay");
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case DROP_STATE_BAY_OPEN:
|
||||
{
|
||||
if (_drop_approval) {
|
||||
map_projection_project(&ref, _global_pos.lat, _global_pos.lon, &x_l, &y_l);
|
||||
x_f = x_l + _global_pos.vel_n * dt_runs;
|
||||
y_f = y_l + _global_pos.vel_e * dt_runs;
|
||||
map_projection_reproject(&ref, x_f, y_f, &x_f_NED, &y_f_NED);
|
||||
future_distance = get_distance_to_next_waypoint(x_f_NED, y_f_NED, _drop_position.lat, _drop_position.lon);
|
||||
|
||||
if (isfinite(distance_real) &&
|
||||
(distance_real < precision) && ((distance_real < future_distance))) {
|
||||
drop();
|
||||
_drop_state = DROP_STATE_DROPPED;
|
||||
mavlink_log_info(_mavlink_fd, "#audio: payload dropped");
|
||||
} else {
|
||||
|
||||
float distance_wp2 = get_distance_to_next_waypoint(_global_pos.lat, _global_pos.lon, flight_vector_e.lat, flight_vector_e.lon);
|
||||
|
||||
if (distance_wp2 < distance_real) {
|
||||
_onboard_mission.current_seq = 0;
|
||||
orb_publish(ORB_ID(onboard_mission), _onboard_mission_pub, &_onboard_mission);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case DROP_STATE_DROPPED:
|
||||
/* 2s after drop, reset and close everything again */
|
||||
if ((hrt_elapsed_time(&_doors_opened) > 2 * 1000 * 1000)) {
|
||||
_drop_state = DROP_STATE_INIT;
|
||||
_drop_approval = false;
|
||||
lock_release();
|
||||
close_bay();
|
||||
mavlink_log_info(_mavlink_fd, "#audio: closing bay");
|
||||
|
||||
// remove onboard mission
|
||||
_onboard_mission.current_seq = -1;
|
||||
_onboard_mission.count = 0;
|
||||
orb_publish(ORB_ID(onboard_mission), _onboard_mission_pub, &_onboard_mission);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
counter++;
|
||||
|
||||
// update_actuators();
|
||||
|
||||
// run at roughly 100 Hz
|
||||
usleep(sleeptime_us);
|
||||
|
||||
dt_runs = hrt_elapsed_time(&last_run) / 1e6f;
|
||||
last_run = hrt_absolute_time();
|
||||
}
|
||||
}
|
||||
|
||||
warnx("exiting.");
|
||||
|
||||
_main_task = -1;
|
||||
_exit(0);
|
||||
}
|
||||
|
||||
void
|
||||
BottleDrop::handle_command(struct vehicle_command_s *cmd)
|
||||
{
|
||||
switch (cmd->command) {
|
||||
case VEHICLE_CMD_CUSTOM_0:
|
||||
/*
|
||||
* param1 and param2 set to 1: open and drop
|
||||
* param1 set to 1: open
|
||||
* else: close (and don't drop)
|
||||
*/
|
||||
if (cmd->param1 > 0.5f && cmd->param2 > 0.5f) {
|
||||
open_bay();
|
||||
drop();
|
||||
mavlink_log_info(_mavlink_fd, "#audio: drop bottle");
|
||||
|
||||
} else if (cmd->param1 > 0.5f) {
|
||||
open_bay();
|
||||
mavlink_log_info(_mavlink_fd, "#audio: opening bay");
|
||||
|
||||
} else {
|
||||
lock_release();
|
||||
close_bay();
|
||||
mavlink_log_info(_mavlink_fd, "#audio: closing bay");
|
||||
}
|
||||
|
||||
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
|
||||
break;
|
||||
|
||||
case VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY:
|
||||
|
||||
switch ((int)(cmd->param1 + 0.5f)) {
|
||||
case 0:
|
||||
_drop_approval = false;
|
||||
mavlink_log_info(_mavlink_fd, "#audio: got drop position, no approval");
|
||||
break;
|
||||
|
||||
case 1:
|
||||
_drop_approval = true;
|
||||
mavlink_log_info(_mavlink_fd, "#audio: got drop position and approval");
|
||||
break;
|
||||
|
||||
default:
|
||||
_drop_approval = false;
|
||||
warnx("param1 val unknown");
|
||||
break;
|
||||
}
|
||||
|
||||
// XXX check all fields (2-3)
|
||||
_alt_clearance = cmd->param4;
|
||||
_target_position.lat = cmd->param5;
|
||||
_target_position.lon = cmd->param6;
|
||||
_target_position.alt = cmd->param7;
|
||||
_drop_state = DROP_STATE_TARGET_VALID;
|
||||
mavlink_log_info(_mavlink_fd, "got target: %8.4f, %8.4f, %8.4f", (double)_target_position.lat,
|
||||
(double)_target_position.lon, (double)_target_position.alt);
|
||||
map_projection_init(&ref, _target_position.lat, _target_position.lon);
|
||||
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
|
||||
break;
|
||||
|
||||
case VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY:
|
||||
|
||||
if (cmd->param1 < 0) {
|
||||
|
||||
// Clear internal states
|
||||
_drop_approval = false;
|
||||
_drop_state = DROP_STATE_INIT;
|
||||
|
||||
// Abort if mission is present
|
||||
_onboard_mission.current_seq = -1;
|
||||
|
||||
if (_onboard_mission_pub > 0) {
|
||||
orb_publish(ORB_ID(onboard_mission), _onboard_mission_pub, &_onboard_mission);
|
||||
}
|
||||
|
||||
} else {
|
||||
switch ((int)(cmd->param1 + 0.5f)) {
|
||||
case 0:
|
||||
_drop_approval = false;
|
||||
break;
|
||||
|
||||
case 1:
|
||||
_drop_approval = true;
|
||||
mavlink_log_info(_mavlink_fd, "#audio: got drop approval");
|
||||
break;
|
||||
|
||||
default:
|
||||
_drop_approval = false;
|
||||
break;
|
||||
// XXX handle other values
|
||||
}
|
||||
}
|
||||
|
||||
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
BottleDrop::answer_command(struct vehicle_command_s *cmd, enum VEHICLE_CMD_RESULT result)
|
||||
{
|
||||
switch (result) {
|
||||
case VEHICLE_CMD_RESULT_ACCEPTED:
|
||||
break;
|
||||
|
||||
case VEHICLE_CMD_RESULT_DENIED:
|
||||
mavlink_log_critical(_mavlink_fd, "#audio: command denied: %u", cmd->command);
|
||||
break;
|
||||
|
||||
case VEHICLE_CMD_RESULT_FAILED:
|
||||
mavlink_log_critical(_mavlink_fd, "#audio: command failed: %u", cmd->command);
|
||||
break;
|
||||
|
||||
case VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
|
||||
mavlink_log_critical(_mavlink_fd, "#audio: command temporarily rejected: %u", cmd->command);
|
||||
break;
|
||||
|
||||
case VEHICLE_CMD_RESULT_UNSUPPORTED:
|
||||
mavlink_log_critical(_mavlink_fd, "#audio: command unsupported: %u", cmd->command);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
BottleDrop::task_main_trampoline(int argc, char *argv[])
|
||||
{
|
||||
bottle_drop::g_bottle_drop->task_main();
|
||||
}
|
||||
|
||||
static void usage()
|
||||
{
|
||||
errx(1, "usage: bottle_drop {start|stop|status}");
|
||||
}
|
||||
|
||||
int bottle_drop_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 2) {
|
||||
usage();
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
if (bottle_drop::g_bottle_drop != nullptr) {
|
||||
errx(1, "already running");
|
||||
}
|
||||
|
||||
bottle_drop::g_bottle_drop = new BottleDrop;
|
||||
|
||||
if (bottle_drop::g_bottle_drop == nullptr) {
|
||||
errx(1, "alloc failed");
|
||||
}
|
||||
|
||||
if (OK != bottle_drop::g_bottle_drop->start()) {
|
||||
delete bottle_drop::g_bottle_drop;
|
||||
bottle_drop::g_bottle_drop = nullptr;
|
||||
err(1, "start failed");
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (bottle_drop::g_bottle_drop == nullptr) {
|
||||
errx(1, "not running");
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "stop")) {
|
||||
delete bottle_drop::g_bottle_drop;
|
||||
bottle_drop::g_bottle_drop = nullptr;
|
||||
|
||||
} else if (!strcmp(argv[1], "status")) {
|
||||
bottle_drop::g_bottle_drop->status();
|
||||
|
||||
} else if (!strcmp(argv[1], "drop")) {
|
||||
bottle_drop::g_bottle_drop->drop();
|
||||
|
||||
} else if (!strcmp(argv[1], "open")) {
|
||||
bottle_drop::g_bottle_drop->open_bay();
|
||||
|
||||
} else if (!strcmp(argv[1], "close")) {
|
||||
bottle_drop::g_bottle_drop->close_bay();
|
||||
|
||||
} else if (!strcmp(argv[1], "lock")) {
|
||||
bottle_drop::g_bottle_drop->lock_release();
|
||||
|
||||
} else {
|
||||
usage();
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
131
src/modules/bottle_drop/bottle_drop_params.c
Normal file
131
src/modules/bottle_drop/bottle_drop_params.c
Normal file
@ -0,0 +1,131 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013, 2014 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 bottle_drop_params.c
|
||||
* Bottle drop parameters
|
||||
*
|
||||
* @author Dominik Juchli <juchlid@ethz.ch>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/**
|
||||
* Ground drag property
|
||||
*
|
||||
* This parameter encodes the ground drag coefficient and the corresponding
|
||||
* decrease in wind speed from the plane altitude to ground altitude.
|
||||
*
|
||||
* @unit unknown
|
||||
* @min 0.001
|
||||
* @max 0.1
|
||||
* @group Payload drop
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(BD_GPROPERTIES, 0.03f);
|
||||
|
||||
/**
|
||||
* Plane turn radius
|
||||
*
|
||||
* The planes known minimal turn radius - use a higher value
|
||||
* to make the plane maneuver more distant from the actual drop
|
||||
* position. This is to ensure the wings are level during the drop.
|
||||
*
|
||||
* @unit meter
|
||||
* @min 30.0
|
||||
* @max 500.0
|
||||
* @group Payload drop
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(BD_TURNRADIUS, 120.0f);
|
||||
|
||||
/**
|
||||
* Drop precision
|
||||
*
|
||||
* If the system is closer than this distance on passing over the
|
||||
* drop position, it will release the payload. This is a safeguard
|
||||
* to prevent a drop out of the required accuracy.
|
||||
*
|
||||
* @unit meter
|
||||
* @min 1.0
|
||||
* @max 80.0
|
||||
* @group Payload drop
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(BD_PRECISION, 30.0f);
|
||||
|
||||
/**
|
||||
* Payload drag coefficient of the dropped object
|
||||
*
|
||||
* The drag coefficient (cd) is the typical drag
|
||||
* constant for air. It is in general object specific,
|
||||
* but the closest primitive shape to the actual object
|
||||
* should give good results:
|
||||
* http://en.wikipedia.org/wiki/Drag_coefficient
|
||||
*
|
||||
* @unit meter
|
||||
* @min 0.08
|
||||
* @max 1.5
|
||||
* @group Payload drop
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(BD_OBJ_CD, 0.1f);
|
||||
|
||||
/**
|
||||
* Payload mass
|
||||
*
|
||||
* A typical small toy ball:
|
||||
* 0.025 kg
|
||||
*
|
||||
* OBC water bottle:
|
||||
* 0.6 kg
|
||||
*
|
||||
* @unit kilogram
|
||||
* @min 0.001
|
||||
* @max 5.0
|
||||
* @group Payload drop
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(BD_OBJ_MASS, 0.6f);
|
||||
|
||||
/**
|
||||
* Payload front surface area
|
||||
*
|
||||
* A typical small toy ball:
|
||||
* (0.045 * 0.045) / 4.0 * pi = 0.001590 m^2
|
||||
*
|
||||
* OBC water bottle:
|
||||
* (0.063 * 0.063) / 4.0 * pi = 0.003117 m^2
|
||||
*
|
||||
* @unit m^2
|
||||
* @min 0.001
|
||||
* @max 0.5
|
||||
* @group Payload drop
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(BD_OBJ_SURFACE, 0.00311724531f);
|
||||
41
src/modules/bottle_drop/module.mk
Normal file
41
src/modules/bottle_drop/module.mk
Normal file
@ -0,0 +1,41 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2013, 2014 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Daemon application
|
||||
#
|
||||
|
||||
MODULE_COMMAND = bottle_drop
|
||||
|
||||
SRCS = bottle_drop.cpp \
|
||||
bottle_drop_params.c
|
||||
@ -633,7 +633,29 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case VEHICLE_CMD_NAV_GUIDED_ENABLE: {
|
||||
transition_result_t res = TRANSITION_DENIED;
|
||||
static main_state_t main_state_pre_offboard = MAIN_STATE_MANUAL;
|
||||
if (status_local->main_state != MAIN_STATE_OFFBOARD) {
|
||||
main_state_pre_offboard = status_local->main_state;
|
||||
}
|
||||
if (cmd->param1 > 0.5f) {
|
||||
res = main_state_transition(status_local, MAIN_STATE_OFFBOARD);
|
||||
if (res == TRANSITION_DENIED) {
|
||||
print_reject_mode(status_local, "OFFBOARD");
|
||||
status_local->offboard_control_set_by_command = false;
|
||||
} else {
|
||||
/* Set flag that offboard was set via command, main state is not overridden by rc */
|
||||
status_local->offboard_control_set_by_command = true;
|
||||
}
|
||||
} else {
|
||||
/* If the mavlink command is used to enable or disable offboard control:
|
||||
* switch back to previous mode when disabling */
|
||||
res = main_state_transition(status_local, main_state_pre_offboard);
|
||||
status_local->offboard_control_set_by_command = false;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
||||
case VEHICLE_CMD_PREFLIGHT_CALIBRATION:
|
||||
case VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
|
||||
@ -1958,6 +1980,11 @@ set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_s
|
||||
/* set main state according to RC switches */
|
||||
transition_result_t res = TRANSITION_DENIED;
|
||||
|
||||
/* if offboard is set allready by a mavlink command, abort */
|
||||
if (status.offboard_control_set_by_command) {
|
||||
return main_state_transition(status_local, MAIN_STATE_OFFBOARD);
|
||||
}
|
||||
|
||||
/* offboard switch overrides main switch */
|
||||
if (sp_man->offboard_switch == SWITCH_POS_ON) {
|
||||
res = main_state_transition(status_local, MAIN_STATE_OFFBOARD);
|
||||
@ -2150,21 +2177,26 @@ set_control_mode()
|
||||
control_mode.flag_control_position_enabled = false;
|
||||
control_mode.flag_control_velocity_enabled = false;
|
||||
break;
|
||||
case OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY:
|
||||
case OFFBOARD_CONTROL_MODE_DIRECT_FORCE:
|
||||
control_mode.flag_control_rates_enabled = true;
|
||||
control_mode.flag_control_attitude_enabled = true;
|
||||
control_mode.flag_control_altitude_enabled = true; /* XXX: hack for now */
|
||||
control_mode.flag_control_climb_rate_enabled = true;
|
||||
control_mode.flag_control_position_enabled = true; /* XXX: hack for now */
|
||||
control_mode.flag_control_velocity_enabled = true;
|
||||
control_mode.flag_control_attitude_enabled = false;
|
||||
control_mode.flag_control_force_enabled = true;
|
||||
control_mode.flag_control_altitude_enabled = false;
|
||||
control_mode.flag_control_climb_rate_enabled = false;
|
||||
control_mode.flag_control_position_enabled = false;
|
||||
control_mode.flag_control_velocity_enabled = false;
|
||||
break;
|
||||
case OFFBOARD_CONTROL_MODE_DIRECT_POSITION:
|
||||
case OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED:
|
||||
case OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_OFFSET_NED:
|
||||
case OFFBOARD_CONTROL_MODE_DIRECT_BODY_NED:
|
||||
case OFFBOARD_CONTROL_MODE_DIRECT_BODY_OFFSET_NED:
|
||||
control_mode.flag_control_rates_enabled = true;
|
||||
control_mode.flag_control_attitude_enabled = true;
|
||||
control_mode.flag_control_altitude_enabled = true;
|
||||
control_mode.flag_control_climb_rate_enabled = true;
|
||||
control_mode.flag_control_position_enabled = true;
|
||||
control_mode.flag_control_velocity_enabled = true;
|
||||
//XXX: the flags could depend on sp_offboard.ignore
|
||||
break;
|
||||
default:
|
||||
control_mode.flag_control_rates_enabled = false;
|
||||
|
||||
@ -1369,7 +1369,7 @@ FixedwingEstimator::task_main()
|
||||
if (newRangeData) {
|
||||
_ekf->fuseRngData = true;
|
||||
_ekf->useRangeFinder = true;
|
||||
_ekf->RecallStates(_ekf->statesAtRngTime, (IMUmsec - 500.0f));
|
||||
_ekf->RecallStates(_ekf->statesAtRngTime, (IMUmsec - 100.0f));
|
||||
_ekf->GroundEKF();
|
||||
}
|
||||
|
||||
|
||||
@ -88,7 +88,6 @@
|
||||
#include <launchdetection/LaunchDetector.h>
|
||||
#include <ecl/l1/ecl_l1_pos_controller.h>
|
||||
#include <external_lgpl/tecs/tecs.h>
|
||||
#include <drivers/drv_range_finder.h>
|
||||
#include "landingslope.h"
|
||||
#include "mtecs/mTecs.h"
|
||||
|
||||
@ -146,7 +145,6 @@ private:
|
||||
int _params_sub; /**< notification of parameter updates */
|
||||
int _manual_control_sub; /**< notification of manual control updates */
|
||||
int _sensor_combined_sub; /**< for body frame accelerations */
|
||||
int _range_finder_sub; /**< range finder subscription */
|
||||
|
||||
orb_advert_t _attitude_sp_pub; /**< attitude setpoint */
|
||||
orb_advert_t _tecs_status_pub; /**< TECS status publication */
|
||||
@ -162,17 +160,16 @@ private:
|
||||
struct vehicle_global_position_s _global_pos; /**< global vehicle position */
|
||||
struct position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of mission items */
|
||||
struct sensor_combined_s _sensor_combined; /**< for body frame accelerations */
|
||||
struct range_finder_report _range_finder; /**< range finder report */
|
||||
|
||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||
|
||||
/* land states */
|
||||
/* not in non-abort mode for landing yet */
|
||||
bool land_noreturn_horizontal;
|
||||
bool land_noreturn_vertical;
|
||||
bool land_stayonground;
|
||||
bool land_motor_lim;
|
||||
bool land_onslope;
|
||||
bool land_useterrain;
|
||||
|
||||
/* takeoff/launch states */
|
||||
LaunchDetectionResult launch_detection_state;
|
||||
@ -243,7 +240,9 @@ private:
|
||||
float land_flare_alt_relative;
|
||||
float land_thrust_lim_alt_relative;
|
||||
float land_heading_hold_horizontal_distance;
|
||||
float range_finder_rel_alt;
|
||||
float land_flare_pitch_min_deg;
|
||||
float land_flare_pitch_max_deg;
|
||||
int land_use_terrain_estimate;
|
||||
|
||||
} _parameters; /**< local copies of interesting parameters */
|
||||
|
||||
@ -289,7 +288,9 @@ private:
|
||||
param_t land_flare_alt_relative;
|
||||
param_t land_thrust_lim_alt_relative;
|
||||
param_t land_heading_hold_horizontal_distance;
|
||||
param_t range_finder_rel_alt;
|
||||
param_t land_flare_pitch_min_deg;
|
||||
param_t land_flare_pitch_max_deg;
|
||||
param_t land_use_terrain_estimate;
|
||||
|
||||
} _parameter_handles; /**< handles for interesting parameters */
|
||||
|
||||
@ -320,12 +321,6 @@ private:
|
||||
*/
|
||||
bool vehicle_airspeed_poll();
|
||||
|
||||
/**
|
||||
* Check for range finder updates.
|
||||
*/
|
||||
bool range_finder_poll();
|
||||
|
||||
|
||||
/**
|
||||
* Check for position updates.
|
||||
*/
|
||||
@ -347,9 +342,9 @@ private:
|
||||
void navigation_capabilities_publish();
|
||||
|
||||
/**
|
||||
* Get the relative alt either from the difference between estimate and waypoint or from the laser range finder
|
||||
* Return the terrain estimate during landing: uses the wp altitude value or the terrain estimate if available
|
||||
*/
|
||||
float get_relative_landingalt(float land_setpoint_alt, float current_alt, const struct range_finder_report &range_finder, float range_finder_use_relative_alt);
|
||||
float get_terrain_altitude_landing(float land_setpoint_alt, const struct vehicle_global_position_s &global_pos);
|
||||
|
||||
/**
|
||||
* Control position.
|
||||
@ -423,7 +418,6 @@ FixedwingPositionControl::FixedwingPositionControl() :
|
||||
_params_sub(-1),
|
||||
_manual_control_sub(-1),
|
||||
_sensor_combined_sub(-1),
|
||||
_range_finder_sub(-1),
|
||||
|
||||
/* publications */
|
||||
_attitude_sp_pub(-1),
|
||||
@ -441,7 +435,6 @@ FixedwingPositionControl::FixedwingPositionControl() :
|
||||
_global_pos(),
|
||||
_pos_sp_triplet(),
|
||||
_sensor_combined(),
|
||||
_range_finder(),
|
||||
|
||||
/* performance counters */
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control")),
|
||||
@ -451,6 +444,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
|
||||
land_stayonground(false),
|
||||
land_motor_lim(false),
|
||||
land_onslope(false),
|
||||
land_useterrain(false),
|
||||
launch_detection_state(LAUNCHDETECTION_RES_NONE),
|
||||
last_manual(false),
|
||||
landingslope(),
|
||||
@ -489,7 +483,9 @@ FixedwingPositionControl::FixedwingPositionControl() :
|
||||
_parameter_handles.land_flare_alt_relative = param_find("FW_LND_FLALT");
|
||||
_parameter_handles.land_thrust_lim_alt_relative = param_find("FW_LND_TLALT");
|
||||
_parameter_handles.land_heading_hold_horizontal_distance = param_find("FW_LND_HHDIST");
|
||||
_parameter_handles.range_finder_rel_alt = param_find("FW_LND_RFRALT");
|
||||
_parameter_handles.land_flare_pitch_min_deg = param_find("FW_FLARE_PMIN");
|
||||
_parameter_handles.land_flare_pitch_max_deg = param_find("FW_FLARE_PMAX");
|
||||
_parameter_handles.land_use_terrain_estimate= param_find("FW_LND_USETER");
|
||||
|
||||
_parameter_handles.time_const = param_find("FW_T_TIME_CONST");
|
||||
_parameter_handles.time_const_throt = param_find("FW_T_THRO_CONST");
|
||||
@ -590,8 +586,9 @@ FixedwingPositionControl::parameters_update()
|
||||
}
|
||||
|
||||
param_get(_parameter_handles.land_heading_hold_horizontal_distance, &(_parameters.land_heading_hold_horizontal_distance));
|
||||
|
||||
param_get(_parameter_handles.range_finder_rel_alt, &(_parameters.range_finder_rel_alt));
|
||||
param_get(_parameter_handles.land_flare_pitch_min_deg, &(_parameters.land_flare_pitch_min_deg));
|
||||
param_get(_parameter_handles.land_flare_pitch_max_deg, &(_parameters.land_flare_pitch_max_deg));
|
||||
param_get(_parameter_handles.land_use_terrain_estimate, &(_parameters.land_use_terrain_estimate));
|
||||
|
||||
_l1_control.set_l1_damping(_parameters.l1_damping);
|
||||
_l1_control.set_l1_period(_parameters.l1_period);
|
||||
@ -695,20 +692,6 @@ FixedwingPositionControl::vehicle_airspeed_poll()
|
||||
return airspeed_updated;
|
||||
}
|
||||
|
||||
bool
|
||||
FixedwingPositionControl::range_finder_poll()
|
||||
{
|
||||
/* check if there is a range finder measurement */
|
||||
bool range_finder_updated;
|
||||
orb_check(_range_finder_sub, &range_finder_updated);
|
||||
|
||||
if (range_finder_updated) {
|
||||
orb_copy(ORB_ID(sensor_range_finder), _range_finder_sub, &_range_finder);
|
||||
}
|
||||
|
||||
return range_finder_updated;
|
||||
}
|
||||
|
||||
void
|
||||
FixedwingPositionControl::vehicle_attitude_poll()
|
||||
{
|
||||
@ -846,21 +829,23 @@ void FixedwingPositionControl::navigation_capabilities_publish()
|
||||
}
|
||||
}
|
||||
|
||||
float FixedwingPositionControl::get_relative_landingalt(float land_setpoint_alt, float current_alt, const struct range_finder_report &range_finder, float range_finder_use_relative_alt)
|
||||
float FixedwingPositionControl::get_terrain_altitude_landing(float land_setpoint_alt, const struct vehicle_global_position_s &global_pos)
|
||||
{
|
||||
float rel_alt_estimated = current_alt - land_setpoint_alt;
|
||||
|
||||
/* only use range finder if:
|
||||
* parameter (range_finder_use_relative_alt) > 0
|
||||
* the measurement is valid
|
||||
* the estimated relative altitude (from global altitude estimate and landing waypoint) <= range_finder_use_relative_alt
|
||||
*/
|
||||
if (range_finder_use_relative_alt < 0 || !range_finder.valid || range_finder.distance > range_finder_use_relative_alt ) {
|
||||
return rel_alt_estimated;
|
||||
if (!isfinite(global_pos.terrain_alt)) {
|
||||
return land_setpoint_alt;
|
||||
}
|
||||
|
||||
return range_finder.distance;
|
||||
|
||||
/* Decide if the terrain estimation can be used, once we switched to using the terrain we stick with it
|
||||
* for the whole landing */
|
||||
if (_parameters.land_use_terrain_estimate && (global_pos.terrain_alt_valid || land_useterrain)) {
|
||||
if(!land_useterrain) {
|
||||
mavlink_log_info(_mavlink_fd, "#audio: Landing, using terrain estimate");
|
||||
land_useterrain = true;
|
||||
}
|
||||
return global_pos.terrain_alt;
|
||||
} else {
|
||||
return land_setpoint_alt;
|
||||
}
|
||||
}
|
||||
|
||||
bool
|
||||
@ -965,10 +950,17 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_LAND) {
|
||||
|
||||
float bearing_lastwp_currwp = get_bearing_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1));
|
||||
float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
|
||||
|
||||
/* Horizontal landing control */
|
||||
/* switch to heading hold for the last meters, continue heading hold after */
|
||||
float wp_distance = get_distance_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
|
||||
/* calculate a waypoint distance value which is 0 when the aircraft is behind the waypoint */
|
||||
float wp_distance_save = wp_distance;
|
||||
if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) >= math::radians(90.0f)) {
|
||||
wp_distance_save = 0.0f;
|
||||
}
|
||||
|
||||
//warnx("wp dist: %d, alt err: %d, noret: %s", (int)wp_distance, (int)altitude_error, (land_noreturn) ? "YES" : "NO");
|
||||
if (wp_distance < _parameters.land_heading_hold_horizontal_distance || land_noreturn_horizontal) {
|
||||
|
||||
@ -1004,29 +996,30 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||
|
||||
/* Vertical landing control */
|
||||
//xxx: using the tecs altitude controller for slope control for now
|
||||
|
||||
// /* do not go down too early */
|
||||
// if (wp_distance > 50.0f) {
|
||||
// altitude_error = (_global_triplet.current.alt + 25.0f) - _global_pos.alt;
|
||||
// }
|
||||
/* apply minimum pitch (flare) and limit roll if close to touch down, altitude error is negative (going down) */
|
||||
// XXX this could make a great param
|
||||
|
||||
float flare_pitch_angle_rad = -math::radians(5.0f);//math::radians(pos_sp_triplet.current.param1)
|
||||
float throttle_land = _parameters.throttle_min + (_parameters.throttle_max - _parameters.throttle_min) * 0.1f;
|
||||
float airspeed_land = 1.3f * _parameters.airspeed_min;
|
||||
float airspeed_approach = 1.3f * _parameters.airspeed_min;
|
||||
|
||||
/* Calculate distance (to landing waypoint) and altitude of last ordinary waypoint L */
|
||||
float L_altitude_rel = _pos_sp_triplet.previous.valid ? _pos_sp_triplet.previous.alt - _pos_sp_triplet.current.alt : 0.0f;
|
||||
/* Get an estimate of the terrain altitude if available, otherwise terrain_alt will be
|
||||
* equal to _pos_sp_triplet.current.alt */
|
||||
float terrain_alt = get_terrain_altitude_landing(_pos_sp_triplet.current.alt, _global_pos);
|
||||
|
||||
/* Calculate distance (to landing waypoint) and altitude of last ordinary waypoint L */
|
||||
float L_altitude_rel = _pos_sp_triplet.previous.valid ?
|
||||
_pos_sp_triplet.previous.alt - terrain_alt : 0.0f;
|
||||
|
||||
float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
|
||||
float landing_slope_alt_rel_desired = landingslope.getLandingSlopeRelativeAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp);
|
||||
|
||||
float relative_alt = get_relative_landingalt(_pos_sp_triplet.current.alt, _global_pos.alt, _range_finder, _parameters.range_finder_rel_alt);
|
||||
|
||||
if ( (relative_alt < landingslope.flare_relative_alt()) || land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
|
||||
|
||||
/* Check if we should start flaring with a vertical and a
|
||||
* horizontal limit (with some tolerance)
|
||||
* The horizontal limit is only applied when we are in front of the wp
|
||||
*/
|
||||
if (((_global_pos.alt < terrain_alt + landingslope.flare_relative_alt()) &&
|
||||
(wp_distance_save < landingslope.flare_length() + 5.0f)) ||
|
||||
land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
|
||||
/* land with minimal speed */
|
||||
|
||||
// /* force TECS to only control speed with pitch, altitude is only implicitely controlled now */
|
||||
@ -1035,7 +1028,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||
/* kill the throttle if param requests it */
|
||||
throttle_max = _parameters.throttle_max;
|
||||
|
||||
if (relative_alt < landingslope.motor_lim_relative_alt() || land_motor_lim) {
|
||||
if (_global_pos.alt < terrain_alt + landingslope.motor_lim_relative_alt() || land_motor_lim) {
|
||||
throttle_max = math::min(throttle_max, _parameters.throttle_land_max);
|
||||
if (!land_motor_lim) {
|
||||
land_motor_lim = true;
|
||||
@ -1053,12 +1046,13 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||
land_stayonground = true;
|
||||
}
|
||||
|
||||
tecs_update_pitch_throttle(_pos_sp_triplet.current.alt + flare_curve_alt_rel,
|
||||
tecs_update_pitch_throttle(terrain_alt + flare_curve_alt_rel,
|
||||
calculate_target_airspeed(airspeed_land), eas2tas,
|
||||
flare_pitch_angle_rad, math::radians(15.0f),
|
||||
math::radians(_parameters.land_flare_pitch_min_deg),
|
||||
math::radians(_parameters.land_flare_pitch_max_deg),
|
||||
0.0f, throttle_max, throttle_land,
|
||||
false, flare_pitch_angle_rad,
|
||||
_pos_sp_triplet.current.alt + relative_alt, ground_speed,
|
||||
false, land_motor_lim ? math::radians(_parameters.land_flare_pitch_min_deg) : math::radians(_parameters.pitch_limit_min),
|
||||
_global_pos.alt, ground_speed,
|
||||
land_motor_lim ? TECS_MODE_LAND_THROTTLELIM : TECS_MODE_LAND);
|
||||
|
||||
if (!land_noreturn_vertical) {
|
||||
@ -1079,8 +1073,8 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||
* if current position is below the slope continue at previous wp altitude
|
||||
* until the intersection with slope
|
||||
* */
|
||||
float altitude_desired_rel = relative_alt;
|
||||
if (relative_alt > landing_slope_alt_rel_desired || land_onslope) {
|
||||
float altitude_desired_rel;
|
||||
if (_global_pos.alt > terrain_alt + landing_slope_alt_rel_desired || land_onslope) {
|
||||
/* stay on slope */
|
||||
altitude_desired_rel = landing_slope_alt_rel_desired;
|
||||
if (!land_onslope) {
|
||||
@ -1089,10 +1083,11 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||
}
|
||||
} else {
|
||||
/* continue horizontally */
|
||||
altitude_desired_rel = _pos_sp_triplet.previous.valid ? L_altitude_rel : relative_alt;
|
||||
altitude_desired_rel = _pos_sp_triplet.previous.valid ? L_altitude_rel :
|
||||
_global_pos.alt - terrain_alt;
|
||||
}
|
||||
|
||||
tecs_update_pitch_throttle(_pos_sp_triplet.current.alt + altitude_desired_rel,
|
||||
tecs_update_pitch_throttle(terrain_alt + altitude_desired_rel,
|
||||
calculate_target_airspeed(airspeed_approach), eas2tas,
|
||||
math::radians(_parameters.pitch_limit_min),
|
||||
math::radians(_parameters.pitch_limit_max),
|
||||
@ -1101,7 +1096,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||
_parameters.throttle_cruise,
|
||||
false,
|
||||
math::radians(_parameters.pitch_limit_min),
|
||||
_pos_sp_triplet.current.alt + relative_alt,
|
||||
_global_pos.alt,
|
||||
ground_speed);
|
||||
}
|
||||
|
||||
@ -1235,8 +1230,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||
_att_sp.thrust = 0.0f;
|
||||
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
|
||||
launch_detection_state != LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS) {
|
||||
/* Copy thrust and pitch values from tecs
|
||||
* making sure again that the correct thrust is used,
|
||||
/* making sure again that the correct thrust is used,
|
||||
* without depending on library calls for safety reasons */
|
||||
_att_sp.thrust = launchDetector.getThrottlePreTakeoff();
|
||||
} else {
|
||||
@ -1278,7 +1272,6 @@ FixedwingPositionControl::task_main()
|
||||
_airspeed_sub = orb_subscribe(ORB_ID(airspeed));
|
||||
_params_sub = orb_subscribe(ORB_ID(parameter_update));
|
||||
_manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
|
||||
_range_finder_sub = orb_subscribe(ORB_ID(sensor_range_finder));
|
||||
|
||||
/* rate limit control mode updates to 5Hz */
|
||||
orb_set_interval(_control_mode_sub, 200);
|
||||
@ -1357,7 +1350,6 @@ FixedwingPositionControl::task_main()
|
||||
vehicle_setpoint_poll();
|
||||
vehicle_sensor_combined_poll();
|
||||
vehicle_airspeed_poll();
|
||||
range_finder_poll();
|
||||
// vehicle_baro_poll();
|
||||
|
||||
math::Vector<3> ground_speed(_global_pos.vel_n, _global_pos.vel_e, _global_pos.vel_d);
|
||||
@ -1421,6 +1413,7 @@ void FixedwingPositionControl::reset_landing_state()
|
||||
land_stayonground = false;
|
||||
land_motor_lim = false;
|
||||
land_onslope = false;
|
||||
land_useterrain = false;
|
||||
}
|
||||
|
||||
void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_sp, float eas2tas,
|
||||
|
||||
@ -412,12 +412,28 @@ PARAM_DEFINE_FLOAT(FW_LND_TLALT, -1.0f);
|
||||
PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f);
|
||||
|
||||
/**
|
||||
* Relative altitude threshold for range finder measurements for use during landing
|
||||
* Enable or disable usage of terrain estimate during landing
|
||||
*
|
||||
* range finder measurements will only be used if the estimated relative altitude (gobal_pos.alt - landing_waypoint.alt) is < FW_LND_RFRALT
|
||||
* set to < 0 to disable
|
||||
* the correct value of this parameter depends on your range measuring device as well as on the terrain at the landing location
|
||||
* 0: disabled, 1: enabled
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_LND_RFRALT, -1.0f);
|
||||
PARAM_DEFINE_INT32(FW_LND_USETER, 0);
|
||||
|
||||
/**
|
||||
* Flare, minimum pitch
|
||||
*
|
||||
* Minimum pitch during flare, a positive sign means nose up
|
||||
* Applied once FW_LND_TLALT is reached
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_FLARE_PMIN, 2.5f);
|
||||
|
||||
/**
|
||||
* Flare, maximum pitch
|
||||
*
|
||||
* Maximum pitch during flare, a positive sign means nose up
|
||||
* Applied once FW_LND_TLALT is reached
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_FLARE_PMAX, 15.0f);
|
||||
|
||||
@ -68,6 +68,13 @@ PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_FIXED_WING);
|
||||
* @group MAVLink
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MAV_USEHILGPS, 0);
|
||||
/**
|
||||
* Forward external setpoint messages
|
||||
* If set to 1 incomming external setpoint messages will be directly forwarded to the controllers if in offboard
|
||||
* control mode
|
||||
* @group MAVLink
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MAV_FWDEXTSP, 1);
|
||||
|
||||
mavlink_system_t mavlink_system = {
|
||||
100,
|
||||
|
||||
@ -123,6 +123,7 @@ Mavlink::Mavlink() :
|
||||
_task_running(false),
|
||||
_hil_enabled(false),
|
||||
_use_hil_gps(false),
|
||||
_forward_externalsp(false),
|
||||
_is_usb_uart(false),
|
||||
_wait_to_transmit(false),
|
||||
_received_messages(false),
|
||||
@ -483,6 +484,7 @@ void Mavlink::mavlink_update_system(void)
|
||||
_param_component_id = param_find("MAV_COMP_ID");
|
||||
_param_system_type = param_find("MAV_TYPE");
|
||||
_param_use_hil_gps = param_find("MAV_USEHILGPS");
|
||||
_param_forward_externalsp = param_find("MAV_FWDEXTSP");
|
||||
}
|
||||
|
||||
/* update system and component id */
|
||||
@ -529,6 +531,11 @@ void Mavlink::mavlink_update_system(void)
|
||||
param_get(_param_use_hil_gps, &use_hil_gps);
|
||||
|
||||
_use_hil_gps = (bool)use_hil_gps;
|
||||
|
||||
int32_t forward_externalsp;
|
||||
param_get(_param_forward_externalsp, &forward_externalsp);
|
||||
|
||||
_forward_externalsp = (bool)forward_externalsp;
|
||||
}
|
||||
|
||||
int Mavlink::get_system_id()
|
||||
@ -1396,7 +1403,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f);
|
||||
configure_stream("ATTITUDE_TARGET", 3.0f);
|
||||
configure_stream("DISTANCE_SENSOR", 0.5f);
|
||||
configure_stream("OPTICAL_FLOW", 20.0f);
|
||||
configure_stream("OPTICAL_FLOW", 5.0f);
|
||||
break;
|
||||
|
||||
case MAVLINK_MODE_ONBOARD:
|
||||
@ -1404,6 +1411,9 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
configure_stream("ATTITUDE", 50.0f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 50.0f);
|
||||
configure_stream("CAMERA_CAPTURE", 2.0f);
|
||||
configure_stream("ATTITUDE_TARGET", 10.0f);
|
||||
configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f);
|
||||
configure_stream("VFR_HUD", 10.0f);
|
||||
break;
|
||||
|
||||
default:
|
||||
|
||||
@ -137,6 +137,8 @@ public:
|
||||
|
||||
bool get_use_hil_gps() { return _use_hil_gps; }
|
||||
|
||||
bool get_forward_externalsp() { return _forward_externalsp; }
|
||||
|
||||
bool get_flow_control_enabled() { return _flow_control_enabled; }
|
||||
|
||||
bool get_forwarding_on() { return _forwarding_on; }
|
||||
@ -232,7 +234,7 @@ public:
|
||||
bool should_transmit() { return (!_wait_to_transmit || (_wait_to_transmit && _received_messages)); }
|
||||
|
||||
bool message_buffer_write(const void *ptr, int size);
|
||||
|
||||
|
||||
void lockMessageBufferMutex(void) { pthread_mutex_lock(&_message_buffer_mutex); }
|
||||
void unlockMessageBufferMutex(void) { pthread_mutex_unlock(&_message_buffer_mutex); }
|
||||
|
||||
@ -275,6 +277,7 @@ private:
|
||||
/* states */
|
||||
bool _hil_enabled; /**< Hardware In the Loop mode */
|
||||
bool _use_hil_gps; /**< Accept GPS HIL messages (for example from an external motion capturing system to fake indoor gps) */
|
||||
bool _forward_externalsp; /**< Forward external setpoint messages to controllers directly if in offboard mode */
|
||||
bool _is_usb_uart; /**< Port is USB */
|
||||
bool _wait_to_transmit; /**< Wait to transmit until received messages. */
|
||||
bool _received_messages; /**< Whether we've received valid mavlink messages. */
|
||||
@ -349,6 +352,7 @@ private:
|
||||
param_t _param_component_id;
|
||||
param_t _param_system_type;
|
||||
param_t _param_use_hil_gps;
|
||||
param_t _param_forward_externalsp;
|
||||
|
||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||
perf_counter_t _txerr_perf; /**< TX error counter */
|
||||
|
||||
@ -37,6 +37,7 @@
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
@ -105,10 +106,11 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
|
||||
_flow_pub(-1),
|
||||
_range_pub(-1),
|
||||
_offboard_control_sp_pub(-1),
|
||||
_local_pos_sp_pub(-1),
|
||||
_global_vel_sp_pub(-1),
|
||||
_att_sp_pub(-1),
|
||||
_rates_sp_pub(-1),
|
||||
_force_sp_pub(-1),
|
||||
_pos_sp_triplet_pub(-1),
|
||||
_vicon_position_pub(-1),
|
||||
_vision_position_pub(-1),
|
||||
_telemetry_status_pub(-1),
|
||||
@ -154,6 +156,14 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
|
||||
handle_message_vicon_position_estimate(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
|
||||
handle_message_set_position_target_local_ned(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
|
||||
handle_message_set_attitude_target(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
|
||||
handle_message_vision_position_estimate(msg);
|
||||
break;
|
||||
@ -474,6 +484,189 @@ MavlinkReceiver::handle_message_vicon_position_estimate(mavlink_message_t *msg)
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t *msg)
|
||||
{
|
||||
mavlink_set_position_target_local_ned_t set_position_target_local_ned;
|
||||
mavlink_msg_set_position_target_local_ned_decode(msg, &set_position_target_local_ned);
|
||||
|
||||
struct offboard_control_setpoint_s offboard_control_sp;
|
||||
memset(&offboard_control_sp, 0, sizeof(offboard_control_sp));//XXX breaks compatibility with multiple setpoints
|
||||
|
||||
/* Only accept messages which are intended for this system */
|
||||
if ((mavlink_system.sysid == set_position_target_local_ned.target_system ||
|
||||
set_position_target_local_ned.target_system == 0) &&
|
||||
(mavlink_system.compid == set_position_target_local_ned.target_component ||
|
||||
set_position_target_local_ned.target_component == 0)) {
|
||||
|
||||
/* convert mavlink type (local, NED) to uORB offboard control struct */
|
||||
switch (set_position_target_local_ned.coordinate_frame) {
|
||||
case MAV_FRAME_LOCAL_NED:
|
||||
offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED;
|
||||
break;
|
||||
case MAV_FRAME_LOCAL_OFFSET_NED:
|
||||
offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_OFFSET_NED;
|
||||
break;
|
||||
case MAV_FRAME_BODY_NED:
|
||||
offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_BODY_NED;
|
||||
break;
|
||||
case MAV_FRAME_BODY_OFFSET_NED:
|
||||
offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_BODY_OFFSET_NED;
|
||||
break;
|
||||
default:
|
||||
/* invalid setpoint, avoid publishing */
|
||||
return;
|
||||
}
|
||||
offboard_control_sp.position[0] = set_position_target_local_ned.x;
|
||||
offboard_control_sp.position[1] = set_position_target_local_ned.y;
|
||||
offboard_control_sp.position[2] = set_position_target_local_ned.z;
|
||||
offboard_control_sp.velocity[0] = set_position_target_local_ned.vx;
|
||||
offboard_control_sp.velocity[1] = set_position_target_local_ned.vy;
|
||||
offboard_control_sp.velocity[2] = set_position_target_local_ned.vz;
|
||||
offboard_control_sp.acceleration[0] = set_position_target_local_ned.afx;
|
||||
offboard_control_sp.acceleration[1] = set_position_target_local_ned.afy;
|
||||
offboard_control_sp.acceleration[2] = set_position_target_local_ned.afz;
|
||||
offboard_control_sp.yaw = set_position_target_local_ned.yaw;
|
||||
offboard_control_sp.yaw_rate = set_position_target_local_ned.yaw_rate;
|
||||
offboard_control_sp.isForceSetpoint = (bool)(set_position_target_local_ned.type_mask & (1 << 9));
|
||||
|
||||
/* If we are in force control mode, for now set offboard mode to force control */
|
||||
if (offboard_control_sp.isForceSetpoint) {
|
||||
offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_FORCE;
|
||||
}
|
||||
|
||||
/* set ignore flags */
|
||||
for (int i = 0; i < 9; i++) {
|
||||
offboard_control_sp.ignore &= ~(1 << i);
|
||||
offboard_control_sp.ignore |= (set_position_target_local_ned.type_mask & (1 << i));
|
||||
}
|
||||
offboard_control_sp.ignore &= ~(1 << OFB_IGN_BIT_YAW);
|
||||
offboard_control_sp.ignore |= (set_position_target_local_ned.type_mask & (1 << 10)) <<
|
||||
OFB_IGN_BIT_YAW;
|
||||
offboard_control_sp.ignore &= ~(1 << OFB_IGN_BIT_YAWRATE);
|
||||
offboard_control_sp.ignore |= (set_position_target_local_ned.type_mask & (1 << 11)) <<
|
||||
OFB_IGN_BIT_YAWRATE;
|
||||
|
||||
offboard_control_sp.timestamp = hrt_absolute_time();
|
||||
|
||||
if (_offboard_control_sp_pub < 0) {
|
||||
_offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);
|
||||
|
||||
} else {
|
||||
orb_publish(ORB_ID(offboard_control_setpoint), _offboard_control_sp_pub, &offboard_control_sp);
|
||||
}
|
||||
|
||||
/* If we are in offboard control mode and offboard control loop through is enabled
|
||||
* also publish the setpoint topic which is read by the controller */
|
||||
if (_mavlink->get_forward_externalsp()) {
|
||||
bool updated;
|
||||
orb_check(_control_mode_sub, &updated);
|
||||
if (updated) {
|
||||
orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode);
|
||||
}
|
||||
if (_control_mode.flag_control_offboard_enabled) {
|
||||
if (offboard_control_sp.isForceSetpoint &&
|
||||
offboard_control_sp_ignore_position_all(offboard_control_sp) &&
|
||||
offboard_control_sp_ignore_velocity_all(offboard_control_sp)) {
|
||||
/* The offboard setpoint is a force setpoint only, directly writing to the force
|
||||
* setpoint topic and not publishing the setpoint triplet topic */
|
||||
struct vehicle_force_setpoint_s force_sp;
|
||||
force_sp.x = offboard_control_sp.acceleration[0];
|
||||
force_sp.y = offboard_control_sp.acceleration[1];
|
||||
force_sp.z = offboard_control_sp.acceleration[2];
|
||||
//XXX: yaw
|
||||
if (_force_sp_pub < 0) {
|
||||
_force_sp_pub = orb_advertise(ORB_ID(vehicle_force_setpoint), &force_sp);
|
||||
} else {
|
||||
orb_publish(ORB_ID(vehicle_force_setpoint), _force_sp_pub, &force_sp);
|
||||
}
|
||||
} else {
|
||||
/* It's not a pure force setpoint: publish to setpoint triplet topic */
|
||||
struct position_setpoint_triplet_s pos_sp_triplet;
|
||||
pos_sp_triplet.previous.valid = false;
|
||||
pos_sp_triplet.next.valid = false;
|
||||
pos_sp_triplet.current.valid = true;
|
||||
pos_sp_triplet.current.type = SETPOINT_TYPE_POSITION; //XXX support others
|
||||
|
||||
/* set the local pos values if the setpoint type is 'local pos' and none
|
||||
* of the local pos fields is set to 'ignore' */
|
||||
if (offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED &&
|
||||
!offboard_control_sp_ignore_position_some(offboard_control_sp)) {
|
||||
pos_sp_triplet.current.position_valid = true;
|
||||
pos_sp_triplet.current.x = offboard_control_sp.position[0];
|
||||
pos_sp_triplet.current.y = offboard_control_sp.position[1];
|
||||
pos_sp_triplet.current.z = offboard_control_sp.position[2];
|
||||
} else {
|
||||
pos_sp_triplet.current.position_valid = false;
|
||||
}
|
||||
|
||||
/* set the local vel values if the setpoint type is 'local pos' and none
|
||||
* of the local vel fields is set to 'ignore' */
|
||||
if (offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED &&
|
||||
!offboard_control_sp_ignore_velocity_some(offboard_control_sp)) {
|
||||
pos_sp_triplet.current.velocity_valid = true;
|
||||
pos_sp_triplet.current.vx = offboard_control_sp.velocity[0];
|
||||
pos_sp_triplet.current.vy = offboard_control_sp.velocity[1];
|
||||
pos_sp_triplet.current.vz = offboard_control_sp.velocity[2];
|
||||
} else {
|
||||
pos_sp_triplet.current.velocity_valid = false;
|
||||
}
|
||||
|
||||
/* set the local acceleration values if the setpoint type is 'local pos' and none
|
||||
* of the accelerations fields is set to 'ignore' */
|
||||
if (offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED &&
|
||||
!offboard_control_sp_ignore_acceleration_some(offboard_control_sp)) {
|
||||
pos_sp_triplet.current.acceleration_valid = true;
|
||||
pos_sp_triplet.current.a_x = offboard_control_sp.acceleration[0];
|
||||
pos_sp_triplet.current.a_y = offboard_control_sp.acceleration[1];
|
||||
pos_sp_triplet.current.a_z = offboard_control_sp.acceleration[2];
|
||||
pos_sp_triplet.current.acceleration_is_force =
|
||||
offboard_control_sp.isForceSetpoint;
|
||||
|
||||
} else {
|
||||
pos_sp_triplet.current.acceleration_valid = false;
|
||||
}
|
||||
|
||||
/* set the yaw sp value if the setpoint type is 'local pos' and the yaw
|
||||
* field is not set to 'ignore' */
|
||||
if (offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED &&
|
||||
!offboard_control_sp_ignore_yaw(offboard_control_sp)) {
|
||||
pos_sp_triplet.current.yaw_valid = true;
|
||||
pos_sp_triplet.current.yaw = offboard_control_sp.yaw;
|
||||
|
||||
} else {
|
||||
pos_sp_triplet.current.yaw_valid = false;
|
||||
}
|
||||
|
||||
/* set the yawrate sp value if the setpoint type is 'local pos' and the yawrate
|
||||
* field is not set to 'ignore' */
|
||||
if (offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED &&
|
||||
!offboard_control_sp_ignore_yawrate(offboard_control_sp)) {
|
||||
pos_sp_triplet.current.yawspeed_valid = true;
|
||||
pos_sp_triplet.current.yawspeed = offboard_control_sp.yaw_rate;
|
||||
|
||||
} else {
|
||||
pos_sp_triplet.current.yawspeed_valid = false;
|
||||
}
|
||||
//XXX handle global pos setpoints (different MAV frames)
|
||||
|
||||
|
||||
if (_pos_sp_triplet_pub < 0) {
|
||||
_pos_sp_triplet_pub = orb_advertise(ORB_ID(position_setpoint_triplet),
|
||||
&pos_sp_triplet);
|
||||
} else {
|
||||
orb_publish(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_pub,
|
||||
&pos_sp_triplet);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
MavlinkReceiver::handle_message_vision_position_estimate(mavlink_message_t *msg)
|
||||
{
|
||||
@ -513,6 +706,103 @@ MavlinkReceiver::handle_message_vision_position_estimate(mavlink_message_t *msg)
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
|
||||
{
|
||||
mavlink_set_attitude_target_t set_attitude_target;
|
||||
mavlink_msg_set_attitude_target_decode(msg, &set_attitude_target);
|
||||
|
||||
struct offboard_control_setpoint_s offboard_control_sp;
|
||||
memset(&offboard_control_sp, 0, sizeof(offboard_control_sp)); //XXX breaks compatibility with multiple setpoints
|
||||
|
||||
/* Only accept messages which are intended for this system */
|
||||
if ((mavlink_system.sysid == set_attitude_target.target_system ||
|
||||
set_attitude_target.target_system == 0) &&
|
||||
(mavlink_system.compid == set_attitude_target.target_component ||
|
||||
set_attitude_target.target_component == 0)) {
|
||||
for (int i = 0; i < 4; i++) {
|
||||
offboard_control_sp.attitude[i] = set_attitude_target.q[i];
|
||||
}
|
||||
offboard_control_sp.attitude_rate[0] = set_attitude_target.body_roll_rate;
|
||||
offboard_control_sp.attitude_rate[1] = set_attitude_target.body_pitch_rate;
|
||||
offboard_control_sp.attitude_rate[2] = set_attitude_target.body_yaw_rate;
|
||||
|
||||
/* set correct ignore flags for body rate fields: copy from mavlink message */
|
||||
for (int i = 0; i < 3; i++) {
|
||||
offboard_control_sp.ignore &= ~(1 << (i + OFB_IGN_BIT_BODYRATE_X));
|
||||
offboard_control_sp.ignore |= (set_attitude_target.type_mask & (1 << i)) << OFB_IGN_BIT_BODYRATE_X;
|
||||
}
|
||||
/* set correct ignore flags for thrust field: copy from mavlink message */
|
||||
offboard_control_sp.ignore &= ~(1 << OFB_IGN_BIT_THRUST);
|
||||
offboard_control_sp.ignore |= ((set_attitude_target.type_mask & (1 << 6)) << OFB_IGN_BIT_THRUST);
|
||||
/* set correct ignore flags for attitude field: copy from mavlink message */
|
||||
offboard_control_sp.ignore &= ~(1 << OFB_IGN_BIT_ATT);
|
||||
offboard_control_sp.ignore |= ((set_attitude_target.type_mask & (1 << 7)) << OFB_IGN_BIT_ATT);
|
||||
|
||||
|
||||
offboard_control_sp.timestamp = hrt_absolute_time();
|
||||
offboard_control_sp.mode =OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE; //XXX handle rate control mode
|
||||
|
||||
if (_offboard_control_sp_pub < 0) {
|
||||
_offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);
|
||||
|
||||
} else {
|
||||
orb_publish(ORB_ID(offboard_control_setpoint), _offboard_control_sp_pub, &offboard_control_sp);
|
||||
}
|
||||
|
||||
/* If we are in offboard control mode and offboard control loop through is enabled
|
||||
* also publish the setpoint topic which is read by the controller */
|
||||
if (_mavlink->get_forward_externalsp()) {
|
||||
bool updated;
|
||||
orb_check(_control_mode_sub, &updated);
|
||||
if (updated) {
|
||||
orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode);
|
||||
}
|
||||
|
||||
if (_control_mode.flag_control_offboard_enabled) {
|
||||
|
||||
/* Publish attitude setpoint if attitude and thrust ignore bits are not set */
|
||||
if (!(offboard_control_sp_ignore_attitude(offboard_control_sp) ||
|
||||
offboard_control_sp_ignore_thrust(offboard_control_sp))) {
|
||||
struct vehicle_attitude_setpoint_s att_sp;
|
||||
att_sp.timestamp = hrt_absolute_time();
|
||||
mavlink_quaternion_to_euler(set_attitude_target.q,
|
||||
&att_sp.roll_body, &att_sp.pitch_body, &att_sp.yaw_body);
|
||||
mavlink_quaternion_to_dcm(set_attitude_target.q, att_sp.R_body);
|
||||
att_sp.R_valid = true;
|
||||
att_sp.thrust = set_attitude_target.thrust;
|
||||
memcpy(att_sp.q_d, set_attitude_target.q, sizeof(att_sp.q_d));
|
||||
att_sp.q_d_valid = true;
|
||||
if (_att_sp_pub < 0) {
|
||||
_att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
|
||||
} else {
|
||||
orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &att_sp);
|
||||
}
|
||||
}
|
||||
|
||||
/* Publish attitude rate setpoint if bodyrate and thrust ignore bits are not set */
|
||||
///XXX add support for ignoring individual axes
|
||||
if (!(offboard_control_sp_ignore_bodyrates_some(offboard_control_sp) ||
|
||||
offboard_control_sp_ignore_thrust(offboard_control_sp))) {
|
||||
struct vehicle_rates_setpoint_s rates_sp;
|
||||
rates_sp.timestamp = hrt_absolute_time();
|
||||
rates_sp.roll = set_attitude_target.body_roll_rate;
|
||||
rates_sp.pitch = set_attitude_target.body_pitch_rate;
|
||||
rates_sp.yaw = set_attitude_target.body_yaw_rate;
|
||||
rates_sp.thrust = set_attitude_target.thrust;
|
||||
|
||||
if (_att_sp_pub < 0) {
|
||||
_rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
|
||||
} else {
|
||||
orb_publish(ORB_ID(vehicle_rates_setpoint), _rates_sp_pub, &rates_sp);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg)
|
||||
{
|
||||
|
||||
@ -71,6 +71,7 @@
|
||||
#include <uORB/topics/debug_key_value.h>
|
||||
#include <uORB/topics/airspeed.h>
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <uORB/topics/vehicle_force_setpoint.h>
|
||||
|
||||
#include "mavlink_ftp.h"
|
||||
|
||||
@ -117,6 +118,8 @@ private:
|
||||
void handle_message_vicon_position_estimate(mavlink_message_t *msg);
|
||||
void handle_message_vision_position_estimate(mavlink_message_t *msg);
|
||||
void handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg);
|
||||
void handle_message_set_position_target_local_ned(mavlink_message_t *msg);
|
||||
void handle_message_set_attitude_target(mavlink_message_t *msg);
|
||||
void handle_message_radio_status(mavlink_message_t *msg);
|
||||
void handle_message_manual_control(mavlink_message_t *msg);
|
||||
void handle_message_heartbeat(mavlink_message_t *msg);
|
||||
@ -145,10 +148,11 @@ private:
|
||||
orb_advert_t _flow_pub;
|
||||
orb_advert_t _range_pub;
|
||||
orb_advert_t _offboard_control_sp_pub;
|
||||
orb_advert_t _local_pos_sp_pub;
|
||||
orb_advert_t _global_vel_sp_pub;
|
||||
orb_advert_t _att_sp_pub;
|
||||
orb_advert_t _rates_sp_pub;
|
||||
orb_advert_t _force_sp_pub;
|
||||
orb_advert_t _pos_sp_triplet_pub;
|
||||
orb_advert_t _vicon_position_pub;
|
||||
orb_advert_t _vision_position_pub;
|
||||
orb_advert_t _telemetry_status_pub;
|
||||
|
||||
@ -653,7 +653,6 @@ MulticopterPositionControl::control_offboard(float dt)
|
||||
_pos_sp(0) = _pos_sp_triplet.current.x;
|
||||
_pos_sp(1) = _pos_sp_triplet.current.y;
|
||||
_pos_sp(2) = _pos_sp_triplet.current.z;
|
||||
_att_sp.yaw_body = _pos_sp_triplet.current.yaw;
|
||||
|
||||
} else if (_control_mode.flag_control_velocity_enabled && _pos_sp_triplet.current.velocity_valid) {
|
||||
/* control velocity */
|
||||
@ -663,6 +662,11 @@ MulticopterPositionControl::control_offboard(float dt)
|
||||
/* set position setpoint move rate */
|
||||
_sp_move_rate(0) = _pos_sp_triplet.current.vx;
|
||||
_sp_move_rate(1) = _pos_sp_triplet.current.vy;
|
||||
}
|
||||
|
||||
if (_pos_sp_triplet.current.yaw_valid) {
|
||||
_att_sp.yaw_body = _pos_sp_triplet.current.yaw;
|
||||
} else if (_pos_sp_triplet.current.yawspeed_valid) {
|
||||
_att_sp.yaw_body = _att_sp.yaw_body + _pos_sp_triplet.current.yawspeed * dt;
|
||||
}
|
||||
|
||||
|
||||
@ -46,7 +46,6 @@ SRCS = navigator_main.cpp \
|
||||
loiter.cpp \
|
||||
rtl.cpp \
|
||||
rtl_params.c \
|
||||
offboard.cpp \
|
||||
mission_feasibility_checker.cpp \
|
||||
geofence.cpp \
|
||||
geofence_params.c \
|
||||
|
||||
@ -60,7 +60,6 @@
|
||||
#include "mission.h"
|
||||
#include "loiter.h"
|
||||
#include "rtl.h"
|
||||
#include "offboard.h"
|
||||
#include "datalinkloss.h"
|
||||
#include "enginefailure.h"
|
||||
#include "gpsfailure.h"
|
||||
@ -70,7 +69,7 @@
|
||||
/**
|
||||
* Number of navigation modes that need on_active/on_inactive calls
|
||||
*/
|
||||
#define NAVIGATOR_MODE_ARRAY_SIZE 8
|
||||
#define NAVIGATOR_MODE_ARRAY_SIZE 7
|
||||
|
||||
class Navigator : public control::SuperBlock
|
||||
{
|
||||
@ -139,7 +138,6 @@ public:
|
||||
|
||||
int get_onboard_mission_sub() { return _onboard_mission_sub; }
|
||||
int get_offboard_mission_sub() { return _offboard_mission_sub; }
|
||||
int get_offboard_control_sp_sub() { return _offboard_control_sp_sub; }
|
||||
Geofence& get_geofence() { return _geofence; }
|
||||
bool get_can_loiter_at_sp() { return _can_loiter_at_sp; }
|
||||
float get_loiter_radius() { return _param_loiter_radius.get(); }
|
||||
@ -159,7 +157,6 @@ private:
|
||||
int _home_pos_sub; /**< home position subscription */
|
||||
int _vstatus_sub; /**< vehicle status subscription */
|
||||
int _capabilities_sub; /**< notification of vehicle capabilities updates */
|
||||
int _offboard_control_sp_sub; /*** offboard control subscription */
|
||||
int _control_mode_sub; /**< vehicle control mode subscription */
|
||||
int _onboard_mission_sub; /**< onboard mission subscription */
|
||||
int _offboard_mission_sub; /**< offboard mission subscription */
|
||||
@ -199,7 +196,6 @@ private:
|
||||
RTL _rtl; /**< class that handles RTL */
|
||||
RCLoss _rcLoss; /**< class that handles RTL according to
|
||||
OBC rules (rc loss mode) */
|
||||
Offboard _offboard; /**< class that handles offboard */
|
||||
DataLinkLoss _dataLinkLoss; /**< class that handles the OBC datalink loss mode */
|
||||
EngineFailure _engineFailure; /**< class that handles the engine failure mode
|
||||
(FW only!) */
|
||||
|
||||
@ -68,7 +68,6 @@
|
||||
#include <uORB/topics/mission.h>
|
||||
#include <uORB/topics/fence.h>
|
||||
#include <uORB/topics/navigation_capabilities.h>
|
||||
#include <uORB/topics/offboard_control_setpoint.h>
|
||||
#include <drivers/drv_baro.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
@ -105,7 +104,6 @@ Navigator::Navigator() :
|
||||
_home_pos_sub(-1),
|
||||
_vstatus_sub(-1),
|
||||
_capabilities_sub(-1),
|
||||
_offboard_control_sp_sub(-1),
|
||||
_control_mode_sub(-1),
|
||||
_onboard_mission_sub(-1),
|
||||
_offboard_mission_sub(-1),
|
||||
@ -134,7 +132,6 @@ Navigator::Navigator() :
|
||||
_loiter(this, "LOI"),
|
||||
_rtl(this, "RTL"),
|
||||
_rcLoss(this, "RCL"),
|
||||
_offboard(this, "OFF"),
|
||||
_dataLinkLoss(this, "DLL"),
|
||||
_engineFailure(this, "EF"),
|
||||
_gpsFailure(this, "GPSF"),
|
||||
@ -149,11 +146,10 @@ Navigator::Navigator() :
|
||||
_navigation_mode_array[0] = &_mission;
|
||||
_navigation_mode_array[1] = &_loiter;
|
||||
_navigation_mode_array[2] = &_rtl;
|
||||
_navigation_mode_array[3] = &_offboard;
|
||||
_navigation_mode_array[4] = &_dataLinkLoss;
|
||||
_navigation_mode_array[5] = &_engineFailure;
|
||||
_navigation_mode_array[6] = &_gpsFailure;
|
||||
_navigation_mode_array[7] = &_rcLoss;
|
||||
_navigation_mode_array[3] = &_dataLinkLoss;
|
||||
_navigation_mode_array[4] = &_engineFailure;
|
||||
_navigation_mode_array[5] = &_gpsFailure;
|
||||
_navigation_mode_array[6] = &_rcLoss;
|
||||
|
||||
updateParams();
|
||||
}
|
||||
@ -282,7 +278,6 @@ Navigator::task_main()
|
||||
_onboard_mission_sub = orb_subscribe(ORB_ID(onboard_mission));
|
||||
_offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission));
|
||||
_param_update_sub = orb_subscribe(ORB_ID(parameter_update));
|
||||
_offboard_control_sp_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
|
||||
|
||||
/* copy all topics first time */
|
||||
vehicle_status_update();
|
||||
@ -388,11 +383,9 @@ Navigator::task_main()
|
||||
/* global position updated */
|
||||
if (fds[0].revents & POLLIN) {
|
||||
global_position_update();
|
||||
static int gposcounter = 0;
|
||||
if (_geofence.getSource() == Geofence::GF_SOURCE_GLOBALPOS) {
|
||||
have_geofence_position_data = true;
|
||||
}
|
||||
gposcounter++;
|
||||
}
|
||||
|
||||
/* Check geofence violation */
|
||||
@ -428,6 +421,7 @@ Navigator::task_main()
|
||||
case NAVIGATION_STATE_POSCTL:
|
||||
case NAVIGATION_STATE_LAND:
|
||||
case NAVIGATION_STATE_TERMINATION:
|
||||
case NAVIGATION_STATE_OFFBOARD:
|
||||
_navigation_mode = nullptr;
|
||||
_can_loiter_at_sp = false;
|
||||
break;
|
||||
@ -462,9 +456,6 @@ Navigator::task_main()
|
||||
case NAVIGATION_STATE_AUTO_LANDGPSFAIL:
|
||||
_navigation_mode = &_gpsFailure;
|
||||
break;
|
||||
case NAVIGATION_STATE_OFFBOARD:
|
||||
_navigation_mode = &_offboard;
|
||||
break;
|
||||
default:
|
||||
_navigation_mode = nullptr;
|
||||
_can_loiter_at_sp = false;
|
||||
|
||||
@ -1,129 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2014 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 offboard.cpp
|
||||
*
|
||||
* Helper class for offboard commands
|
||||
*
|
||||
* @author Julian Oes <julian@oes.ch>
|
||||
*/
|
||||
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdbool.h>
|
||||
#include <math.h>
|
||||
#include <fcntl.h>
|
||||
|
||||
#include <mavlink/mavlink_log.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
|
||||
#include "navigator.h"
|
||||
#include "offboard.h"
|
||||
|
||||
Offboard::Offboard(Navigator *navigator, const char *name) :
|
||||
NavigatorMode(navigator, name),
|
||||
_offboard_control_sp({0})
|
||||
{
|
||||
/* load initial params */
|
||||
updateParams();
|
||||
/* initial reset */
|
||||
on_inactive();
|
||||
}
|
||||
|
||||
Offboard::~Offboard()
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
Offboard::on_inactive()
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
Offboard::on_activation()
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
Offboard::on_active()
|
||||
{
|
||||
struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
|
||||
|
||||
bool updated;
|
||||
orb_check(_navigator->get_offboard_control_sp_sub(), &updated);
|
||||
if (updated) {
|
||||
update_offboard_control_setpoint();
|
||||
}
|
||||
|
||||
/* copy offboard setpoints to the corresponding topics */
|
||||
if (_navigator->get_control_mode()->flag_control_position_enabled
|
||||
&& _offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION) {
|
||||
/* position control */
|
||||
pos_sp_triplet->current.x = _offboard_control_sp.p1;
|
||||
pos_sp_triplet->current.y = _offboard_control_sp.p2;
|
||||
pos_sp_triplet->current.yaw = _offboard_control_sp.p3;
|
||||
pos_sp_triplet->current.z = -_offboard_control_sp.p4;
|
||||
|
||||
pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD;
|
||||
pos_sp_triplet->current.valid = true;
|
||||
pos_sp_triplet->current.position_valid = true;
|
||||
|
||||
_navigator->set_position_setpoint_triplet_updated();
|
||||
|
||||
} else if (_navigator->get_control_mode()->flag_control_velocity_enabled
|
||||
&& _offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY) {
|
||||
/* velocity control */
|
||||
pos_sp_triplet->current.vx = _offboard_control_sp.p2;
|
||||
pos_sp_triplet->current.vy = _offboard_control_sp.p1;
|
||||
pos_sp_triplet->current.yawspeed = _offboard_control_sp.p3;
|
||||
pos_sp_triplet->current.vz = _offboard_control_sp.p4;
|
||||
|
||||
pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD;
|
||||
pos_sp_triplet->current.valid = true;
|
||||
pos_sp_triplet->current.velocity_valid = true;
|
||||
|
||||
_navigator->set_position_setpoint_triplet_updated();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
Offboard::update_offboard_control_setpoint()
|
||||
{
|
||||
orb_copy(ORB_ID(offboard_control_setpoint), _navigator->get_offboard_control_sp_sub(), &_offboard_control_sp);
|
||||
|
||||
}
|
||||
@ -53,11 +53,42 @@ enum OFFBOARD_CONTROL_MODE {
|
||||
OFFBOARD_CONTROL_MODE_DIRECT = 0,
|
||||
OFFBOARD_CONTROL_MODE_DIRECT_RATES = 1,
|
||||
OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE = 2,
|
||||
OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY = 3,
|
||||
OFFBOARD_CONTROL_MODE_DIRECT_POSITION = 4,
|
||||
OFFBOARD_CONTROL_MODE_ATT_YAW_RATE = 5,
|
||||
OFFBOARD_CONTROL_MODE_ATT_YAW_POS = 6,
|
||||
OFFBOARD_CONTROL_MODE_MULTIROTOR_SIMPLE = 7, /**< roll / pitch rotated aligned to the takeoff orientation, throttle stabilized, yaw pos */
|
||||
OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED = 3,
|
||||
OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_OFFSET_NED = 4,
|
||||
OFFBOARD_CONTROL_MODE_DIRECT_BODY_NED = 5,
|
||||
OFFBOARD_CONTROL_MODE_DIRECT_BODY_OFFSET_NED = 6,
|
||||
OFFBOARD_CONTROL_MODE_DIRECT_GLOBAL = 7,
|
||||
OFFBOARD_CONTROL_MODE_DIRECT_FORCE = 8,
|
||||
OFFBOARD_CONTROL_MODE_ATT_YAW_RATE = 9,
|
||||
OFFBOARD_CONTROL_MODE_ATT_YAW_POS = 10,
|
||||
OFFBOARD_CONTROL_MODE_MULTIROTOR_SIMPLE = 11 /**< roll / pitch rotated aligned to the takeoff orientation, throttle stabilized, yaw pos */
|
||||
};
|
||||
|
||||
enum OFFBOARD_CONTROL_FRAME {
|
||||
OFFBOARD_CONTROL_FRAME_LOCAL_NED = 0,
|
||||
OFFBOARD_CONTROL_FRAME_LOCAL_OFFSET_NED = 1,
|
||||
OFFBOARD_CONTROL_FRAME_BODY_NED = 2,
|
||||
OFFBOARD_CONTROL_FRAME_BODY_OFFSET_NED = 3,
|
||||
OFFBOARD_CONTROL_FRAME_GLOBAL = 4
|
||||
};
|
||||
|
||||
/* mappings for the ignore bitmask */
|
||||
enum {OFB_IGN_BIT_POS_X,
|
||||
OFB_IGN_BIT_POS_Y,
|
||||
OFB_IGN_BIT_POS_Z,
|
||||
OFB_IGN_BIT_VEL_X,
|
||||
OFB_IGN_BIT_VEL_Y,
|
||||
OFB_IGN_BIT_VEL_Z,
|
||||
OFB_IGN_BIT_ACC_X,
|
||||
OFB_IGN_BIT_ACC_Y,
|
||||
OFB_IGN_BIT_ACC_Z,
|
||||
OFB_IGN_BIT_BODYRATE_X,
|
||||
OFB_IGN_BIT_BODYRATE_Y,
|
||||
OFB_IGN_BIT_BODYRATE_Z,
|
||||
OFB_IGN_BIT_ATT,
|
||||
OFB_IGN_BIT_THRUST,
|
||||
OFB_IGN_BIT_YAW,
|
||||
OFB_IGN_BIT_YAWRATE,
|
||||
};
|
||||
|
||||
/**
|
||||
@ -70,10 +101,21 @@ struct offboard_control_setpoint_s {
|
||||
|
||||
enum OFFBOARD_CONTROL_MODE mode; /**< The current control inputs mode */
|
||||
|
||||
float p1; /**< ailerons roll / roll rate input */
|
||||
float p2; /**< elevator / pitch / pitch rate */
|
||||
float p3; /**< rudder / yaw rate / yaw */
|
||||
float p4; /**< throttle / collective thrust / altitude */
|
||||
double position[3]; /**< lat, lon, alt / x, y, z */
|
||||
float velocity[3]; /**< x vel, y vel, z vel */
|
||||
float acceleration[3]; /**< x acc, y acc, z acc */
|
||||
float attitude[4]; /**< attitude of vehicle (quaternion) */
|
||||
float attitude_rate[3]; /**< body angular rates (x, y, z) */
|
||||
float thrust; /**< thrust */
|
||||
float yaw; /**< yaw: this is the yaw from the position_target message
|
||||
(not from the full attitude_target message) */
|
||||
float yaw_rate; /**< yaw rate: this is the yaw from the position_target message
|
||||
(not from the full attitude_target message) */
|
||||
|
||||
uint16_t ignore; /**< if field i is set to true, the value should be ignored, see definition at top of file
|
||||
for mapping */
|
||||
|
||||
bool isForceSetpoint; /**< the acceleration vector should be interpreted as force */
|
||||
|
||||
float override_mode_switch;
|
||||
|
||||
@ -87,6 +129,147 @@ struct offboard_control_setpoint_s {
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* Returns true if the position setpoint at index should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_position(const struct offboard_control_setpoint_s &offboard_control_sp, int index) {
|
||||
return (bool)(offboard_control_sp.ignore & (1 << (OFB_IGN_BIT_POS_X + index)));
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if all position setpoints should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_position_all(const struct offboard_control_setpoint_s &offboard_control_sp) {
|
||||
for (int i = 0; i < 3; i++) {
|
||||
if (!offboard_control_sp_ignore_position(offboard_control_sp, i)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if some position setpoints should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_position_some(const struct offboard_control_setpoint_s &offboard_control_sp) {
|
||||
for (int i = 0; i < 3; i++) {
|
||||
if (offboard_control_sp_ignore_position(offboard_control_sp, i)) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if the velocity setpoint at index should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_velocity(const struct offboard_control_setpoint_s &offboard_control_sp, int index) {
|
||||
return (bool)(offboard_control_sp.ignore & (1 << (OFB_IGN_BIT_VEL_X + index)));
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if all velocity setpoints should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_velocity_all(const struct offboard_control_setpoint_s &offboard_control_sp) {
|
||||
for (int i = 0; i < 3; i++) {
|
||||
if (!offboard_control_sp_ignore_velocity(offboard_control_sp, i)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if some velocity setpoints should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_velocity_some(const struct offboard_control_setpoint_s &offboard_control_sp) {
|
||||
for (int i = 0; i < 3; i++) {
|
||||
if (offboard_control_sp_ignore_velocity(offboard_control_sp, i)) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if the acceleration setpoint at index should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_acceleration(const struct offboard_control_setpoint_s &offboard_control_sp, int index) {
|
||||
return (bool)(offboard_control_sp.ignore & (1 << (OFB_IGN_BIT_ACC_X + index)));
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if all acceleration setpoints should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_acceleration_all(const struct offboard_control_setpoint_s &offboard_control_sp) {
|
||||
for (int i = 0; i < 3; i++) {
|
||||
if (!offboard_control_sp_ignore_acceleration(offboard_control_sp, i)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if some acceleration setpoints should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_acceleration_some(const struct offboard_control_setpoint_s &offboard_control_sp) {
|
||||
for (int i = 0; i < 3; i++) {
|
||||
if (offboard_control_sp_ignore_acceleration(offboard_control_sp, i)) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if the bodyrate setpoint at index should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_bodyrates(const struct offboard_control_setpoint_s &offboard_control_sp, int index) {
|
||||
return (bool)(offboard_control_sp.ignore & (1 << (OFB_IGN_BIT_BODYRATE_X + index)));
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if some of the bodyrate setpoints should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_bodyrates_some(const struct offboard_control_setpoint_s &offboard_control_sp) {
|
||||
for (int i = 0; i < 3; i++) {
|
||||
if (offboard_control_sp_ignore_bodyrates(offboard_control_sp, i)) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if the attitude setpoint should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_attitude(const struct offboard_control_setpoint_s &offboard_control_sp) {
|
||||
return (bool)(offboard_control_sp.ignore & (1 << OFB_IGN_BIT_ATT));
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if the thrust setpoint should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_thrust(const struct offboard_control_setpoint_s &offboard_control_sp) {
|
||||
return (bool)(offboard_control_sp.ignore & (1 << OFB_IGN_BIT_THRUST));
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if the yaw setpoint should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_yaw(const struct offboard_control_setpoint_s &offboard_control_sp) {
|
||||
return (bool)(offboard_control_sp.ignore & (1 << OFB_IGN_BIT_YAW));
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if the yaw rate setpoint should be ignored
|
||||
*/
|
||||
inline bool offboard_control_sp_ignore_yawrate(const struct offboard_control_setpoint_s &offboard_control_sp) {
|
||||
return (bool)(offboard_control_sp.ignore & (1 << OFB_IGN_BIT_YAWRATE));
|
||||
}
|
||||
|
||||
|
||||
/* register this as object request broker structure */
|
||||
ORB_DECLARE(offboard_control_setpoint);
|
||||
|
||||
|
||||
@ -79,10 +79,17 @@ struct position_setpoint_s
|
||||
double lon; /**< longitude, in deg */
|
||||
float alt; /**< altitude AMSL, in m */
|
||||
float yaw; /**< yaw (only for multirotors), in rad [-PI..PI), NaN = hold current yaw */
|
||||
bool yaw_valid; /**< true if yaw setpoint valid */
|
||||
float yawspeed; /**< yawspeed (only for multirotors, in rad/s) */
|
||||
bool yawspeed_valid; /**< true if yawspeed setpoint valid */
|
||||
float loiter_radius; /**< loiter radius (only for fixed wing), in m */
|
||||
int8_t loiter_direction; /**< loiter direction: 1 = CW, -1 = CCW */
|
||||
float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
|
||||
float a_x; //**< acceleration x setpoint */
|
||||
float a_y; //**< acceleration y setpoint */
|
||||
float a_z; //**< acceleration z setpoint */
|
||||
bool acceleration_valid; //*< true if acceleration setpoint is valid/should be used */
|
||||
bool acceleration_is_force; //*< interprete acceleration as force */
|
||||
};
|
||||
|
||||
/**
|
||||
|
||||
@ -65,6 +65,9 @@ enum VEHICLE_CMD {
|
||||
VEHICLE_CMD_NAV_TAKEOFF = 22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_ROI = 80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
|
||||
VEHICLE_CMD_NAV_PATHPLANNING = 81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
|
||||
VEHICLE_CMD_NAV_GUIDED_LIMITS=90, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_NAV_GUIDED_MASTER=91, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_NAV_LAST = 95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_CONDITION_DELAY = 112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_CONDITION_CHANGE_ALT = 113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
|
||||
|
||||
@ -77,6 +77,7 @@ struct vehicle_control_mode_s {
|
||||
bool flag_control_offboard_enabled; /**< true if offboard control should be used */
|
||||
bool flag_control_rates_enabled; /**< true if rates are stabilized */
|
||||
bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
|
||||
bool flag_control_force_enabled; /**< true if force control is mixed in */
|
||||
bool flag_control_velocity_enabled; /**< true if horizontal velocity (implies direction) is controlled */
|
||||
bool flag_control_position_enabled; /**< true if position is controlled */
|
||||
bool flag_control_altitude_enabled; /**< true if altitude is controlled */
|
||||
|
||||
@ -218,6 +218,8 @@ struct vehicle_status_s {
|
||||
bool offboard_control_signal_lost;
|
||||
bool offboard_control_signal_weak;
|
||||
uint64_t offboard_control_signal_lost_interval; /**< interval in microseconds without an offboard control message */
|
||||
bool offboard_control_set_by_command; /**< true if the offboard mode was set by a mavlink command
|
||||
and should not be overridden by RC */
|
||||
|
||||
/* see SYS_STATUS mavlink message for the following */
|
||||
uint32_t onboard_control_sensors_present;
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user