mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Merge remote-tracking branch 'upstream/master' into obcfailsafe
This commit is contained in:
commit
f78ea38d98
@ -11,4 +11,8 @@ then
|
||||
param set NAV_RTL_ALT 100
|
||||
param set NAV_RTL_LAND_T -1
|
||||
param set NAV_ACCEPT_RAD 50
|
||||
param set FW_T_HRATE_P 0.01
|
||||
param set FW_T_RLL2THR 15
|
||||
param set FW_T_SRATE_P 0.01
|
||||
param set FW_T_TIME_CONST 5
|
||||
fi
|
||||
@ -3,8 +3,12 @@
|
||||
# USB MAVLink start
|
||||
#
|
||||
|
||||
mavlink start -r 10000 -d /dev/ttyACM0 -x
|
||||
mavlink start -r 20000 -d /dev/ttyACM0 -x
|
||||
# Enable a number of interesting streams we want via USB
|
||||
mavlink stream -d /dev/ttyACM0 -s PARAM_VALUE -r 200
|
||||
usleep 100000
|
||||
mavlink stream -d /dev/ttyACM0 -s MISSION_ITEM -r 50
|
||||
usleep 100000
|
||||
mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10
|
||||
usleep 100000
|
||||
mavlink stream -d /dev/ttyACM0 -s OPTICAL_FLOW -r 10
|
||||
@ -15,6 +19,8 @@ mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 20
|
||||
usleep 100000
|
||||
mavlink stream -d /dev/ttyACM0 -s ATTITUDE_CONTROLS -r 30
|
||||
usleep 100000
|
||||
mavlink stream -d /dev/ttyACM0 -s RC_CHANNELS_RAW -r 5
|
||||
usleep 100000
|
||||
mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
|
||||
usleep 100000
|
||||
mavlink stream -d /dev/ttyACM0 -s GLOBAL_POSITION_SETPOINT_INT -r 20
|
||||
|
||||
207
Tools/fetch_file.py
Normal file
207
Tools/fetch_file.py
Normal file
@ -0,0 +1,207 @@
|
||||
#!/usr/bin/env python
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
"""Fetch files via nsh console
|
||||
|
||||
Usage: python fetch_file.py [-l] [-f] [-d device] [-s speed] [-o out_path] path
|
||||
\t-l\tList files
|
||||
\t-f\tOverwrite existing files
|
||||
\t-d\tSerial device
|
||||
\t-s\tSerial baudrate
|
||||
\t-o\tOutput path
|
||||
\tpath\tPath to list/fetch, if ends with "/" then directory will be fetched recursively"""
|
||||
|
||||
__author__ = "Anton Babushkin"
|
||||
__version__ = "1.1"
|
||||
|
||||
import serial, time, sys, os
|
||||
|
||||
def _wait_for_string(ser, s, timeout):
|
||||
t0 = time.time()
|
||||
buf = []
|
||||
res = []
|
||||
while (True):
|
||||
c = ser.read()
|
||||
buf.append(c)
|
||||
if len(buf) > len(s):
|
||||
res.append(buf.pop(0))
|
||||
if "".join(buf) == s:
|
||||
break
|
||||
if timeout > 0.0 and time.time() - t0 > timeout:
|
||||
raise Exception("Timeout while waiting for: " + s)
|
||||
return "".join(res)
|
||||
|
||||
def _exec_cmd(ser, cmd, timeout):
|
||||
ser.write(cmd + "\n")
|
||||
ser.flush()
|
||||
_wait_for_string(ser, cmd + "\r\n", timeout)
|
||||
return _wait_for_string(ser, "nsh> \x1b[K", timeout)
|
||||
|
||||
def _ls_dir_raw(ser, dir, timeout):
|
||||
return _exec_cmd(ser, "ls -l " + dir, timeout)
|
||||
|
||||
def _ls_dir(ser, dir, timeout):
|
||||
res = []
|
||||
for line in _ls_dir_raw(ser, dir, timeout).splitlines():
|
||||
if line == dir + ":":
|
||||
continue
|
||||
if line.startswith("nsh: ls: no such directory:"):
|
||||
raise Exception("No such file: " + dir)
|
||||
res.append((line[20:], int(line[11:19].strip()), line[1] == "d"))
|
||||
return res
|
||||
|
||||
def _get_file(ser, fn, fn_out, force, timeout):
|
||||
print "Get %s:" % fn,
|
||||
if not force:
|
||||
# Check if file already exists with the same size
|
||||
try:
|
||||
os.stat(fn_out)
|
||||
except:
|
||||
pass
|
||||
else:
|
||||
print "already fetched, skip"
|
||||
return
|
||||
|
||||
cmd = "dumpfile " + fn
|
||||
ser.write(cmd + "\n")
|
||||
ser.flush()
|
||||
_wait_for_string(ser, cmd + "\r\n", timeout)
|
||||
res = _wait_for_string(ser, "\n", timeout)
|
||||
if res.startswith("OK"):
|
||||
# Got correct responce, open temp file
|
||||
fn_out_part = fn_out + ".part"
|
||||
fout = open(fn_out_part, "wb")
|
||||
|
||||
size = int(res.split()[1])
|
||||
sys.stdout.write(" [%i bytes] " % size)
|
||||
n = 0
|
||||
while (n < size):
|
||||
buf = ser.read(min(size - n, 8192))
|
||||
n += len(buf)
|
||||
sys.stdout.write(".")
|
||||
sys.stdout.flush()
|
||||
fout.write(buf)
|
||||
print " done"
|
||||
fout.close()
|
||||
os.rename(fn_out_part, fn_out)
|
||||
else:
|
||||
raise Exception("Error reading file")
|
||||
_wait_for_string(ser, "nsh> \x1b[K", timeout)
|
||||
|
||||
def _get_files_in_dir(ser, path, path_out, force, timeout):
|
||||
try:
|
||||
os.mkdir(path_out)
|
||||
except:
|
||||
pass
|
||||
for fn in _ls_dir(ser, path, timeout):
|
||||
path_fn = os.path.join(path, fn[0])
|
||||
path_fn_out = os.path.join(path_out, fn[0])
|
||||
if fn[2]:
|
||||
_get_files_in_dir(ser, path_fn[:-1], path_fn_out[:-1], force, timeout)
|
||||
else:
|
||||
_get_file(ser, path_fn, path_fn_out, force, timeout)
|
||||
|
||||
def _usage():
|
||||
print """Usage: python fetch_file.py [-l] [-f] [-d device] [-s speed] [-o out_path] path
|
||||
\t-l\tList files
|
||||
\t-f\tOverwrite existing files
|
||||
\t-d\tSerial device
|
||||
\t-s\tSerial baudrate
|
||||
\t-o\tOutput path
|
||||
\tpath\tPath to list/fetch, if ends with "/" then directory will be fetched recursively"""
|
||||
|
||||
def _main():
|
||||
dev = "/dev/tty.usbmodem1"
|
||||
speed = "57600"
|
||||
cmd = "get"
|
||||
path = None
|
||||
path_out = None
|
||||
force = False
|
||||
|
||||
opt = None
|
||||
for arg in sys.argv[1:]:
|
||||
if opt != None:
|
||||
if opt == "d":
|
||||
dev = arg
|
||||
elif opt == "s":
|
||||
speed = arg
|
||||
elif opt == "o":
|
||||
path_out = arg
|
||||
opt = None
|
||||
else:
|
||||
if arg == "-l":
|
||||
cmd = "ls"
|
||||
elif arg == "-f":
|
||||
force = True
|
||||
elif arg == "-d":
|
||||
opt = "d"
|
||||
elif arg == "-s":
|
||||
opt = "s"
|
||||
elif arg == "-o":
|
||||
opt = "o"
|
||||
elif path == None:
|
||||
path = arg
|
||||
|
||||
if path == None:
|
||||
_usage()
|
||||
exit(0)
|
||||
|
||||
# Connect to serial port
|
||||
ser = serial.Serial(dev, speed, timeout=0.2)
|
||||
|
||||
timeout = 1.0
|
||||
|
||||
try:
|
||||
if cmd == "ls":
|
||||
# List directory
|
||||
print _ls_dir_raw(ser, path, timeout)
|
||||
elif cmd == "get":
|
||||
# Get file(s)
|
||||
if path.endswith("/"):
|
||||
# Get all files from directory recursively
|
||||
if path_out == None:
|
||||
path_out = os.path.split(path[:-1])[1]
|
||||
_get_files_in_dir(ser, path[:-1], path_out, force, timeout)
|
||||
else:
|
||||
# Get one file
|
||||
if path_out == None:
|
||||
path_out = os.path.split(path)[1]
|
||||
_get_file(ser, path, os.path.split(path)[1], force, timeout)
|
||||
except Exception as e:
|
||||
print e
|
||||
|
||||
ser.close()
|
||||
|
||||
if __name__ == "__main__":
|
||||
_main()
|
||||
@ -1,133 +0,0 @@
|
||||
#!/usr/bin/env python
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Log fetcher
|
||||
#
|
||||
# Print list of logs:
|
||||
# python fetch_log.py
|
||||
#
|
||||
# Fetch log:
|
||||
# python fetch_log.py sess001/log001.bin
|
||||
#
|
||||
|
||||
import serial, time, sys, os
|
||||
|
||||
def wait_for_string(ser, s, timeout=1.0, debug=False):
|
||||
t0 = time.time()
|
||||
buf = []
|
||||
res = []
|
||||
n = 0
|
||||
while (True):
|
||||
c = ser.read()
|
||||
if debug:
|
||||
sys.stderr.write(c)
|
||||
buf.append(c)
|
||||
if len(buf) > len(s):
|
||||
res.append(buf.pop(0))
|
||||
n += 1
|
||||
if n % 10000 == 0:
|
||||
sys.stderr.write(str(n) + "\n")
|
||||
if "".join(buf) == s:
|
||||
break
|
||||
if timeout > 0.0 and time.time() - t0 > timeout:
|
||||
raise Exception("Timeout while waiting for: " + s)
|
||||
return "".join(res)
|
||||
|
||||
def exec_cmd(ser, cmd, timeout):
|
||||
ser.write(cmd + "\n")
|
||||
ser.flush()
|
||||
wait_for_string(ser, cmd + "\r\n", timeout)
|
||||
return wait_for_string(ser, "nsh> \x1b[K", timeout)
|
||||
|
||||
def ls_dir(ser, dir, timeout=1.0):
|
||||
res = []
|
||||
for line in exec_cmd(ser, "ls -l " + dir, timeout).splitlines()[1:]:
|
||||
res.append((line[20:], int(line[11:19].strip()), line[1] == "d"))
|
||||
return res
|
||||
|
||||
def list_logs(ser):
|
||||
logs_dir = "/fs/microsd/log"
|
||||
res = []
|
||||
for d in ls_dir(ser, logs_dir):
|
||||
if d[2]:
|
||||
sess_dir = d[0][:-1]
|
||||
for f in ls_dir(ser, logs_dir + "/" + sess_dir):
|
||||
log_file = f[0]
|
||||
log_size = f[1]
|
||||
res.append(sess_dir + "/" + log_file + "\t" + str(log_size))
|
||||
return "\n".join(res)
|
||||
|
||||
def fetch_log(ser, fn, timeout):
|
||||
cmd = "dumpfile " + fn
|
||||
ser.write(cmd + "\n")
|
||||
ser.flush()
|
||||
wait_for_string(ser, cmd + "\r\n", timeout, True)
|
||||
res = wait_for_string(ser, "\n", timeout, True)
|
||||
data = []
|
||||
if res.startswith("OK"):
|
||||
size = int(res.split()[1])
|
||||
n = 0
|
||||
print "Reading data:"
|
||||
while (n < size):
|
||||
buf = ser.read(min(size - n, 8192))
|
||||
data.append(buf)
|
||||
n += len(buf)
|
||||
sys.stdout.write(".")
|
||||
sys.stdout.flush()
|
||||
print
|
||||
else:
|
||||
raise Exception("Error reading log")
|
||||
wait_for_string(ser, "nsh> \x1b[K", timeout)
|
||||
return "".join(data)
|
||||
|
||||
def main():
|
||||
dev = "/dev/tty.usbmodem1"
|
||||
ser = serial.Serial(dev, "115200", timeout=0.2)
|
||||
if len(sys.argv) < 2:
|
||||
print list_logs(ser)
|
||||
else:
|
||||
log_file = sys.argv[1]
|
||||
data = fetch_log(ser, "/fs/microsd/log/" + log_file, 1.0)
|
||||
try:
|
||||
os.mkdir(log_file.split("/")[0])
|
||||
except:
|
||||
pass
|
||||
fout = open(log_file, "wb")
|
||||
fout.write(data)
|
||||
fout.close()
|
||||
ser.close()
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
@ -149,7 +149,8 @@ class SDLog2Parser:
|
||||
break
|
||||
if first_data_msg:
|
||||
# build CSV columns and init data map
|
||||
self.__initCSV()
|
||||
if not self.__debug_out:
|
||||
self.__initCSV()
|
||||
first_data_msg = False
|
||||
self.__parseMsg(msg_descr)
|
||||
bytes_read += self.__ptr
|
||||
|
||||
@ -80,6 +80,7 @@ LIBRARIES += lib/mathlib/CMSIS
|
||||
MODULES += lib/mathlib
|
||||
MODULES += lib/mathlib/math/filter
|
||||
MODULES += lib/ecl
|
||||
MODULES += lib/external_lgpl
|
||||
MODULES += lib/geo
|
||||
MODULES += lib/geo_lookup
|
||||
MODULES += lib/conversion
|
||||
|
||||
@ -108,6 +108,7 @@ LIBRARIES += lib/mathlib/CMSIS
|
||||
MODULES += lib/mathlib
|
||||
MODULES += lib/mathlib/math/filter
|
||||
MODULES += lib/ecl
|
||||
MODULES += lib/external_lgpl
|
||||
MODULES += lib/geo
|
||||
MODULES += lib/geo_lookup
|
||||
MODULES += lib/conversion
|
||||
|
||||
@ -121,6 +121,7 @@ LIBRARIES += lib/mathlib/CMSIS
|
||||
MODULES += lib/mathlib
|
||||
MODULES += lib/mathlib/math/filter
|
||||
MODULES += lib/ecl
|
||||
MODULES += lib/external_lgpl
|
||||
MODULES += lib/geo
|
||||
MODULES += lib/geo_lookup
|
||||
MODULES += lib/conversion
|
||||
|
||||
@ -150,6 +150,7 @@ enum {
|
||||
TONE_ARMING_FAILURE_TUNE,
|
||||
TONE_PARACHUTE_RELEASE_TUNE,
|
||||
TONE_EKF_WARNING_TUNE,
|
||||
TONE_BARO_WARNING_TUNE,
|
||||
TONE_NUMBER_OF_TUNES
|
||||
};
|
||||
|
||||
|
||||
@ -92,7 +92,7 @@
|
||||
#include <drivers/airspeed/airspeed.h>
|
||||
|
||||
/* I2C bus address is 1010001x */
|
||||
#define I2C_ADDRESS_MS4525DO 0x28 //0x51 /* 7-bit address. */
|
||||
#define I2C_ADDRESS_MS4525DO 0x28 /**< 7-bit address. Depends on the order code (this is for code "I") */
|
||||
#define PATH_MS4525 "/dev/ms4525"
|
||||
/* The MS5525DSO address is 111011Cx, where C is the complementary value of the pin CSB */
|
||||
#define I2C_ADDRESS_MS5525DSO 0x77 //0x77/* 7-bit address, addr. pin pulled low */
|
||||
@ -102,9 +102,9 @@
|
||||
#define ADDR_READ_MR 0x00 /* write to this address to start conversion */
|
||||
|
||||
/* Measurement rate is 100Hz */
|
||||
#define MEAS_RATE 100.0f
|
||||
#define MEAS_DRIVER_FILTER_FREQ 3.0f
|
||||
#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
|
||||
#define MEAS_RATE 100
|
||||
#define MEAS_DRIVER_FILTER_FREQ 1.5f
|
||||
#define CONVERSION_INTERVAL (1000000 / MEAS_RATE) /* microseconds */
|
||||
|
||||
class MEASAirspeed : public Airspeed
|
||||
{
|
||||
|
||||
@ -157,6 +157,10 @@ private:
|
||||
perf_counter_t _pc_idle;
|
||||
perf_counter_t _pc_badidle;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
PX4IO_serial(PX4IO_serial &);
|
||||
PX4IO_serial& operator = (const PX4IO_serial &);
|
||||
|
||||
};
|
||||
|
||||
IOPacket PX4IO_serial::_dma_buffer;
|
||||
@ -173,7 +177,9 @@ PX4IO_serial::PX4IO_serial() :
|
||||
_tx_dma(nullptr),
|
||||
_rx_dma(nullptr),
|
||||
_rx_dma_status(_dma_status_inactive),
|
||||
_pc_txns(perf_alloc(PC_ELAPSED, "io_txns ")),
|
||||
_bus_semaphore(SEM_INITIALIZER(0)),
|
||||
_completion_semaphore(SEM_INITIALIZER(0)),
|
||||
_pc_txns(perf_alloc(PC_ELAPSED, "io_txns ")),
|
||||
_pc_dmasetup(perf_alloc(PC_ELAPSED, "io_dmasetup ")),
|
||||
_pc_retries(perf_alloc(PC_COUNT, "io_retries ")),
|
||||
_pc_timeouts(perf_alloc(PC_COUNT, "io_timeouts ")),
|
||||
|
||||
@ -65,7 +65,8 @@
|
||||
|
||||
PX4IO_Uploader::PX4IO_Uploader() :
|
||||
_io_fd(-1),
|
||||
_fw_fd(-1)
|
||||
_fw_fd(-1),
|
||||
bl_rev(0)
|
||||
{
|
||||
}
|
||||
|
||||
@ -245,7 +246,7 @@ PX4IO_Uploader::upload(const char *filenames[])
|
||||
}
|
||||
|
||||
int
|
||||
PX4IO_Uploader::recv(uint8_t &c, unsigned timeout)
|
||||
PX4IO_Uploader::recv_byte_with_timeout(uint8_t *c, unsigned timeout)
|
||||
{
|
||||
struct pollfd fds[1];
|
||||
|
||||
@ -262,19 +263,19 @@ PX4IO_Uploader::recv(uint8_t &c, unsigned timeout)
|
||||
return -ETIMEDOUT;
|
||||
}
|
||||
|
||||
read(_io_fd, &c, 1);
|
||||
read(_io_fd, c, 1);
|
||||
#ifdef UDEBUG
|
||||
log("recv 0x%02x", c);
|
||||
log("recv_bytes 0x%02x", c);
|
||||
#endif
|
||||
return OK;
|
||||
}
|
||||
|
||||
int
|
||||
PX4IO_Uploader::recv(uint8_t *p, unsigned count)
|
||||
PX4IO_Uploader::recv_bytes(uint8_t *p, unsigned count)
|
||||
{
|
||||
int ret;
|
||||
int ret = OK;
|
||||
while (count--) {
|
||||
ret = recv(*p++, 5000);
|
||||
ret = recv_byte_with_timeout(p++, 5000);
|
||||
|
||||
if (ret != OK)
|
||||
break;
|
||||
@ -289,10 +290,10 @@ PX4IO_Uploader::drain()
|
||||
int ret;
|
||||
|
||||
do {
|
||||
// the small recv timeout here is to allow for fast
|
||||
// the small recv_bytes timeout here is to allow for fast
|
||||
// drain when rebooting the io board for a forced
|
||||
// update of the fw without using the safety switch
|
||||
ret = recv(c, 40);
|
||||
ret = recv_byte_with_timeout(&c, 40);
|
||||
|
||||
#ifdef UDEBUG
|
||||
if (ret == OK) {
|
||||
@ -331,12 +332,12 @@ PX4IO_Uploader::get_sync(unsigned timeout)
|
||||
uint8_t c[2];
|
||||
int ret;
|
||||
|
||||
ret = recv(c[0], timeout);
|
||||
ret = recv_byte_with_timeout(c, timeout);
|
||||
|
||||
if (ret != OK)
|
||||
return ret;
|
||||
|
||||
ret = recv(c[1], timeout);
|
||||
ret = recv_byte_with_timeout(c + 1, timeout);
|
||||
|
||||
if (ret != OK)
|
||||
return ret;
|
||||
@ -372,7 +373,7 @@ PX4IO_Uploader::get_info(int param, uint32_t &val)
|
||||
send(param);
|
||||
send(PROTO_EOC);
|
||||
|
||||
ret = recv((uint8_t *)&val, sizeof(val));
|
||||
ret = recv_bytes((uint8_t *)&val, sizeof(val));
|
||||
|
||||
if (ret != OK)
|
||||
return ret;
|
||||
@ -513,7 +514,7 @@ PX4IO_Uploader::verify_rev2(size_t fw_size)
|
||||
for (ssize_t i = 0; i < count; i++) {
|
||||
uint8_t c;
|
||||
|
||||
ret = recv(c, 5000);
|
||||
ret = recv_byte_with_timeout(&c, 5000);
|
||||
|
||||
if (ret != OK) {
|
||||
log("%d: got %d waiting for bytes", sent + i, ret);
|
||||
@ -600,7 +601,7 @@ PX4IO_Uploader::verify_rev3(size_t fw_size_local)
|
||||
send(PROTO_GET_CRC);
|
||||
send(PROTO_EOC);
|
||||
|
||||
ret = recv((uint8_t*)(&crc), sizeof(crc));
|
||||
ret = recv_bytes((uint8_t*)(&crc), sizeof(crc));
|
||||
|
||||
if (ret != OK) {
|
||||
log("did not receive CRC checksum");
|
||||
|
||||
@ -74,19 +74,19 @@ private:
|
||||
INFO_BOARD_REV = 3, /**< board revision */
|
||||
INFO_FLASH_SIZE = 4, /**< max firmware size in bytes */
|
||||
|
||||
PROG_MULTI_MAX = 60, /**< protocol max is 255, must be multiple of 4 */
|
||||
PROG_MULTI_MAX = 248, /**< protocol max is 255, must be multiple of 4 */
|
||||
|
||||
};
|
||||
|
||||
int _io_fd;
|
||||
int _fw_fd;
|
||||
|
||||
uint32_t bl_rev; /**< bootloader revision */
|
||||
uint32_t bl_rev; /**< bootloader revision */
|
||||
|
||||
void log(const char *fmt, ...);
|
||||
|
||||
int recv(uint8_t &c, unsigned timeout);
|
||||
int recv(uint8_t *p, unsigned count);
|
||||
int recv_byte_with_timeout(uint8_t *c, unsigned timeout);
|
||||
int recv_bytes(uint8_t *p, unsigned count);
|
||||
void drain();
|
||||
int send(uint8_t c);
|
||||
int send(uint8_t *p, unsigned count);
|
||||
|
||||
@ -337,6 +337,7 @@ ToneAlarm::ToneAlarm() :
|
||||
_default_tunes[TONE_ARMING_FAILURE_TUNE] = "MFT255L4<<<BAP";
|
||||
_default_tunes[TONE_PARACHUTE_RELEASE_TUNE] = "MFT255L16agagagag"; // parachute release
|
||||
_default_tunes[TONE_EKF_WARNING_TUNE] = "MFT255L8ddd#d#eeff"; // ekf warning
|
||||
_default_tunes[TONE_BARO_WARNING_TUNE] = "MFT255L4gf#fed#d"; // baro warning
|
||||
|
||||
_tune_names[TONE_STARTUP_TUNE] = "startup"; // startup tune
|
||||
_tune_names[TONE_ERROR_TUNE] = "error"; // ERROR tone
|
||||
@ -350,6 +351,7 @@ ToneAlarm::ToneAlarm() :
|
||||
_tune_names[TONE_ARMING_FAILURE_TUNE] = "arming_failure"; //fail to arm
|
||||
_tune_names[TONE_PARACHUTE_RELEASE_TUNE] = "parachute_release"; // parachute release
|
||||
_tune_names[TONE_EKF_WARNING_TUNE] = "ekf_warning"; // ekf warning
|
||||
_tune_names[TONE_BARO_WARNING_TUNE] = "baro_warning"; // baro warning
|
||||
}
|
||||
|
||||
ToneAlarm::~ToneAlarm()
|
||||
|
||||
@ -39,3 +39,5 @@ SRCS = attitude_fw/ecl_pitch_controller.cpp \
|
||||
attitude_fw/ecl_roll_controller.cpp \
|
||||
attitude_fw/ecl_yaw_controller.cpp \
|
||||
l1/ecl_l1_pos_controller.cpp
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
@ -46,3 +46,5 @@
|
||||
#
|
||||
|
||||
SRCS = tecs/tecs.cpp
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
@ -124,7 +124,7 @@ extern struct system_load_s system_load;
|
||||
#define STICK_ON_OFF_HYSTERESIS_TIME_MS 1000
|
||||
#define STICK_ON_OFF_COUNTER_LIMIT (STICK_ON_OFF_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
|
||||
|
||||
#define POSITION_TIMEOUT (600 * 1000) /**< consider the local or global position estimate invalid after 600ms */
|
||||
#define POSITION_TIMEOUT (2 * 1000 * 1000) /**< consider the local or global position estimate invalid after 600ms */
|
||||
#define FAILSAFE_DEFAULT_TIMEOUT (3 * 1000 * 1000) /**< hysteresis time - the failsafe will trigger after 3 seconds in this state */
|
||||
#define RC_TIMEOUT 500000
|
||||
#define OFFBOARD_TIMEOUT 500000
|
||||
@ -162,7 +162,8 @@ static bool on_usb_power = false;
|
||||
|
||||
static float takeoff_alt = 5.0f;
|
||||
static int parachute_enabled = 0;
|
||||
static float eph_epv_threshold = 5.0f;
|
||||
static float eph_threshold = 5.0f;
|
||||
static float epv_threshold = 10.0f;
|
||||
|
||||
static struct vehicle_status_s status;
|
||||
static struct actuator_armed_s armed;
|
||||
@ -334,6 +335,7 @@ void print_status()
|
||||
{
|
||||
warnx("type: %s", (status.is_rotary_wing) ? "ROTARY" : "PLANE");
|
||||
warnx("usb powered: %s", (on_usb_power) ? "yes" : "no");
|
||||
warnx("avionics rail: %6.2f V", (double)status.avionics_power_rail_voltage);
|
||||
|
||||
/* read all relevant states */
|
||||
int state_sub = orb_subscribe(ORB_ID(vehicle_status));
|
||||
@ -737,6 +739,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||
|
||||
// CIRCUIT BREAKERS
|
||||
status.circuit_breaker_engaged_power_check = false;
|
||||
status.circuit_breaker_engaged_airspd_check = false;
|
||||
|
||||
/* publish initial state */
|
||||
status_pub = orb_advertise(ORB_ID(vehicle_status), &status);
|
||||
@ -982,6 +985,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||
param_get(_param_component_id, &(status.component_id));
|
||||
|
||||
status.circuit_breaker_engaged_power_check = circuit_breaker_enabled("CBRK_SUPPLY_CHK", CBRK_SUPPLY_CHK_KEY);
|
||||
status.circuit_breaker_engaged_airspd_check = circuit_breaker_enabled("CBRK_AIRSPD_CHK", CBRK_AIRSPD_CHK_KEY);
|
||||
|
||||
status_changed = true;
|
||||
|
||||
@ -1113,26 +1117,26 @@ int commander_thread_main(int argc, char *argv[])
|
||||
|
||||
/* update condition_global_position_valid */
|
||||
/* hysteresis for EPH/EPV */
|
||||
bool eph_epv_good;
|
||||
bool eph_good;
|
||||
|
||||
if (status.condition_global_position_valid) {
|
||||
if (global_position.eph > eph_epv_threshold * 2.0f || global_position.epv > eph_epv_threshold * 2.0f) {
|
||||
eph_epv_good = false;
|
||||
if (global_position.eph > eph_threshold * 2.5f) {
|
||||
eph_good = false;
|
||||
|
||||
} else {
|
||||
eph_epv_good = true;
|
||||
eph_good = true;
|
||||
}
|
||||
|
||||
} else {
|
||||
if (global_position.eph < eph_epv_threshold && global_position.epv < eph_epv_threshold) {
|
||||
eph_epv_good = true;
|
||||
if (global_position.eph < eph_threshold) {
|
||||
eph_good = true;
|
||||
|
||||
} else {
|
||||
eph_epv_good = false;
|
||||
eph_good = false;
|
||||
}
|
||||
}
|
||||
|
||||
check_valid(global_position.timestamp, POSITION_TIMEOUT, eph_epv_good, &(status.condition_global_position_valid), &status_changed);
|
||||
check_valid(global_position.timestamp, POSITION_TIMEOUT, eph_good, &(status.condition_global_position_valid), &status_changed);
|
||||
|
||||
/* check if GPS fix is ok */
|
||||
if (gps_position.fix_type >= 3 && //XXX check eph and epv ?
|
||||
@ -1154,7 +1158,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||
|
||||
/* update home position */
|
||||
if (!status.condition_home_position_valid && status.condition_global_position_valid && !armed.armed &&
|
||||
(global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
|
||||
(global_position.eph < eph_threshold) && (global_position.epv < epv_threshold)) {
|
||||
|
||||
home.lat = global_position.lat;
|
||||
home.lon = global_position.lon;
|
||||
@ -1184,8 +1188,8 @@ int commander_thread_main(int argc, char *argv[])
|
||||
/* hysteresis for EPH */
|
||||
bool local_eph_good;
|
||||
|
||||
if (status.condition_global_position_valid) {
|
||||
if (local_position.eph > eph_epv_threshold * 2.0f) {
|
||||
if (status.condition_local_position_valid) {
|
||||
if (local_position.eph > eph_threshold * 2.5f) {
|
||||
local_eph_good = false;
|
||||
|
||||
} else {
|
||||
@ -1193,7 +1197,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||
}
|
||||
|
||||
} else {
|
||||
if (local_position.eph < eph_epv_threshold) {
|
||||
if (local_position.eph < eph_threshold) {
|
||||
local_eph_good = true;
|
||||
|
||||
} else {
|
||||
@ -1540,7 +1544,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||
|
||||
/* update home position on arming if at least 2s from commander start spent to avoid setting home on in-air restart */
|
||||
if (armed.armed && !was_armed && hrt_absolute_time() > start_time + 2000000 && status.condition_global_position_valid &&
|
||||
(global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
|
||||
(global_position.eph < eph_threshold) && (global_position.epv < epv_threshold)) {
|
||||
|
||||
// TODO remove code duplication
|
||||
home.lat = global_position.lat;
|
||||
|
||||
@ -679,7 +679,9 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd)
|
||||
goto system_eval;
|
||||
}
|
||||
|
||||
if (!status->is_rotary_wing) {
|
||||
/* Perform airspeed check only if circuit breaker is not
|
||||
* engaged and it's not a rotary wing */
|
||||
if (!status->circuit_breaker_engaged_airspd_check && !status->is_rotary_wing) {
|
||||
/* accel done, close it */
|
||||
close(fd);
|
||||
fd = orb_subscribe(ORB_ID(airspeed));
|
||||
|
||||
@ -121,6 +121,9 @@ int blockLimitSymTest()
|
||||
|
||||
float BlockLowPass::update(float input)
|
||||
{
|
||||
if (!isfinite(getState())) {
|
||||
setState(input);
|
||||
}
|
||||
float b = 2 * float(M_PI) * getFCut() * getDt();
|
||||
float a = b / (1 + b);
|
||||
setState(a * input + (1 - a)*getState());
|
||||
|
||||
@ -114,7 +114,7 @@ public:
|
||||
// methods
|
||||
BlockLowPass(SuperBlock *parent, const char *name) :
|
||||
Block(parent, name),
|
||||
_state(0),
|
||||
_state(0.0f/0.0f /* initialize to invalid val, force into is_finite() check on first call */),
|
||||
_fCut(this, "") // only one parameter, no need to name
|
||||
{};
|
||||
virtual ~BlockLowPass() {};
|
||||
|
||||
@ -630,10 +630,10 @@ FixedwingEstimator::check_filter_state()
|
||||
rep.health_flags |= (((uint8_t)ekf_report.posHealth) << 1);
|
||||
rep.health_flags |= (((uint8_t)ekf_report.hgtHealth) << 2);
|
||||
rep.health_flags |= (((uint8_t)!ekf_report.gyroOffsetsExcessive) << 3);
|
||||
// rep.health_flags |= (((uint8_t)ekf_report.onGround) << 4);
|
||||
// rep.health_flags |= (((uint8_t)ekf_report.staticMode) << 5);
|
||||
// rep.health_flags |= (((uint8_t)ekf_report.useCompass) << 6);
|
||||
// rep.health_flags |= (((uint8_t)ekf_report.useAirspeed) << 7);
|
||||
rep.health_flags |= (((uint8_t)ekf_report.onGround) << 4);
|
||||
rep.health_flags |= (((uint8_t)ekf_report.staticMode) << 5);
|
||||
rep.health_flags |= (((uint8_t)ekf_report.useCompass) << 6);
|
||||
rep.health_flags |= (((uint8_t)ekf_report.useAirspeed) << 7);
|
||||
|
||||
rep.timeout_flags |= (((uint8_t)ekf_report.velTimeout) << 0);
|
||||
rep.timeout_flags |= (((uint8_t)ekf_report.posTimeout) << 1);
|
||||
@ -1465,25 +1465,6 @@ FixedwingEstimator::task_main()
|
||||
_global_pos_pub = orb_advertise(ORB_ID(vehicle_global_position), &_global_pos);
|
||||
}
|
||||
|
||||
if (hrt_elapsed_time(&_wind.timestamp) > 99000) {
|
||||
_wind.timestamp = _global_pos.timestamp;
|
||||
_wind.windspeed_north = _ekf->states[14];
|
||||
_wind.windspeed_east = _ekf->states[15];
|
||||
_wind.covariance_north = 0.0f; // XXX get form filter
|
||||
_wind.covariance_east = 0.0f;
|
||||
|
||||
/* lazily publish the wind estimate only once available */
|
||||
if (_wind_pub > 0) {
|
||||
/* publish the wind estimate */
|
||||
orb_publish(ORB_ID(wind_estimate), _wind_pub, &_wind);
|
||||
|
||||
} else {
|
||||
/* advertise and publish */
|
||||
_wind_pub = orb_advertise(ORB_ID(wind_estimate), &_wind);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if (hrt_elapsed_time(&_wind.timestamp) > 99000) {
|
||||
_wind.timestamp = _global_pos.timestamp;
|
||||
_wind.windspeed_north = _ekf->states[14];
|
||||
|
||||
@ -3028,6 +3028,10 @@ void AttPosEKF::GetFilterState(struct ekf_status_report *err)
|
||||
current_ekf_state.states[i] = states[i];
|
||||
}
|
||||
current_ekf_state.n_states = n_states;
|
||||
current_ekf_state.onGround = onGround;
|
||||
current_ekf_state.staticMode = staticMode;
|
||||
current_ekf_state.useCompass = useCompass;
|
||||
current_ekf_state.useAirspeed = useAirspeed;
|
||||
|
||||
memcpy(err, ¤t_ekf_state, sizeof(*err));
|
||||
|
||||
|
||||
@ -68,6 +68,10 @@ struct ekf_status_report {
|
||||
bool posTimeout;
|
||||
bool hgtTimeout;
|
||||
bool imuTimeout;
|
||||
bool onGround;
|
||||
bool staticMode;
|
||||
bool useCompass;
|
||||
bool useAirspeed;
|
||||
uint32_t velFailTime;
|
||||
uint32_t posFailTime;
|
||||
uint32_t hgtFailTime;
|
||||
|
||||
@ -42,8 +42,8 @@
|
||||
* Proceedings of the AIAA Guidance, Navigation and Control
|
||||
* Conference, Aug 2004. AIAA-2004-4900.
|
||||
*
|
||||
* Implementation for total energy control class:
|
||||
* Thomas Gubler
|
||||
* Original implementation for total energy control class:
|
||||
* Paul Riseborough and Andrew Tridgell, 2013 (code in lib/external_lgpl)
|
||||
*
|
||||
* More details and acknowledgements in the referenced library headers.
|
||||
*
|
||||
@ -87,10 +87,13 @@
|
||||
#include <mavlink/mavlink_log.h>
|
||||
#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"
|
||||
|
||||
static int _control_task = -1; /**< task handle for sensor task */
|
||||
|
||||
|
||||
/**
|
||||
* L1 control app start / stop handling function
|
||||
@ -115,9 +118,9 @@ public:
|
||||
/**
|
||||
* Start the sensors task.
|
||||
*
|
||||
* @return OK on success.
|
||||
* @return OK on success.
|
||||
*/
|
||||
int start();
|
||||
static int start();
|
||||
|
||||
/**
|
||||
* Task status
|
||||
@ -131,7 +134,6 @@ private:
|
||||
|
||||
bool _task_should_exit; /**< if true, sensor task should exit */
|
||||
bool _task_running; /**< if true, task is running in its mainloop */
|
||||
int _control_task; /**< task handle for sensor task */
|
||||
|
||||
int _global_pos_sub;
|
||||
int _pos_sp_triplet_sub;
|
||||
@ -192,6 +194,7 @@ private:
|
||||
math::Matrix<3, 3> _R_nb; ///< current attitude
|
||||
|
||||
ECL_L1_Pos_Controller _l1_control;
|
||||
TECS _tecs;
|
||||
fwPosctrl::mTecs _mTecs;
|
||||
bool _was_pos_control_mode;
|
||||
|
||||
@ -199,6 +202,21 @@ private:
|
||||
float l1_period;
|
||||
float l1_damping;
|
||||
|
||||
float time_const;
|
||||
float min_sink_rate;
|
||||
float max_sink_rate;
|
||||
float max_climb_rate;
|
||||
float heightrate_p;
|
||||
float speedrate_p;
|
||||
float throttle_damp;
|
||||
float integrator_gain;
|
||||
float vertical_accel_limit;
|
||||
float height_comp_filter_omega;
|
||||
float speed_comp_filter_omega;
|
||||
float roll_throttle_compensation;
|
||||
float speed_weight;
|
||||
float pitch_damping;
|
||||
|
||||
float airspeed_min;
|
||||
float airspeed_trim;
|
||||
float airspeed_max;
|
||||
@ -226,6 +244,21 @@ private:
|
||||
param_t l1_period;
|
||||
param_t l1_damping;
|
||||
|
||||
param_t time_const;
|
||||
param_t min_sink_rate;
|
||||
param_t max_sink_rate;
|
||||
param_t max_climb_rate;
|
||||
param_t heightrate_p;
|
||||
param_t speedrate_p;
|
||||
param_t throttle_damp;
|
||||
param_t integrator_gain;
|
||||
param_t vertical_accel_limit;
|
||||
param_t height_comp_filter_omega;
|
||||
param_t speed_comp_filter_omega;
|
||||
param_t roll_throttle_compensation;
|
||||
param_t speed_weight;
|
||||
param_t pitch_damping;
|
||||
|
||||
param_t airspeed_min;
|
||||
param_t airspeed_trim;
|
||||
param_t airspeed_max;
|
||||
@ -361,7 +394,6 @@ FixedwingPositionControl::FixedwingPositionControl() :
|
||||
_mavlink_fd(-1),
|
||||
_task_should_exit(false),
|
||||
_task_running(false),
|
||||
_control_task(-1),
|
||||
|
||||
/* subscriptions */
|
||||
_global_pos_sub(-1),
|
||||
@ -438,6 +470,21 @@ FixedwingPositionControl::FixedwingPositionControl() :
|
||||
_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.time_const = param_find("FW_T_TIME_CONST");
|
||||
_parameter_handles.min_sink_rate = param_find("FW_T_SINK_MIN");
|
||||
_parameter_handles.max_sink_rate = param_find("FW_T_SINK_MAX");
|
||||
_parameter_handles.max_climb_rate = param_find("FW_T_CLMB_MAX");
|
||||
_parameter_handles.throttle_damp = param_find("FW_T_THR_DAMP");
|
||||
_parameter_handles.integrator_gain = param_find("FW_T_INTEG_GAIN");
|
||||
_parameter_handles.vertical_accel_limit = param_find("FW_T_VERT_ACC");
|
||||
_parameter_handles.height_comp_filter_omega = param_find("FW_T_HGT_OMEGA");
|
||||
_parameter_handles.speed_comp_filter_omega = param_find("FW_T_SPD_OMEGA");
|
||||
_parameter_handles.roll_throttle_compensation = param_find("FW_T_RLL2THR");
|
||||
_parameter_handles.speed_weight = param_find("FW_T_SPDWEIGHT");
|
||||
_parameter_handles.pitch_damping = param_find("FW_T_PTCH_DAMP");
|
||||
_parameter_handles.heightrate_p = param_find("FW_T_HRATE_P");
|
||||
_parameter_handles.speedrate_p = param_find("FW_T_SRATE_P");
|
||||
|
||||
/* fetch initial parameter values */
|
||||
parameters_update();
|
||||
}
|
||||
@ -488,6 +535,22 @@ FixedwingPositionControl::parameters_update()
|
||||
|
||||
param_get(_parameter_handles.throttle_land_max, &(_parameters.throttle_land_max));
|
||||
|
||||
param_get(_parameter_handles.time_const, &(_parameters.time_const));
|
||||
param_get(_parameter_handles.min_sink_rate, &(_parameters.min_sink_rate));
|
||||
param_get(_parameter_handles.max_sink_rate, &(_parameters.max_sink_rate));
|
||||
param_get(_parameter_handles.throttle_damp, &(_parameters.throttle_damp));
|
||||
param_get(_parameter_handles.integrator_gain, &(_parameters.integrator_gain));
|
||||
param_get(_parameter_handles.vertical_accel_limit, &(_parameters.vertical_accel_limit));
|
||||
param_get(_parameter_handles.height_comp_filter_omega, &(_parameters.height_comp_filter_omega));
|
||||
param_get(_parameter_handles.speed_comp_filter_omega, &(_parameters.speed_comp_filter_omega));
|
||||
param_get(_parameter_handles.roll_throttle_compensation, &(_parameters.roll_throttle_compensation));
|
||||
param_get(_parameter_handles.speed_weight, &(_parameters.speed_weight));
|
||||
param_get(_parameter_handles.pitch_damping, &(_parameters.pitch_damping));
|
||||
param_get(_parameter_handles.max_climb_rate, &(_parameters.max_climb_rate));
|
||||
|
||||
param_get(_parameter_handles.heightrate_p, &(_parameters.heightrate_p));
|
||||
param_get(_parameter_handles.speedrate_p, &(_parameters.speedrate_p));
|
||||
|
||||
param_get(_parameter_handles.land_slope_angle, &(_parameters.land_slope_angle));
|
||||
param_get(_parameter_handles.land_H1_virt, &(_parameters.land_H1_virt));
|
||||
param_get(_parameter_handles.land_flare_alt_relative, &(_parameters.land_flare_alt_relative));
|
||||
@ -500,6 +563,23 @@ FixedwingPositionControl::parameters_update()
|
||||
_l1_control.set_l1_period(_parameters.l1_period);
|
||||
_l1_control.set_l1_roll_limit(math::radians(_parameters.roll_limit));
|
||||
|
||||
_tecs.set_time_const(_parameters.time_const);
|
||||
_tecs.set_min_sink_rate(_parameters.min_sink_rate);
|
||||
_tecs.set_max_sink_rate(_parameters.max_sink_rate);
|
||||
_tecs.set_throttle_damp(_parameters.throttle_damp);
|
||||
_tecs.set_integrator_gain(_parameters.integrator_gain);
|
||||
_tecs.set_vertical_accel_limit(_parameters.vertical_accel_limit);
|
||||
_tecs.set_height_comp_filter_omega(_parameters.height_comp_filter_omega);
|
||||
_tecs.set_speed_comp_filter_omega(_parameters.speed_comp_filter_omega);
|
||||
_tecs.set_roll_throttle_compensation(_parameters.roll_throttle_compensation);
|
||||
_tecs.set_speed_weight(_parameters.speed_weight);
|
||||
_tecs.set_pitch_damping(_parameters.pitch_damping);
|
||||
_tecs.set_indicated_airspeed_min(_parameters.airspeed_min);
|
||||
_tecs.set_indicated_airspeed_max(_parameters.airspeed_max);
|
||||
_tecs.set_max_climb_rate(_parameters.max_climb_rate);
|
||||
_tecs.set_heightrate_p(_parameters.heightrate_p);
|
||||
_tecs.set_speedrate_p(_parameters.speedrate_p);
|
||||
|
||||
/* sanity check parameters */
|
||||
if (_parameters.airspeed_max < _parameters.airspeed_min ||
|
||||
_parameters.airspeed_max < 5.0f ||
|
||||
@ -561,6 +641,9 @@ FixedwingPositionControl::vehicle_airspeed_poll()
|
||||
}
|
||||
}
|
||||
|
||||
/* update TECS state */
|
||||
_tecs.enable_airspeed(_airspeed_valid);
|
||||
|
||||
return airspeed_updated;
|
||||
}
|
||||
|
||||
@ -621,7 +704,17 @@ FixedwingPositionControl::vehicle_setpoint_poll()
|
||||
void
|
||||
FixedwingPositionControl::task_main_trampoline(int argc, char *argv[])
|
||||
{
|
||||
l1_control::g_control = new FixedwingPositionControl();
|
||||
|
||||
if (l1_control::g_control == nullptr) {
|
||||
warnx("OUT OF MEM");
|
||||
return;
|
||||
}
|
||||
|
||||
/* only returns on exit */
|
||||
l1_control::g_control->task_main();
|
||||
delete l1_control::g_control;
|
||||
l1_control::g_control = nullptr;
|
||||
}
|
||||
|
||||
float
|
||||
@ -733,6 +826,14 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||
|
||||
float eas2tas = 1.0f; // XXX calculate actual number based on current measurements
|
||||
|
||||
/* filter speed and altitude for controller */
|
||||
math::Vector<3> accel_body(_sensor_combined.accelerometer_m_s2);
|
||||
math::Vector<3> accel_earth = _R_nb * accel_body;
|
||||
|
||||
if (!_mTecs.getEnabled()) {
|
||||
_tecs.update_50hz(_global_pos.alt /* XXX might switch to alt err here */, _airspeed.indicated_airspeed_m_s, _R_nb, accel_body, accel_earth);
|
||||
}
|
||||
|
||||
/* define altitude error */
|
||||
float altitude_error = _pos_sp_triplet.current.alt - _global_pos.alt;
|
||||
|
||||
@ -758,6 +859,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||
/* get circle mode */
|
||||
bool was_circle_mode = _l1_control.circle_mode();
|
||||
|
||||
/* restore speed weight, in case changed intermittently (e.g. in landing handling) */
|
||||
_tecs.set_speed_weight(_parameters.speed_weight);
|
||||
|
||||
/* current waypoint (the one currently heading for) */
|
||||
math::Vector<2> next_wp((float)pos_sp_triplet.current.lat, (float)pos_sp_triplet.current.lon);
|
||||
|
||||
@ -1066,9 +1170,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||
_att_sp.thrust = launchDetector.getThrottlePreTakeoff();
|
||||
}
|
||||
else {
|
||||
_att_sp.thrust = math::min(_mTecs.getThrottleSetpoint(), throttle_max);
|
||||
_att_sp.thrust = math::min(_mTecs.getEnabled() ? _mTecs.getThrottleSetpoint() : _tecs.get_throttle_demand(), throttle_max);
|
||||
}
|
||||
_att_sp.pitch_body = _mTecs.getPitchSetpoint();
|
||||
_att_sp.pitch_body = _mTecs.getEnabled() ? _mTecs.getPitchSetpoint() : _tecs.get_pitch_demand();
|
||||
|
||||
if (_control_mode.flag_control_position_enabled) {
|
||||
last_manual = false;
|
||||
@ -1084,10 +1188,6 @@ void
|
||||
FixedwingPositionControl::task_main()
|
||||
{
|
||||
|
||||
/* inform about start */
|
||||
warnx("Initializing..");
|
||||
fflush(stdout);
|
||||
|
||||
/*
|
||||
* do subscriptions
|
||||
*/
|
||||
@ -1248,20 +1348,29 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_
|
||||
const math::Vector<3> &ground_speed,
|
||||
tecs_mode mode)
|
||||
{
|
||||
/* Using mtecs library: prepare arguments for mtecs call */
|
||||
float flightPathAngle = 0.0f;
|
||||
float ground_speed_length = ground_speed.length();
|
||||
if (ground_speed_length > FLT_EPSILON) {
|
||||
flightPathAngle = -asinf(ground_speed(2)/ground_speed_length);
|
||||
}
|
||||
fwPosctrl::LimitOverride limitOverride;
|
||||
if (climbout_mode) {
|
||||
limitOverride.enablePitchMinOverride(M_RAD_TO_DEG_F * climbout_pitch_min_rad);
|
||||
if (_mTecs.getEnabled()) {
|
||||
/* Using mtecs library: prepare arguments for mtecs call */
|
||||
float flightPathAngle = 0.0f;
|
||||
float ground_speed_length = ground_speed.length();
|
||||
if (ground_speed_length > FLT_EPSILON) {
|
||||
flightPathAngle = -asinf(ground_speed(2)/ground_speed_length);
|
||||
}
|
||||
fwPosctrl::LimitOverride limitOverride;
|
||||
if (climbout_mode) {
|
||||
limitOverride.enablePitchMinOverride(M_RAD_TO_DEG_F * climbout_pitch_min_rad);
|
||||
} else {
|
||||
limitOverride.disablePitchMinOverride();
|
||||
}
|
||||
_mTecs.updateAltitudeSpeed(flightPathAngle, altitude, alt_sp, _airspeed.true_airspeed_m_s, v_sp, mode,
|
||||
limitOverride);
|
||||
} else {
|
||||
limitOverride.disablePitchMinOverride();
|
||||
/* Using tecs library */
|
||||
_tecs.update_pitch_throttle(_R_nb, _att.pitch, altitude, alt_sp, v_sp,
|
||||
_airspeed.indicated_airspeed_m_s, eas2tas,
|
||||
climbout_mode, climbout_pitch_min_rad,
|
||||
throttle_min, throttle_max, throttle_cruise,
|
||||
pitch_min_rad, pitch_max_rad);
|
||||
}
|
||||
_mTecs.updateAltitudeSpeed(flightPathAngle, altitude, alt_sp, _airspeed.true_airspeed_m_s, v_sp, mode,
|
||||
limitOverride);
|
||||
}
|
||||
|
||||
int
|
||||
@ -1295,14 +1404,7 @@ int fw_pos_control_l1_main(int argc, char *argv[])
|
||||
if (l1_control::g_control != nullptr)
|
||||
errx(1, "already running");
|
||||
|
||||
l1_control::g_control = new FixedwingPositionControl;
|
||||
|
||||
if (l1_control::g_control == nullptr)
|
||||
errx(1, "alloc failed");
|
||||
|
||||
if (OK != l1_control::g_control->start()) {
|
||||
delete l1_control::g_control;
|
||||
l1_control::g_control = nullptr;
|
||||
if (OK != FixedwingPositionControl::start()) {
|
||||
err(1, "start failed");
|
||||
}
|
||||
|
||||
|
||||
@ -154,6 +154,182 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f);
|
||||
|
||||
/**
|
||||
* Maximum climb rate
|
||||
*
|
||||
* This is the best climb rate that the aircraft can achieve with
|
||||
* the throttle set to THR_MAX and the airspeed set to the
|
||||
* default value. For electric aircraft make sure this number can be
|
||||
* achieved towards the end of flight when the battery voltage has reduced.
|
||||
* The setting of this parameter can be checked by commanding a positive
|
||||
* altitude change of 100m in loiter, RTL or guided mode. If the throttle
|
||||
* required to climb is close to THR_MAX and the aircraft is maintaining
|
||||
* airspeed, then this parameter is set correctly. If the airspeed starts
|
||||
* to reduce, then the parameter is set to high, and if the throttle
|
||||
* demand required to climb and maintain speed is noticeably less than
|
||||
* FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or
|
||||
* FW_THR_MAX reduced.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f);
|
||||
|
||||
/**
|
||||
* Minimum descent rate
|
||||
*
|
||||
* This is the sink rate of the aircraft with the throttle
|
||||
* set to THR_MIN and flown at the same airspeed as used
|
||||
* to measure FW_T_CLMB_MAX.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f);
|
||||
|
||||
/**
|
||||
* Maximum descent rate
|
||||
*
|
||||
* This sets the maximum descent rate that the controller will use.
|
||||
* If this value is too large, the aircraft can over-speed on descent.
|
||||
* This should be set to a value that can be achieved without
|
||||
* exceeding the lower pitch angle limit and without over-speeding
|
||||
* the aircraft.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
|
||||
|
||||
/**
|
||||
* TECS time constant
|
||||
*
|
||||
* This is the time constant of the TECS control algorithm (in seconds).
|
||||
* Smaller values make it faster to respond, larger values make it slower
|
||||
* to respond.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f);
|
||||
|
||||
/**
|
||||
* Throttle damping factor
|
||||
*
|
||||
* This is the damping gain for the throttle demand loop.
|
||||
* Increase to add damping to correct for oscillations in speed and height.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f);
|
||||
|
||||
/**
|
||||
* Integrator gain
|
||||
*
|
||||
* This is the integrator gain on the control loop.
|
||||
* Increasing this gain increases the speed at which speed
|
||||
* and height offsets are trimmed out, but reduces damping and
|
||||
* increases overshoot.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f);
|
||||
|
||||
/**
|
||||
* Maximum vertical acceleration
|
||||
*
|
||||
* This is the maximum vertical acceleration (in metres/second square)
|
||||
* either up or down that the controller will use to correct speed
|
||||
* or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g)
|
||||
* allows for reasonably aggressive pitch changes if required to recover
|
||||
* from under-speed conditions.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
|
||||
|
||||
/**
|
||||
* Complementary filter "omega" parameter for height
|
||||
*
|
||||
* This is the cross-over frequency (in radians/second) of the complementary
|
||||
* filter used to fuse vertical acceleration and barometric height to obtain
|
||||
* an estimate of height rate and height. Increasing this frequency weights
|
||||
* the solution more towards use of the barometer, whilst reducing it weights
|
||||
* the solution more towards use of the accelerometer data.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f);
|
||||
|
||||
/**
|
||||
* Complementary filter "omega" parameter for speed
|
||||
*
|
||||
* This is the cross-over frequency (in radians/second) of the complementary
|
||||
* filter used to fuse longitudinal acceleration and airspeed to obtain an
|
||||
* improved airspeed estimate. Increasing this frequency weights the solution
|
||||
* more towards use of the arispeed sensor, whilst reducing it weights the
|
||||
* solution more towards use of the accelerometer data.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f);
|
||||
|
||||
/**
|
||||
* Roll -> Throttle feedforward
|
||||
*
|
||||
* Increasing this gain turn increases the amount of throttle that will
|
||||
* be used to compensate for the additional drag created by turning.
|
||||
* Ideally this should be set to approximately 10 x the extra sink rate
|
||||
* in m/s created by a 45 degree bank turn. Increase this gain if
|
||||
* the aircraft initially loses energy in turns and reduce if the
|
||||
* aircraft initially gains energy in turns. Efficient high aspect-ratio
|
||||
* aircraft (eg powered sailplanes) can use a lower value, whereas
|
||||
* inefficient low aspect-ratio models (eg delta wings) can use a higher value.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f);
|
||||
|
||||
/**
|
||||
* Speed <--> Altitude priority
|
||||
*
|
||||
* This parameter adjusts the amount of weighting that the pitch control
|
||||
* applies to speed vs height errors. Setting it to 0.0 will cause the
|
||||
* pitch control to control height and ignore speed errors. This will
|
||||
* normally improve height accuracy but give larger airspeed errors.
|
||||
* Setting it to 2.0 will cause the pitch control loop to control speed
|
||||
* and ignore height errors. This will normally reduce airspeed errors,
|
||||
* but give larger height errors. The default value of 1.0 allows the pitch
|
||||
* control to simultaneously control height and speed.
|
||||
* Note to Glider Pilots - set this parameter to 2.0 (The glider will
|
||||
* adjust its pitch angle to maintain airspeed, ignoring changes in height).
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f);
|
||||
|
||||
/**
|
||||
* Pitch damping factor
|
||||
*
|
||||
* This is the damping gain for the pitch demand loop. Increase to add
|
||||
* damping to correct for oscillations in height. The default value of 0.0
|
||||
* will work well provided the pitch to servo controller has been tuned
|
||||
* properly.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f);
|
||||
|
||||
/**
|
||||
* Height rate P factor
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f);
|
||||
|
||||
/**
|
||||
* Speed rate P factor
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f);
|
||||
|
||||
/**
|
||||
* Landing slope angle
|
||||
*
|
||||
|
||||
@ -76,6 +76,7 @@ mTecs::mTecs() :
|
||||
_counter(0),
|
||||
_debug(false)
|
||||
{
|
||||
warnx("starting");
|
||||
}
|
||||
|
||||
mTecs::~mTecs()
|
||||
|
||||
@ -55,7 +55,7 @@
|
||||
* @max 1
|
||||
* @group mTECS
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MT_ENABLED, 1);
|
||||
PARAM_DEFINE_INT32(MT_ENABLED, 0);
|
||||
|
||||
/**
|
||||
* Total Energy Rate Control Feedforward
|
||||
@ -241,7 +241,14 @@ PARAM_DEFINE_FLOAT(MT_FPA_MAX, 30.0f);
|
||||
*
|
||||
* @group mTECS
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MT_A_LP, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(MT_A_LP, 0.5f);
|
||||
|
||||
/**
|
||||
* Airspeed derivative calculation lowpass
|
||||
*
|
||||
* @group mTECS
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MT_AD_LP, 0.5f);
|
||||
|
||||
/**
|
||||
* P gain for the airspeed control
|
||||
@ -268,7 +275,7 @@ PARAM_DEFINE_FLOAT(MT_ACC_D, 0.0f);
|
||||
*
|
||||
* @group mTECS
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MT_ACC_D_LP, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(MT_ACC_D_LP, 0.5f);
|
||||
|
||||
/**
|
||||
* Minimal acceleration (air)
|
||||
@ -286,13 +293,6 @@ PARAM_DEFINE_FLOAT(MT_ACC_MIN, -40.0f);
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MT_ACC_MAX, 40.0f);
|
||||
|
||||
/**
|
||||
* Airspeed derivative calculation lowpass
|
||||
*
|
||||
* @group mTECS
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MT_AD_LP, 1.0f);
|
||||
|
||||
/**
|
||||
* Minimal throttle during takeoff
|
||||
*
|
||||
|
||||
@ -44,7 +44,12 @@
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
/*
|
||||
* We are NOT using convenience functions,
|
||||
* but instead send messages with a custom function.
|
||||
* So we do NOT do this:
|
||||
* #define MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
*/
|
||||
|
||||
/* use efficient approach, see mavlink_helpers.h */
|
||||
#define MAVLINK_SEND_UART_BYTES mavlink_send_uart_bytes
|
||||
|
||||
@ -1,73 +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 mavlink_commands.cpp
|
||||
* Mavlink commands stream implementation.
|
||||
*
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#include "mavlink_commands.h"
|
||||
|
||||
MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) :
|
||||
_cmd_sub(mavlink->add_orb_subscription(ORB_ID(vehicle_command))),
|
||||
_cmd{},
|
||||
_channel(channel),
|
||||
_cmd_time(0)
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
MavlinkCommandsStream::update(const hrt_abstime t)
|
||||
{
|
||||
struct vehicle_command_s cmd;
|
||||
|
||||
if (_cmd_sub->update(&_cmd_time, &cmd)) {
|
||||
/* only send commands for other systems/components */
|
||||
if (cmd.target_system != mavlink_system.sysid || cmd.target_component != mavlink_system.compid) {
|
||||
mavlink_msg_command_long_send(_channel,
|
||||
cmd.target_system,
|
||||
cmd.target_component,
|
||||
cmd.command,
|
||||
cmd.confirmation,
|
||||
cmd.param1,
|
||||
cmd.param2,
|
||||
cmd.param3,
|
||||
cmd.param4,
|
||||
cmd.param5,
|
||||
cmd.param6,
|
||||
cmd.param7);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -55,6 +55,7 @@
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include "mavlink_messages.h"
|
||||
#include "mavlink_main.h"
|
||||
|
||||
class MavlinkFTP
|
||||
{
|
||||
|
||||
@ -78,7 +78,6 @@
|
||||
#include "mavlink_messages.h"
|
||||
#include "mavlink_receiver.h"
|
||||
#include "mavlink_rate_limiter.h"
|
||||
#include "mavlink_commands.h"
|
||||
|
||||
#ifndef MAVLINK_CRC_EXTRA
|
||||
#error MAVLINK_CRC_EXTRA has to be defined on PX4 systems
|
||||
@ -91,14 +90,19 @@
|
||||
static const int ERROR = -1;
|
||||
|
||||
#define DEFAULT_DEVICE_NAME "/dev/ttyS1"
|
||||
#define MAX_DATA_RATE 10000 // max data rate in bytes/s
|
||||
#define MAX_DATA_RATE 20000 // max data rate in bytes/s
|
||||
#define MAIN_LOOP_DELAY 10000 // 100 Hz @ 1000 bytes/s data rate
|
||||
|
||||
#define TX_BUFFER_GAP MAVLINK_MAX_PACKET_LEN
|
||||
|
||||
static Mavlink *_mavlink_instances = nullptr;
|
||||
|
||||
/* TODO: if this is a class member it crashes */
|
||||
static struct file_operations fops;
|
||||
|
||||
static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS;
|
||||
static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
|
||||
|
||||
/**
|
||||
* mavlink app start / stop handling function
|
||||
*
|
||||
@ -108,113 +112,6 @@ extern "C" __EXPORT int mavlink_main(int argc, char *argv[]);
|
||||
|
||||
extern mavlink_system_t mavlink_system;
|
||||
|
||||
static uint64_t last_write_success_times[6] = {0};
|
||||
static uint64_t last_write_try_times[6] = {0};
|
||||
|
||||
/*
|
||||
* Internal function to send the bytes through the right serial port
|
||||
*/
|
||||
void
|
||||
mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length)
|
||||
{
|
||||
|
||||
Mavlink *instance;
|
||||
|
||||
switch (channel) {
|
||||
case MAVLINK_COMM_0:
|
||||
instance = Mavlink::get_instance(0);
|
||||
break;
|
||||
|
||||
case MAVLINK_COMM_1:
|
||||
instance = Mavlink::get_instance(1);
|
||||
break;
|
||||
|
||||
case MAVLINK_COMM_2:
|
||||
instance = Mavlink::get_instance(2);
|
||||
break;
|
||||
|
||||
case MAVLINK_COMM_3:
|
||||
instance = Mavlink::get_instance(3);
|
||||
break;
|
||||
#ifdef MAVLINK_COMM_4
|
||||
|
||||
case MAVLINK_COMM_4:
|
||||
instance = Mavlink::get_instance(4);
|
||||
break;
|
||||
#endif
|
||||
#ifdef MAVLINK_COMM_5
|
||||
|
||||
case MAVLINK_COMM_5:
|
||||
instance = Mavlink::get_instance(5);
|
||||
break;
|
||||
#endif
|
||||
#ifdef MAVLINK_COMM_6
|
||||
|
||||
case MAVLINK_COMM_6:
|
||||
instance = Mavlink::get_instance(6);
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
return;
|
||||
}
|
||||
|
||||
int uart = instance->get_uart_fd();
|
||||
|
||||
ssize_t desired = (sizeof(uint8_t) * length);
|
||||
|
||||
/*
|
||||
* Check if the OS buffer is full and disable HW
|
||||
* flow control if it continues to be full
|
||||
*/
|
||||
int buf_free = 0;
|
||||
|
||||
if (instance->get_flow_control_enabled()
|
||||
&& ioctl(uart, FIONWRITE, (unsigned long)&buf_free) == 0) {
|
||||
|
||||
/* Disable hardware flow control:
|
||||
* if no successful write since a defined time
|
||||
* and if the last try was not the last successful write
|
||||
*/
|
||||
if (last_write_try_times[(unsigned)channel] != 0 &&
|
||||
hrt_elapsed_time(&last_write_success_times[(unsigned)channel]) > 500 * 1000UL &&
|
||||
last_write_success_times[(unsigned)channel] !=
|
||||
last_write_try_times[(unsigned)channel]) {
|
||||
warnx("DISABLING HARDWARE FLOW CONTROL");
|
||||
instance->enable_flow_control(false);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/* If the wait until transmit flag is on, only transmit after we've received messages.
|
||||
Otherwise, transmit all the time. */
|
||||
if (instance->should_transmit()) {
|
||||
last_write_try_times[(unsigned)channel] = hrt_absolute_time();
|
||||
|
||||
/* check if there is space in the buffer, let it overflow else */
|
||||
if (!ioctl(uart, FIONWRITE, (unsigned long)&buf_free)) {
|
||||
|
||||
if (buf_free < desired) {
|
||||
/* we don't want to send anything just in half, so return */
|
||||
instance->count_txerr();
|
||||
instance->count_txerrbytes(desired);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
ssize_t ret = write(uart, ch, desired);
|
||||
|
||||
if (ret != desired) {
|
||||
instance->count_txerr();
|
||||
instance->count_txerrbytes(desired);
|
||||
|
||||
} else {
|
||||
last_write_success_times[(unsigned)channel] = last_write_try_times[(unsigned)channel];
|
||||
instance->count_txbytes(desired);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void usage(void);
|
||||
|
||||
Mavlink::Mavlink() :
|
||||
@ -233,8 +130,7 @@ Mavlink::Mavlink() :
|
||||
_subscriptions(nullptr),
|
||||
_streams(nullptr),
|
||||
_mission_manager(nullptr),
|
||||
_mission_pub(-1),
|
||||
_mission_result_sub(-1),
|
||||
_parameters_manager(nullptr),
|
||||
_mode(MAVLINK_MODE_NORMAL),
|
||||
_channel(MAVLINK_COMM_0),
|
||||
_logbuffer {},
|
||||
@ -246,12 +142,16 @@ Mavlink::Mavlink() :
|
||||
_ftp_on(false),
|
||||
_uart_fd(-1),
|
||||
_baudrate(57600),
|
||||
_datarate(10000),
|
||||
_datarate(1000),
|
||||
_datarate_events(500),
|
||||
_rate_mult(1.0f),
|
||||
_mavlink_param_queue_index(0),
|
||||
mavlink_link_termination_allowed(false),
|
||||
_subscribe_to_stream(nullptr),
|
||||
_subscribe_to_stream_rate(0.0f),
|
||||
_flow_control_enabled(true),
|
||||
_last_write_success_time(0),
|
||||
_last_write_try_time(0),
|
||||
_bytes_tx(0),
|
||||
_bytes_txerr(0),
|
||||
_bytes_rx(0),
|
||||
@ -262,6 +162,7 @@ Mavlink::Mavlink() :
|
||||
_rstatus {},
|
||||
_message_buffer {},
|
||||
_message_buffer_mutex {},
|
||||
_send_mutex {},
|
||||
_param_initialized(false),
|
||||
_param_system_id(0),
|
||||
_param_component_id(0),
|
||||
@ -483,7 +384,12 @@ Mavlink::forward_message(const mavlink_message_t *msg, Mavlink *self)
|
||||
Mavlink *inst;
|
||||
LL_FOREACH(_mavlink_instances, inst) {
|
||||
if (inst != self) {
|
||||
inst->pass_message(msg);
|
||||
|
||||
/* if not in normal mode, we are an onboard link
|
||||
* onboard links should only pass on messages from the same system ID */
|
||||
if (!(self->_mode != MAVLINK_MODE_NORMAL && msg->sysid != mavlink_system.sysid)) {
|
||||
inst->pass_message(msg);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -531,10 +437,26 @@ Mavlink::mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg)
|
||||
case (int)MAVLINK_IOC_SEND_TEXT_EMERGENCY: {
|
||||
|
||||
const char *txt = (const char *)arg;
|
||||
// printf("logmsg: %s\n", txt);
|
||||
struct mavlink_logmessage msg;
|
||||
strncpy(msg.text, txt, sizeof(msg.text));
|
||||
msg.severity = (unsigned char)cmd;
|
||||
|
||||
switch (cmd) {
|
||||
case MAVLINK_IOC_SEND_TEXT_INFO:
|
||||
msg.severity = MAV_SEVERITY_INFO;
|
||||
break;
|
||||
|
||||
case MAVLINK_IOC_SEND_TEXT_CRITICAL:
|
||||
msg.severity = MAV_SEVERITY_CRITICAL;
|
||||
break;
|
||||
|
||||
case MAVLINK_IOC_SEND_TEXT_EMERGENCY:
|
||||
msg.severity = MAV_SEVERITY_EMERGENCY;
|
||||
break;
|
||||
|
||||
default:
|
||||
msg.severity = MAV_SEVERITY_INFO;
|
||||
break;
|
||||
}
|
||||
|
||||
Mavlink *inst;
|
||||
LL_FOREACH(_mavlink_instances, inst) {
|
||||
@ -728,6 +650,9 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name, struct termios *
|
||||
if (enable_flow_control(true)) {
|
||||
warnx("hardware flow control not supported");
|
||||
}
|
||||
|
||||
} else {
|
||||
_flow_control_enabled = false;
|
||||
}
|
||||
|
||||
return _uart_fd;
|
||||
@ -769,8 +694,7 @@ Mavlink::set_hil_enabled(bool hil_enabled)
|
||||
/* enable HIL */
|
||||
if (hil_enabled && !_hil_enabled) {
|
||||
_hil_enabled = true;
|
||||
float rate_mult = _datarate / 1000.0f;
|
||||
configure_stream("HIL_CONTROLS", 15.0f * rate_mult);
|
||||
configure_stream("HIL_CONTROLS", 200.0f);
|
||||
}
|
||||
|
||||
/* disable HIL */
|
||||
@ -785,13 +709,145 @@ Mavlink::set_hil_enabled(bool hil_enabled)
|
||||
return ret;
|
||||
}
|
||||
|
||||
void
|
||||
Mavlink::send_message(const mavlink_message_t *msg)
|
||||
unsigned
|
||||
Mavlink::get_free_tx_buf()
|
||||
{
|
||||
/*
|
||||
* Check if the OS buffer is full and disable HW
|
||||
* flow control if it continues to be full
|
||||
*/
|
||||
int buf_free = 0;
|
||||
(void) ioctl(_uart_fd, FIONWRITE, (unsigned long)&buf_free);
|
||||
|
||||
if (get_flow_control_enabled() && buf_free < TX_BUFFER_GAP) {
|
||||
/* Disable hardware flow control:
|
||||
* if no successful write since a defined time
|
||||
* and if the last try was not the last successful write
|
||||
*/
|
||||
if (_last_write_try_time != 0 &&
|
||||
hrt_elapsed_time(&_last_write_success_time) > 500 * 1000UL &&
|
||||
_last_write_success_time != _last_write_try_time) {
|
||||
warnx("DISABLING HARDWARE FLOW CONTROL");
|
||||
enable_flow_control(false);
|
||||
}
|
||||
}
|
||||
|
||||
return buf_free;
|
||||
}
|
||||
|
||||
void
|
||||
Mavlink::send_message(const uint8_t msgid, const void *msg)
|
||||
{
|
||||
/* If the wait until transmit flag is on, only transmit after we've received messages.
|
||||
Otherwise, transmit all the time. */
|
||||
if (!should_transmit()) {
|
||||
return;
|
||||
}
|
||||
|
||||
pthread_mutex_lock(&_send_mutex);
|
||||
|
||||
int buf_free = get_free_tx_buf();
|
||||
|
||||
uint8_t payload_len = mavlink_message_lengths[msgid];
|
||||
unsigned packet_len = payload_len + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
|
||||
_last_write_try_time = hrt_absolute_time();
|
||||
|
||||
/* check if there is space in the buffer, let it overflow else */
|
||||
if (buf_free < TX_BUFFER_GAP) {
|
||||
/* no enough space in buffer to send */
|
||||
count_txerr();
|
||||
count_txerrbytes(packet_len);
|
||||
pthread_mutex_unlock(&_send_mutex);
|
||||
return;
|
||||
}
|
||||
|
||||
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
|
||||
|
||||
uint16_t len = mavlink_msg_to_send_buffer(buf, msg);
|
||||
mavlink_send_uart_bytes(_channel, buf, len);
|
||||
/* header */
|
||||
buf[0] = MAVLINK_STX;
|
||||
buf[1] = payload_len;
|
||||
/* use mavlink's internal counter for the TX seq */
|
||||
buf[2] = mavlink_get_channel_status(_channel)->current_tx_seq++;
|
||||
buf[3] = mavlink_system.sysid;
|
||||
buf[4] = mavlink_system.compid;
|
||||
buf[5] = msgid;
|
||||
|
||||
/* payload */
|
||||
memcpy(&buf[MAVLINK_NUM_HEADER_BYTES], msg, payload_len);
|
||||
|
||||
/* checksum */
|
||||
uint16_t checksum;
|
||||
crc_init(&checksum);
|
||||
crc_accumulate_buffer(&checksum, (const char *) &buf[1], MAVLINK_CORE_HEADER_LEN + payload_len);
|
||||
crc_accumulate(mavlink_message_crcs[msgid], &checksum);
|
||||
|
||||
buf[MAVLINK_NUM_HEADER_BYTES + payload_len] = (uint8_t)(checksum & 0xFF);
|
||||
buf[MAVLINK_NUM_HEADER_BYTES + payload_len + 1] = (uint8_t)(checksum >> 8);
|
||||
|
||||
/* send message to UART */
|
||||
ssize_t ret = write(_uart_fd, buf, packet_len);
|
||||
|
||||
if (ret != (int) packet_len) {
|
||||
count_txerr();
|
||||
count_txerrbytes(packet_len);
|
||||
|
||||
} else {
|
||||
_last_write_success_time = _last_write_try_time;
|
||||
count_txbytes(packet_len);
|
||||
}
|
||||
|
||||
pthread_mutex_unlock(&_send_mutex);
|
||||
}
|
||||
|
||||
void
|
||||
Mavlink::resend_message(mavlink_message_t *msg)
|
||||
{
|
||||
/* If the wait until transmit flag is on, only transmit after we've received messages.
|
||||
Otherwise, transmit all the time. */
|
||||
if (!should_transmit()) {
|
||||
return;
|
||||
}
|
||||
|
||||
pthread_mutex_lock(&_send_mutex);
|
||||
|
||||
int buf_free = get_free_tx_buf();
|
||||
|
||||
_last_write_try_time = hrt_absolute_time();
|
||||
|
||||
unsigned packet_len = msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
|
||||
/* check if there is space in the buffer, let it overflow else */
|
||||
if (buf_free < TX_BUFFER_GAP) {
|
||||
/* no enough space in buffer to send */
|
||||
count_txerr();
|
||||
count_txerrbytes(packet_len);
|
||||
pthread_mutex_unlock(&_send_mutex);
|
||||
return;
|
||||
}
|
||||
|
||||
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
|
||||
|
||||
/* header and payload */
|
||||
memcpy(&buf[0], &msg->magic, MAVLINK_NUM_HEADER_BYTES + msg->len);
|
||||
|
||||
/* checksum */
|
||||
buf[MAVLINK_NUM_HEADER_BYTES + msg->len] = (uint8_t)(msg->checksum & 0xFF);
|
||||
buf[MAVLINK_NUM_HEADER_BYTES + msg->len + 1] = (uint8_t)(msg->checksum >> 8);
|
||||
|
||||
/* send message to UART */
|
||||
ssize_t ret = write(_uart_fd, buf, packet_len);
|
||||
|
||||
if (ret != (int) packet_len) {
|
||||
count_txerr();
|
||||
count_txerrbytes(packet_len);
|
||||
|
||||
} else {
|
||||
_last_write_success_time = _last_write_try_time;
|
||||
count_txbytes(packet_len);
|
||||
}
|
||||
|
||||
pthread_mutex_unlock(&_send_mutex);
|
||||
}
|
||||
|
||||
void
|
||||
@ -801,7 +857,7 @@ Mavlink::handle_message(const mavlink_message_t *msg)
|
||||
_mission_manager->handle_message(msg);
|
||||
|
||||
/* handle packet with parameter component */
|
||||
mavlink_pm_message_handler(_channel, msg);
|
||||
_parameters_manager->handle_message(msg);
|
||||
|
||||
if (get_forwarding_on()) {
|
||||
/* forward any messages to other mavlink instances */
|
||||
@ -809,224 +865,32 @@ Mavlink::handle_message(const mavlink_message_t *msg)
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
Mavlink::mavlink_pm_queued_send()
|
||||
{
|
||||
if (_mavlink_param_queue_index < param_count()) {
|
||||
mavlink_pm_send_param(param_for_index(_mavlink_param_queue_index));
|
||||
_mavlink_param_queue_index++;
|
||||
return 0;
|
||||
|
||||
} else {
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
void Mavlink::mavlink_pm_start_queued_send()
|
||||
{
|
||||
_mavlink_param_queue_index = 0;
|
||||
}
|
||||
|
||||
int Mavlink::mavlink_pm_send_param_for_index(uint16_t index)
|
||||
{
|
||||
return mavlink_pm_send_param(param_for_index(index));
|
||||
}
|
||||
|
||||
int Mavlink::mavlink_pm_send_param_for_name(const char *name)
|
||||
{
|
||||
return mavlink_pm_send_param(param_find(name));
|
||||
}
|
||||
|
||||
int Mavlink::mavlink_pm_send_param(param_t param)
|
||||
{
|
||||
if (param == PARAM_INVALID) { return 1; }
|
||||
|
||||
/* buffers for param transmission */
|
||||
char name_buf[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN];
|
||||
float val_buf;
|
||||
mavlink_message_t tx_msg;
|
||||
|
||||
/* query parameter type */
|
||||
param_type_t type = param_type(param);
|
||||
/* copy parameter name */
|
||||
strncpy((char *)name_buf, param_name(param), MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
|
||||
|
||||
/*
|
||||
* Map onboard parameter type to MAVLink type,
|
||||
* endianess matches (both little endian)
|
||||
*/
|
||||
uint8_t mavlink_type;
|
||||
|
||||
if (type == PARAM_TYPE_INT32) {
|
||||
mavlink_type = MAVLINK_TYPE_INT32_T;
|
||||
|
||||
} else if (type == PARAM_TYPE_FLOAT) {
|
||||
mavlink_type = MAVLINK_TYPE_FLOAT;
|
||||
|
||||
} else {
|
||||
mavlink_type = MAVLINK_TYPE_FLOAT;
|
||||
}
|
||||
|
||||
/*
|
||||
* get param value, since MAVLink encodes float and int params in the same
|
||||
* space during transmission, copy param onto float val_buf
|
||||
*/
|
||||
|
||||
int ret;
|
||||
|
||||
if ((ret = param_get(param, &val_buf)) != OK) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
mavlink_msg_param_value_pack_chan(mavlink_system.sysid,
|
||||
mavlink_system.compid,
|
||||
_channel,
|
||||
&tx_msg,
|
||||
name_buf,
|
||||
val_buf,
|
||||
mavlink_type,
|
||||
param_count(),
|
||||
param_get_index(param));
|
||||
send_message(&tx_msg);
|
||||
return OK;
|
||||
}
|
||||
|
||||
void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_message_t *msg)
|
||||
{
|
||||
switch (msg->msgid) {
|
||||
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
|
||||
mavlink_param_request_list_t req;
|
||||
mavlink_msg_param_request_list_decode(msg, &req);
|
||||
|
||||
if (req.target_system == mavlink_system.sysid &&
|
||||
(req.target_component == mavlink_system.compid || req.target_component == MAV_COMP_ID_ALL)) {
|
||||
/* Start sending parameters */
|
||||
mavlink_pm_start_queued_send();
|
||||
send_statustext_info("[pm] sending list");
|
||||
}
|
||||
} break;
|
||||
|
||||
case MAVLINK_MSG_ID_PARAM_SET: {
|
||||
|
||||
/* Handle parameter setting */
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_PARAM_SET) {
|
||||
mavlink_param_set_t mavlink_param_set;
|
||||
mavlink_msg_param_set_decode(msg, &mavlink_param_set);
|
||||
|
||||
if (mavlink_param_set.target_system == mavlink_system.sysid
|
||||
&& ((mavlink_param_set.target_component == mavlink_system.compid)
|
||||
|| (mavlink_param_set.target_component == MAV_COMP_ID_ALL))) {
|
||||
/* local name buffer to enforce null-terminated string */
|
||||
char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1];
|
||||
strncpy(name, mavlink_param_set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
|
||||
/* enforce null termination */
|
||||
name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0';
|
||||
/* attempt to find parameter, set and send it */
|
||||
param_t param = param_find(name);
|
||||
|
||||
if (param == PARAM_INVALID) {
|
||||
char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN];
|
||||
sprintf(buf, "[pm] unknown: %s", name);
|
||||
send_statustext_info(buf);
|
||||
|
||||
} else {
|
||||
/* set and send parameter */
|
||||
param_set(param, &(mavlink_param_set.param_value));
|
||||
mavlink_pm_send_param(param);
|
||||
}
|
||||
}
|
||||
}
|
||||
} break;
|
||||
|
||||
case MAVLINK_MSG_ID_PARAM_REQUEST_READ: {
|
||||
mavlink_param_request_read_t mavlink_param_request_read;
|
||||
mavlink_msg_param_request_read_decode(msg, &mavlink_param_request_read);
|
||||
|
||||
if (mavlink_param_request_read.target_system == mavlink_system.sysid
|
||||
&& ((mavlink_param_request_read.target_component == mavlink_system.compid)
|
||||
|| (mavlink_param_request_read.target_component == MAV_COMP_ID_ALL))) {
|
||||
/* when no index is given, loop through string ids and compare them */
|
||||
if (mavlink_param_request_read.param_index == -1) {
|
||||
/* local name buffer to enforce null-terminated string */
|
||||
char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1];
|
||||
strncpy(name, mavlink_param_request_read.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
|
||||
/* enforce null termination */
|
||||
name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0';
|
||||
/* attempt to find parameter and send it */
|
||||
mavlink_pm_send_param_for_name(name);
|
||||
|
||||
} else {
|
||||
/* when index is >= 0, send this parameter again */
|
||||
mavlink_pm_send_param_for_index(mavlink_param_request_read.param_index);
|
||||
}
|
||||
}
|
||||
|
||||
} break;
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
void
|
||||
Mavlink::send_statustext_info(const char *string)
|
||||
{
|
||||
return send_statustext(MAVLINK_IOC_SEND_TEXT_INFO, string);
|
||||
send_statustext(MAV_SEVERITY_INFO, string);
|
||||
}
|
||||
|
||||
int
|
||||
void
|
||||
Mavlink::send_statustext_critical(const char *string)
|
||||
{
|
||||
return send_statustext(MAVLINK_IOC_SEND_TEXT_CRITICAL, string);
|
||||
send_statustext(MAV_SEVERITY_CRITICAL, string);
|
||||
}
|
||||
|
||||
int
|
||||
void
|
||||
Mavlink::send_statustext_emergency(const char *string)
|
||||
{
|
||||
return send_statustext(MAVLINK_IOC_SEND_TEXT_EMERGENCY, string);
|
||||
send_statustext(MAV_SEVERITY_EMERGENCY, string);
|
||||
}
|
||||
|
||||
int
|
||||
Mavlink::send_statustext(unsigned severity, const char *string)
|
||||
void
|
||||
Mavlink::send_statustext(unsigned char severity, const char *string)
|
||||
{
|
||||
const int len = MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN;
|
||||
mavlink_statustext_t statustext;
|
||||
struct mavlink_logmessage logmsg;
|
||||
strncpy(logmsg.text, string, sizeof(logmsg.text));
|
||||
logmsg.severity = severity;
|
||||
|
||||
int i = 0;
|
||||
|
||||
while (i < len - 1) {
|
||||
statustext.text[i] = string[i];
|
||||
|
||||
if (string[i] == '\0') {
|
||||
break;
|
||||
}
|
||||
|
||||
i++;
|
||||
}
|
||||
|
||||
if (i > 1) {
|
||||
/* Enforce null termination */
|
||||
statustext.text[i] = '\0';
|
||||
|
||||
/* Map severity */
|
||||
switch (severity) {
|
||||
case MAVLINK_IOC_SEND_TEXT_INFO:
|
||||
statustext.severity = MAV_SEVERITY_INFO;
|
||||
break;
|
||||
|
||||
case MAVLINK_IOC_SEND_TEXT_CRITICAL:
|
||||
statustext.severity = MAV_SEVERITY_CRITICAL;
|
||||
break;
|
||||
|
||||
case MAVLINK_IOC_SEND_TEXT_EMERGENCY:
|
||||
statustext.severity = MAV_SEVERITY_EMERGENCY;
|
||||
break;
|
||||
}
|
||||
|
||||
mavlink_msg_statustext_send(_channel, statustext.severity, statustext.text);
|
||||
return OK;
|
||||
|
||||
} else {
|
||||
return ERROR;
|
||||
}
|
||||
mavlink_logbuffer_write(&_logbuffer, &logmsg);
|
||||
}
|
||||
|
||||
MavlinkOrbSubscription *Mavlink::add_orb_subscription(const orb_id_t topic)
|
||||
@ -1049,11 +913,17 @@ MavlinkOrbSubscription *Mavlink::add_orb_subscription(const orb_id_t topic)
|
||||
return sub_new;
|
||||
}
|
||||
|
||||
unsigned int
|
||||
Mavlink::interval_from_rate(float rate)
|
||||
{
|
||||
return (rate > 0.0f) ? (1000000.0f / rate) : 0;
|
||||
}
|
||||
|
||||
int
|
||||
Mavlink::configure_stream(const char *stream_name, const float rate)
|
||||
{
|
||||
/* calculate interval in us, 0 means disabled stream */
|
||||
unsigned int interval = (rate > 0.0f) ? (1000000.0f / rate) : 0;
|
||||
unsigned int interval = interval_from_rate(rate);
|
||||
|
||||
/* search if stream exists */
|
||||
MavlinkStream *stream;
|
||||
@ -1084,10 +954,8 @@ Mavlink::configure_stream(const char *stream_name, const float rate)
|
||||
|
||||
if (strcmp(stream_name, streams_list[i]->get_name()) == 0) {
|
||||
/* create new instance */
|
||||
stream = streams_list[i]->new_instance();
|
||||
stream->set_channel(get_channel());
|
||||
stream = streams_list[i]->new_instance(this);
|
||||
stream->set_interval(interval);
|
||||
stream->subscribe(this);
|
||||
LL_APPEND(_streams, stream);
|
||||
|
||||
return OK;
|
||||
@ -1100,6 +968,31 @@ Mavlink::configure_stream(const char *stream_name, const float rate)
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
void
|
||||
Mavlink::adjust_stream_rates(const float multiplier)
|
||||
{
|
||||
/* do not allow to push us to zero */
|
||||
if (multiplier < 0.01f) {
|
||||
return;
|
||||
}
|
||||
|
||||
/* search if stream exists */
|
||||
MavlinkStream *stream;
|
||||
LL_FOREACH(_streams, stream) {
|
||||
/* set new interval */
|
||||
unsigned interval = stream->get_interval();
|
||||
interval /= multiplier;
|
||||
|
||||
/* allow max ~600 Hz */
|
||||
if (interval < 1600) {
|
||||
interval = 1600;
|
||||
}
|
||||
|
||||
/* set new interval */
|
||||
stream->set_interval(interval * multiplier);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Mavlink::configure_stream_threadsafe(const char *stream_name, const float rate)
|
||||
{
|
||||
@ -1260,7 +1153,27 @@ Mavlink::pass_message(const mavlink_message_t *msg)
|
||||
float
|
||||
Mavlink::get_rate_mult()
|
||||
{
|
||||
return _datarate / 1000.0f;
|
||||
return _rate_mult;
|
||||
}
|
||||
|
||||
void
|
||||
Mavlink::update_rate_mult()
|
||||
{
|
||||
float const_rate = 0.0f;
|
||||
float rate = 0.0f;
|
||||
|
||||
MavlinkStream *stream;
|
||||
LL_FOREACH(_streams, stream) {
|
||||
if (stream->const_rate()) {
|
||||
const_rate += stream->get_size() * 1000000.0f / stream->get_interval();
|
||||
|
||||
} else {
|
||||
rate += stream->get_size() * 1000000.0f / stream->get_interval();
|
||||
}
|
||||
}
|
||||
|
||||
/* don't scale up rates, only scale down if needed */
|
||||
_rate_mult = fminf(1.0f, ((float)_datarate - const_rate) / rate);
|
||||
}
|
||||
|
||||
int
|
||||
@ -1398,6 +1311,9 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* initialize send mutex */
|
||||
pthread_mutex_init(&_send_mutex, NULL);
|
||||
|
||||
/* initialize mavlink text message buffering */
|
||||
mavlink_logbuffer_init(&_logbuffer, 5);
|
||||
|
||||
@ -1407,7 +1323,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
* make space for two messages plus off-by-one space as we use the empty element
|
||||
* marker ring buffer approach.
|
||||
*/
|
||||
if (OK != message_buffer_init(2 * MAVLINK_MAX_PACKET_LEN + 2)) {
|
||||
if (OK != message_buffer_init(2 * sizeof(mavlink_message_t) + 1)) {
|
||||
errx(1, "can't allocate message buffer, exiting");
|
||||
}
|
||||
|
||||
@ -1427,12 +1343,6 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
/* start the MAVLink receiver */
|
||||
_receive_thread = MavlinkReceiver::receive_start(this);
|
||||
|
||||
_mission_result_sub = orb_subscribe(ORB_ID(mission_result));
|
||||
|
||||
/* create mission manager */
|
||||
_mission_manager = new MavlinkMissionManager(this);
|
||||
_mission_manager->set_verbose(_verbose);
|
||||
|
||||
_task_running = true;
|
||||
|
||||
MavlinkOrbSubscription *param_sub = add_orb_subscription(ORB_ID(parameter_update));
|
||||
@ -1443,34 +1353,50 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
struct vehicle_status_s status;
|
||||
status_sub->update(&status_time, &status);
|
||||
|
||||
MavlinkCommandsStream commands_stream(this, _channel);
|
||||
|
||||
/* add default streams depending on mode and intervals depending on datarate */
|
||||
float rate_mult = get_rate_mult();
|
||||
/* add default streams depending on mode */
|
||||
|
||||
/* HEARTBEAT is constant rate stream, rate never adjusted */
|
||||
configure_stream("HEARTBEAT", 1.0f);
|
||||
|
||||
/* STATUSTEXT stream is like normal stream but gets messages from logbuffer instead of uORB */
|
||||
configure_stream("STATUSTEXT", 20.0f);
|
||||
|
||||
/* COMMAND_LONG stream: use high rate to avoid commands skipping */
|
||||
configure_stream("COMMAND_LONG", 100.0f);
|
||||
|
||||
/* PARAM_VALUE stream */
|
||||
_parameters_manager = (MavlinkParametersManager *) MavlinkParametersManager::new_instance(this);
|
||||
_parameters_manager->set_interval(interval_from_rate(30.0f));
|
||||
LL_APPEND(_streams, _parameters_manager);
|
||||
|
||||
/* MISSION_STREAM stream, actually sends all MISSION_XXX messages at some rate depending on
|
||||
* remote requests rate. Rate specified here controls how much bandwidth we will reserve for
|
||||
* mission messages. */
|
||||
_mission_manager = (MavlinkMissionManager *) MavlinkMissionManager::new_instance(this);
|
||||
_mission_manager->set_interval(interval_from_rate(10.0f));
|
||||
_mission_manager->set_verbose(_verbose);
|
||||
LL_APPEND(_streams, _mission_manager);
|
||||
|
||||
switch (_mode) {
|
||||
case MAVLINK_MODE_NORMAL:
|
||||
configure_stream("SYS_STATUS", 1.0f);
|
||||
configure_stream("GPS_GLOBAL_ORIGIN", 0.5f);
|
||||
configure_stream("HIGHRES_IMU", 1.0f * rate_mult);
|
||||
configure_stream("ATTITUDE", 10.0f * rate_mult);
|
||||
configure_stream("VFR_HUD", 8.0f * rate_mult);
|
||||
configure_stream("GPS_RAW_INT", 1.0f * rate_mult);
|
||||
configure_stream("GLOBAL_POSITION_INT", 3.0f * rate_mult);
|
||||
configure_stream("LOCAL_POSITION_NED", 3.0f * rate_mult);
|
||||
configure_stream("RC_CHANNELS_RAW", 1.0f * rate_mult);
|
||||
configure_stream("NAMED_VALUE_FLOAT", 1.0f * rate_mult);
|
||||
configure_stream("GLOBAL_POSITION_SETPOINT_INT", 3.0f * rate_mult);
|
||||
configure_stream("ROLL_PITCH_YAW_THRUST_SETPOINT", 3.0f * rate_mult);
|
||||
configure_stream("HIGHRES_IMU", 1.0f);
|
||||
configure_stream("ATTITUDE", 10.0f);
|
||||
configure_stream("VFR_HUD", 8.0f);
|
||||
configure_stream("GPS_RAW_INT", 1.0f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 3.0f);
|
||||
configure_stream("LOCAL_POSITION_NED", 3.0f);
|
||||
configure_stream("RC_CHANNELS_RAW", 1.0f);
|
||||
configure_stream("GLOBAL_POSITION_SETPOINT_INT", 3.0f);
|
||||
configure_stream("ROLL_PITCH_YAW_THRUST_SETPOINT", 3.0f);
|
||||
configure_stream("DISTANCE_SENSOR", 0.5f);
|
||||
break;
|
||||
|
||||
case MAVLINK_MODE_CAMERA:
|
||||
configure_stream("SYS_STATUS", 1.0f);
|
||||
configure_stream("ATTITUDE", 15.0f * rate_mult);
|
||||
configure_stream("GLOBAL_POSITION_INT", 15.0f * rate_mult);
|
||||
configure_stream("ATTITUDE", 15.0f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 15.0f);
|
||||
configure_stream("CAMERA_CAPTURE", 1.0f);
|
||||
break;
|
||||
|
||||
@ -1478,13 +1404,8 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
break;
|
||||
}
|
||||
|
||||
/* don't send parameters on startup without request */
|
||||
_mavlink_param_queue_index = param_count();
|
||||
|
||||
MavlinkRateLimiter fast_rate_limiter(30000.0f / rate_mult);
|
||||
|
||||
/* set main loop delay depending on data rate to minimize CPU overhead */
|
||||
_main_loop_delay = MAIN_LOOP_DELAY / rate_mult;
|
||||
_main_loop_delay = MAIN_LOOP_DELAY * 1000 / _datarate;
|
||||
|
||||
/* now the instance is fully initialized and we can bump the instance count */
|
||||
LL_APPEND(_mavlink_instances, this);
|
||||
@ -1497,6 +1418,8 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
|
||||
hrt_abstime t = hrt_absolute_time();
|
||||
|
||||
update_rate_mult();
|
||||
|
||||
if (param_sub->update(¶m_time, nullptr)) {
|
||||
/* parameters updated */
|
||||
mavlink_update_system();
|
||||
@ -1507,9 +1430,6 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
set_hil_enabled(status.hil_state == HIL_STATE_ON);
|
||||
}
|
||||
|
||||
/* update commands stream */
|
||||
commands_stream.update(t);
|
||||
|
||||
/* check for requested subscriptions */
|
||||
if (_subscribe_to_stream != nullptr) {
|
||||
if (OK == configure_stream(_subscribe_to_stream, _subscribe_to_stream_rate)) {
|
||||
@ -1535,20 +1455,6 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
stream->update(t);
|
||||
}
|
||||
|
||||
if (fast_rate_limiter.check(t)) {
|
||||
mavlink_pm_queued_send();
|
||||
_mission_manager->eventloop();
|
||||
|
||||
if (!mavlink_logbuffer_is_empty(&_logbuffer)) {
|
||||
struct mavlink_logmessage msg;
|
||||
int lb_ret = mavlink_logbuffer_read(&_logbuffer, &msg);
|
||||
|
||||
if (lb_ret == OK) {
|
||||
send_statustext(msg.severity, msg.text);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* pass messages from other UARTs or FTP worker */
|
||||
if (_passing_on || _ftp_on) {
|
||||
|
||||
@ -1593,7 +1499,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
|
||||
pthread_mutex_unlock(&_message_buffer_mutex);
|
||||
|
||||
_mavlink_resend_uart(_channel, &msg);
|
||||
resend_message(&msg);
|
||||
}
|
||||
}
|
||||
|
||||
@ -1608,14 +1514,13 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
_bytes_txerr = 0;
|
||||
_bytes_rx = 0;
|
||||
}
|
||||
|
||||
_bytes_timestamp = t;
|
||||
}
|
||||
|
||||
perf_end(_loop_perf);
|
||||
}
|
||||
|
||||
delete _mission_manager;
|
||||
|
||||
delete _subscribe_to_stream;
|
||||
_subscribe_to_stream = nullptr;
|
||||
|
||||
@ -1773,10 +1678,12 @@ Mavlink::display_status()
|
||||
} else {
|
||||
printf("\tno telem status.\n");
|
||||
}
|
||||
|
||||
printf("\trates:\n");
|
||||
printf("\ttx: %.3f kB/s\n", (double)_rate_tx);
|
||||
printf("\ttxerr: %.3f kB/s\n", (double)_rate_txerr);
|
||||
printf("\trx: %.3f kB/s\n", (double)_rate_rx);
|
||||
printf("\trate mult: %.3f\n", (double)_rate_mult);
|
||||
}
|
||||
|
||||
int
|
||||
|
||||
@ -58,7 +58,7 @@
|
||||
#include "mavlink_stream.h"
|
||||
#include "mavlink_messages.h"
|
||||
#include "mavlink_mission.h"
|
||||
|
||||
#include "mavlink_parameters.h"
|
||||
|
||||
class Mavlink
|
||||
{
|
||||
@ -160,7 +160,12 @@ public:
|
||||
*/
|
||||
int set_hil_enabled(bool hil_enabled);
|
||||
|
||||
void send_message(const mavlink_message_t *msg);
|
||||
void send_message(const uint8_t msgid, const void *msg);
|
||||
|
||||
/**
|
||||
* Resend message as is, don't change sequence number and CRC.
|
||||
*/
|
||||
void resend_message(mavlink_message_t *msg);
|
||||
|
||||
void handle_message(const mavlink_message_t *msg);
|
||||
|
||||
@ -188,29 +193,33 @@ public:
|
||||
*
|
||||
* @param string the message to send (will be capped by mavlink max string length)
|
||||
*/
|
||||
int send_statustext_info(const char *string);
|
||||
void send_statustext_info(const char *string);
|
||||
|
||||
/**
|
||||
* Send a status text with loglevel CRITICAL
|
||||
*
|
||||
* @param string the message to send (will be capped by mavlink max string length)
|
||||
*/
|
||||
int send_statustext_critical(const char *string);
|
||||
void send_statustext_critical(const char *string);
|
||||
|
||||
/**
|
||||
* Send a status text with loglevel EMERGENCY
|
||||
*
|
||||
* @param string the message to send (will be capped by mavlink max string length)
|
||||
*/
|
||||
int send_statustext_emergency(const char *string);
|
||||
void send_statustext_emergency(const char *string);
|
||||
|
||||
/**
|
||||
* Send a status text with loglevel
|
||||
* Send a status text with loglevel, the difference from mavlink_log_xxx() is that message sent
|
||||
* only on this mavlink connection. Useful for reporting communication specific, not system-wide info
|
||||
* only to client interested in it. Message will be not sent immediately but queued in buffer as
|
||||
* for mavlink_log_xxx().
|
||||
*
|
||||
* @param string the message to send (will be capped by mavlink max string length)
|
||||
* @param severity the log level, one of
|
||||
* @param severity the log level
|
||||
*/
|
||||
int send_statustext(unsigned severity, const char *string);
|
||||
void send_statustext(unsigned char severity, const char *string);
|
||||
|
||||
MavlinkStream * get_streams() const { return _streams; }
|
||||
|
||||
float get_rate_mult();
|
||||
@ -252,6 +261,8 @@ public:
|
||||
*/
|
||||
struct telemetry_status_s& get_rx_status() { return _rstatus; }
|
||||
|
||||
struct mavlink_logbuffer *get_logbuffer() { return &_logbuffer; }
|
||||
|
||||
protected:
|
||||
Mavlink *next;
|
||||
|
||||
@ -274,9 +285,8 @@ private:
|
||||
MavlinkStream *_streams;
|
||||
|
||||
MavlinkMissionManager *_mission_manager;
|
||||
MavlinkParametersManager *_parameters_manager;
|
||||
|
||||
orb_advert_t _mission_pub;
|
||||
int _mission_result_sub;
|
||||
MAVLINK_MODE _mode;
|
||||
|
||||
mavlink_channel_t _channel;
|
||||
@ -292,7 +302,9 @@ private:
|
||||
bool _ftp_on;
|
||||
int _uart_fd;
|
||||
int _baudrate;
|
||||
int _datarate;
|
||||
int _datarate; ///< data rate for normal streams (attitude, position, etc.)
|
||||
int _datarate_events; ///< data rate for params, waypoints, text messages
|
||||
float _rate_mult;
|
||||
|
||||
/**
|
||||
* If the queue index is not at 0, the queue sending
|
||||
@ -307,6 +319,8 @@ private:
|
||||
float _subscribe_to_stream_rate;
|
||||
|
||||
bool _flow_control_enabled;
|
||||
uint64_t _last_write_success_time;
|
||||
uint64_t _last_write_try_time;
|
||||
|
||||
unsigned _bytes_tx;
|
||||
unsigned _bytes_txerr;
|
||||
@ -328,6 +342,7 @@ private:
|
||||
mavlink_message_buffer _message_buffer;
|
||||
|
||||
pthread_mutex_t _message_buffer_mutex;
|
||||
pthread_mutex_t _send_mutex;
|
||||
|
||||
bool _param_initialized;
|
||||
param_t _param_system_id;
|
||||
@ -338,53 +353,28 @@ private:
|
||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||
perf_counter_t _txerr_perf; /**< TX error counter */
|
||||
|
||||
/**
|
||||
* Send one parameter.
|
||||
*
|
||||
* @param param The parameter id to send.
|
||||
* @return zero on success, nonzero on failure.
|
||||
*/
|
||||
int mavlink_pm_send_param(param_t param);
|
||||
|
||||
/**
|
||||
* Send one parameter identified by index.
|
||||
*
|
||||
* @param index The index of the parameter to send.
|
||||
* @return zero on success, nonzero else.
|
||||
*/
|
||||
int mavlink_pm_send_param_for_index(uint16_t index);
|
||||
|
||||
/**
|
||||
* Send one parameter identified by name.
|
||||
*
|
||||
* @param name The index of the parameter to send.
|
||||
* @return zero on success, nonzero else.
|
||||
*/
|
||||
int mavlink_pm_send_param_for_name(const char *name);
|
||||
|
||||
/**
|
||||
* Send a queue of parameters, one parameter per function call.
|
||||
*
|
||||
* @return zero on success, nonzero on failure
|
||||
*/
|
||||
int mavlink_pm_queued_send(void);
|
||||
|
||||
/**
|
||||
* Start sending the parameter queue.
|
||||
*
|
||||
* This function will not directly send parameters, but instead
|
||||
* activate the sending of one parameter on each call of
|
||||
* mavlink_pm_queued_send().
|
||||
* @see mavlink_pm_queued_send()
|
||||
*/
|
||||
void mavlink_pm_start_queued_send();
|
||||
|
||||
void mavlink_update_system();
|
||||
|
||||
int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_config_original, bool *is_usb);
|
||||
|
||||
/**
|
||||
* Get the free space in the transmit buffer
|
||||
*
|
||||
* @return free space in the UART TX buffer
|
||||
*/
|
||||
unsigned get_free_tx_buf();
|
||||
|
||||
static unsigned int interval_from_rate(float rate);
|
||||
|
||||
int configure_stream(const char *stream_name, const float rate);
|
||||
|
||||
/**
|
||||
* Adjust the stream rates based on the current rate
|
||||
*
|
||||
* @param multiplier if greater than 1, the transmission rate will increase, if smaller than one decrease
|
||||
*/
|
||||
void adjust_stream_rates(const float multiplier);
|
||||
|
||||
int message_buffer_init(int size);
|
||||
|
||||
void message_buffer_destroy();
|
||||
@ -399,6 +389,11 @@ private:
|
||||
|
||||
void pass_message(const mavlink_message_t *msg);
|
||||
|
||||
/**
|
||||
* Update rate mult so total bitrate will be equal to _datarate.
|
||||
*/
|
||||
void update_rate_mult();
|
||||
|
||||
static int mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@ -46,10 +46,10 @@
|
||||
class StreamListItem {
|
||||
|
||||
public:
|
||||
MavlinkStream* (*new_instance)();
|
||||
MavlinkStream* (*new_instance)(Mavlink *mavlink);
|
||||
const char* (*get_name)();
|
||||
|
||||
StreamListItem(MavlinkStream* (*inst)(), const char* (*name)()) :
|
||||
StreamListItem(MavlinkStream* (*inst)(Mavlink *mavlink), const char* (*name)()) :
|
||||
new_instance(inst),
|
||||
get_name(name) {};
|
||||
|
||||
|
||||
@ -59,8 +59,7 @@
|
||||
static const int ERROR = -1;
|
||||
|
||||
|
||||
MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) :
|
||||
_mavlink(mavlink),
|
||||
MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) : MavlinkStream(mavlink),
|
||||
_state(MAVLINK_WPM_STATE_IDLE),
|
||||
_time_last_recv(0),
|
||||
_time_last_sent(0),
|
||||
@ -79,9 +78,8 @@ MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) :
|
||||
_offboard_mission_sub(-1),
|
||||
_mission_result_sub(-1),
|
||||
_offboard_mission_pub(-1),
|
||||
_slow_rate_limiter(2000000.0f / mavlink->get_rate_mult()),
|
||||
_slow_rate_limiter(_interval / 10.0f),
|
||||
_verbose(false),
|
||||
_channel(mavlink->get_channel()),
|
||||
_comp_id(MAV_COMP_ID_MISSIONPLANNER)
|
||||
{
|
||||
_offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission));
|
||||
@ -96,6 +94,20 @@ MavlinkMissionManager::~MavlinkMissionManager()
|
||||
close(_mission_result_sub);
|
||||
}
|
||||
|
||||
unsigned
|
||||
MavlinkMissionManager::get_size()
|
||||
{
|
||||
if (_state == MAVLINK_WPM_STATE_SENDLIST) {
|
||||
return MAVLINK_MSG_ID_MISSION_ITEM_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
|
||||
} else if (_state == MAVLINK_WPM_STATE_GETLIST) {
|
||||
return MAVLINK_MSG_ID_MISSION_REQUEST + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
MavlinkMissionManager::init_offboard_mission()
|
||||
{
|
||||
@ -157,15 +169,13 @@ MavlinkMissionManager::update_active_mission(int dataman_id, unsigned count, int
|
||||
void
|
||||
MavlinkMissionManager::send_mission_ack(uint8_t sysid, uint8_t compid, uint8_t type)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_mission_ack_t wpa;
|
||||
|
||||
wpa.target_system = sysid;
|
||||
wpa.target_component = compid;
|
||||
wpa.type = type;
|
||||
|
||||
mavlink_msg_mission_ack_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpa);
|
||||
_mavlink->send_message(&msg);
|
||||
_mavlink->send_message(MAVLINK_MSG_ID_MISSION_ACK, &wpa);
|
||||
|
||||
if (_verbose) { warnx("WPM: Send MISSION_ACK type %u to ID %u", wpa.type, wpa.target_system); }
|
||||
}
|
||||
@ -175,13 +185,11 @@ void
|
||||
MavlinkMissionManager::send_mission_current(uint16_t seq)
|
||||
{
|
||||
if (seq < _count) {
|
||||
mavlink_message_t msg;
|
||||
mavlink_mission_current_t wpc;
|
||||
|
||||
wpc.seq = seq;
|
||||
|
||||
mavlink_msg_mission_current_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpc);
|
||||
_mavlink->send_message(&msg);
|
||||
_mavlink->send_message(MAVLINK_MSG_ID_MISSION_CURRENT, &wpc);
|
||||
|
||||
} else if (seq == 0 && _count == 0) {
|
||||
/* don't broadcast if no WPs */
|
||||
@ -199,15 +207,13 @@ MavlinkMissionManager::send_mission_count(uint8_t sysid, uint8_t compid, uint16_
|
||||
{
|
||||
_time_last_sent = hrt_absolute_time();
|
||||
|
||||
mavlink_message_t msg;
|
||||
mavlink_mission_count_t wpc;
|
||||
|
||||
wpc.target_system = sysid;
|
||||
wpc.target_component = compid;
|
||||
wpc.count = _count;
|
||||
|
||||
mavlink_msg_mission_count_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpc);
|
||||
_mavlink->send_message(&msg);
|
||||
_mavlink->send_message(MAVLINK_MSG_ID_MISSION_COUNT, &wpc);
|
||||
|
||||
if (_verbose) { warnx("WPM: Send MISSION_COUNT %u to ID %u", wpc.count, wpc.target_system); }
|
||||
}
|
||||
@ -226,13 +232,12 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t
|
||||
mavlink_mission_item_t wp;
|
||||
format_mavlink_mission_item(&mission_item, &wp);
|
||||
|
||||
mavlink_message_t msg;
|
||||
wp.target_system = sysid;
|
||||
wp.target_component = compid;
|
||||
wp.seq = seq;
|
||||
wp.current = (_current_seq == seq) ? 1 : 0;
|
||||
mavlink_msg_mission_item_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wp);
|
||||
_mavlink->send_message(&msg);
|
||||
|
||||
_mavlink->send_message(MAVLINK_MSG_ID_MISSION_ITEM, &wp);
|
||||
|
||||
if (_verbose) { warnx("WPM: Send MISSION_ITEM seq %u to ID %u", wp.seq, wp.target_system); }
|
||||
|
||||
@ -251,13 +256,12 @@ MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint1
|
||||
if (seq < _max_count) {
|
||||
_time_last_sent = hrt_absolute_time();
|
||||
|
||||
mavlink_message_t msg;
|
||||
mavlink_mission_request_t wpr;
|
||||
wpr.target_system = sysid;
|
||||
wpr.target_component = compid;
|
||||
wpr.seq = seq;
|
||||
mavlink_msg_mission_request_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpr);
|
||||
_mavlink->send_message(&msg);
|
||||
|
||||
_mavlink->send_message(MAVLINK_MSG_ID_MISSION_REQUEST, &wpr);
|
||||
|
||||
if (_verbose) { warnx("WPM: Send MISSION_REQUEST seq %u to ID %u", wpr.seq, wpr.target_system); }
|
||||
|
||||
@ -272,22 +276,21 @@ MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint1
|
||||
void
|
||||
MavlinkMissionManager::send_mission_item_reached(uint16_t seq)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_mission_item_reached_t wp_reached;
|
||||
|
||||
wp_reached.seq = seq;
|
||||
|
||||
mavlink_msg_mission_item_reached_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wp_reached);
|
||||
_mavlink->send_message(&msg);
|
||||
_mavlink->send_message(MAVLINK_MSG_ID_MISSION_ITEM_REACHED, &wp_reached);
|
||||
|
||||
if (_verbose) { warnx("WPM: Send MISSION_ITEM_REACHED reached_seq %u", wp_reached.seq); }
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
MavlinkMissionManager::eventloop()
|
||||
MavlinkMissionManager::send(const hrt_abstime now)
|
||||
{
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
/* update interval for slow rate limiter */
|
||||
_slow_rate_limiter.set_interval(_interval * 10 / _mavlink->get_rate_mult());
|
||||
|
||||
bool updated = false;
|
||||
orb_check(_mission_result_sub, &updated);
|
||||
|
||||
@ -42,11 +42,12 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include "mavlink_rate_limiter.h"
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
// FIXME XXX - TO BE MOVED TO XML
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include "mavlink_rate_limiter.h"
|
||||
#include "mavlink_stream.h"
|
||||
|
||||
enum MAVLINK_WPM_STATES {
|
||||
MAVLINK_WPM_STATE_IDLE = 0,
|
||||
MAVLINK_WPM_STATE_SENDLIST,
|
||||
@ -66,20 +67,75 @@ enum MAVLINK_WPM_CODES {
|
||||
#define MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT 5000000 ///< Protocol communication action timeout in useconds
|
||||
#define MAVLINK_MISSION_RETRY_TIMEOUT_DEFAULT 500000 ///< Protocol communication retry timeout in useconds
|
||||
|
||||
class Mavlink;
|
||||
|
||||
class MavlinkMissionManager {
|
||||
class MavlinkMissionManager : public MavlinkStream {
|
||||
public:
|
||||
MavlinkMissionManager(Mavlink *parent);
|
||||
|
||||
~MavlinkMissionManager();
|
||||
|
||||
const char *get_name() const
|
||||
{
|
||||
return MavlinkMissionManager::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
{
|
||||
return "MISSION_ITEM";
|
||||
}
|
||||
|
||||
uint8_t get_id()
|
||||
{
|
||||
return MAVLINK_MSG_ID_MISSION_ITEM;
|
||||
}
|
||||
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink)
|
||||
{
|
||||
return new MavlinkMissionManager(mavlink);
|
||||
}
|
||||
|
||||
unsigned get_size();
|
||||
|
||||
void handle_message(const mavlink_message_t *msg);
|
||||
|
||||
void set_verbose(bool v) { _verbose = v; }
|
||||
|
||||
private:
|
||||
enum MAVLINK_WPM_STATES _state; ///< Current state
|
||||
|
||||
uint64_t _time_last_recv;
|
||||
uint64_t _time_last_sent;
|
||||
|
||||
uint32_t _action_timeout;
|
||||
uint32_t _retry_timeout;
|
||||
unsigned _max_count; ///< Maximum number of mission items
|
||||
|
||||
int _dataman_id; ///< Dataman storage ID for active mission
|
||||
unsigned _count; ///< Count of items in active mission
|
||||
int _current_seq; ///< Current item sequence in active mission
|
||||
|
||||
int _transfer_dataman_id; ///< Dataman storage ID for current transmission
|
||||
unsigned _transfer_count; ///< Items count in current transmission
|
||||
unsigned _transfer_seq; ///< Item sequence in current transmission
|
||||
unsigned _transfer_current_seq; ///< Current item ID for current transmission (-1 means not initialized)
|
||||
unsigned _transfer_partner_sysid; ///< Partner system ID for current transmission
|
||||
unsigned _transfer_partner_compid; ///< Partner component ID for current transmission
|
||||
|
||||
int _offboard_mission_sub;
|
||||
int _mission_result_sub;
|
||||
orb_advert_t _offboard_mission_pub;
|
||||
|
||||
MavlinkRateLimiter _slow_rate_limiter;
|
||||
|
||||
bool _verbose;
|
||||
|
||||
uint8_t _comp_id;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkMissionManager(MavlinkMissionManager &);
|
||||
MavlinkMissionManager& operator = (const MavlinkMissionManager &);
|
||||
|
||||
void init_offboard_mission();
|
||||
|
||||
int update_active_mission(int dataman_id, unsigned count, int seq);
|
||||
|
||||
void send_message(mavlink_message_t *msg);
|
||||
|
||||
/**
|
||||
* @brief Sends an waypoint ack message
|
||||
*/
|
||||
@ -111,10 +167,6 @@ public:
|
||||
*/
|
||||
void send_mission_item_reached(uint16_t seq);
|
||||
|
||||
void eventloop();
|
||||
|
||||
void handle_message(const mavlink_message_t *msg);
|
||||
|
||||
void handle_mission_ack(const mavlink_message_t *msg);
|
||||
|
||||
void handle_mission_set_current(const mavlink_message_t *msg);
|
||||
@ -139,43 +191,8 @@ public:
|
||||
*/
|
||||
int format_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item);
|
||||
|
||||
void set_verbose(bool v) { _verbose = v; }
|
||||
protected:
|
||||
explicit MavlinkMissionManager(Mavlink *mavlink);
|
||||
|
||||
private:
|
||||
Mavlink* _mavlink;
|
||||
|
||||
enum MAVLINK_WPM_STATES _state; ///< Current state
|
||||
|
||||
uint64_t _time_last_recv;
|
||||
uint64_t _time_last_sent;
|
||||
|
||||
uint32_t _action_timeout;
|
||||
uint32_t _retry_timeout;
|
||||
unsigned _max_count; ///< Maximum number of mission items
|
||||
|
||||
int _dataman_id; ///< Dataman storage ID for active mission
|
||||
unsigned _count; ///< Count of items in active mission
|
||||
int _current_seq; ///< Current item sequence in active mission
|
||||
|
||||
int _transfer_dataman_id; ///< Dataman storage ID for current transmission
|
||||
unsigned _transfer_count; ///< Items count in current transmission
|
||||
unsigned _transfer_seq; ///< Item sequence in current transmission
|
||||
unsigned _transfer_current_seq; ///< Current item ID for current transmission (-1 means not initialized)
|
||||
unsigned _transfer_partner_sysid; ///< Partner system ID for current transmission
|
||||
unsigned _transfer_partner_compid; ///< Partner component ID for current transmission
|
||||
|
||||
int _offboard_mission_sub;
|
||||
int _mission_result_sub;
|
||||
orb_advert_t _offboard_mission_pub;
|
||||
|
||||
MavlinkRateLimiter _slow_rate_limiter;
|
||||
|
||||
bool _verbose;
|
||||
|
||||
mavlink_channel_t _channel;
|
||||
uint8_t _comp_id;
|
||||
|
||||
/* do not allow copying this class */
|
||||
MavlinkMissionManager(const MavlinkMissionManager&);
|
||||
MavlinkMissionManager operator=(const MavlinkMissionManager&);
|
||||
void send(const hrt_abstime t);
|
||||
};
|
||||
|
||||
197
src/modules/mavlink/mavlink_parameters.cpp
Normal file
197
src/modules/mavlink/mavlink_parameters.cpp
Normal file
@ -0,0 +1,197 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 mavlink_parameters.cpp
|
||||
* Mavlink parameters manager implementation.
|
||||
*
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
#include "mavlink_parameters.h"
|
||||
#include "mavlink_main.h"
|
||||
|
||||
MavlinkParametersManager::MavlinkParametersManager(Mavlink *mavlink) : MavlinkStream(mavlink),
|
||||
_send_all_index(-1)
|
||||
{
|
||||
}
|
||||
|
||||
unsigned
|
||||
MavlinkParametersManager::get_size()
|
||||
{
|
||||
if (_send_all_index >= 0) {
|
||||
return MAVLINK_MSG_ID_PARAM_VALUE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
|
||||
{
|
||||
switch (msg->msgid) {
|
||||
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
|
||||
/* request all parameters */
|
||||
mavlink_param_request_list_t req_list;
|
||||
mavlink_msg_param_request_list_decode(msg, &req_list);
|
||||
|
||||
if (req_list.target_system == mavlink_system.sysid &&
|
||||
(req_list.target_component == mavlink_system.compid || req_list.target_component == MAV_COMP_ID_ALL)) {
|
||||
|
||||
_send_all_index = 0;
|
||||
_mavlink->send_statustext_info("[pm] sending list");
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_PARAM_SET: {
|
||||
/* set parameter */
|
||||
if (msg->msgid == MAVLINK_MSG_ID_PARAM_SET) {
|
||||
mavlink_param_set_t set;
|
||||
mavlink_msg_param_set_decode(msg, &set);
|
||||
|
||||
if (set.target_system == mavlink_system.sysid &&
|
||||
(set.target_component == mavlink_system.compid || set.target_component == MAV_COMP_ID_ALL)) {
|
||||
|
||||
/* local name buffer to enforce null-terminated string */
|
||||
char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1];
|
||||
strncpy(name, set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
|
||||
/* enforce null termination */
|
||||
name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0';
|
||||
/* attempt to find parameter, set and send it */
|
||||
param_t param = param_find(name);
|
||||
|
||||
if (param == PARAM_INVALID) {
|
||||
char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN];
|
||||
sprintf(buf, "[pm] unknown param: %s", name);
|
||||
_mavlink->send_statustext_info(buf);
|
||||
|
||||
} else {
|
||||
/* set and send parameter */
|
||||
param_set(param, &(set.param_value));
|
||||
send_param(param);
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_PARAM_REQUEST_READ: {
|
||||
/* request one parameter */
|
||||
mavlink_param_request_read_t req_read;
|
||||
mavlink_msg_param_request_read_decode(msg, &req_read);
|
||||
|
||||
if (req_read.target_system == mavlink_system.sysid &&
|
||||
(req_read.target_component == mavlink_system.compid || req_read.target_component == MAV_COMP_ID_ALL)) {
|
||||
|
||||
/* when no index is given, loop through string ids and compare them */
|
||||
if (req_read.param_index < 0) {
|
||||
/* local name buffer to enforce null-terminated string */
|
||||
char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1];
|
||||
strncpy(name, req_read.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
|
||||
/* enforce null termination */
|
||||
name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0';
|
||||
/* attempt to find parameter and send it */
|
||||
send_param(param_find(name));
|
||||
|
||||
} else {
|
||||
/* when index is >= 0, send this parameter again */
|
||||
send_param(param_for_index(req_read.param_index));
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
MavlinkParametersManager::send(const hrt_abstime t)
|
||||
{
|
||||
/* send all parameters if requested */
|
||||
if (_send_all_index >= 0) {
|
||||
send_param(param_for_index(_send_all_index));
|
||||
_send_all_index++;
|
||||
if (_send_all_index >= (int) param_count()) {
|
||||
_send_all_index = -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
MavlinkParametersManager::send_param(param_t param)
|
||||
{
|
||||
if (param == PARAM_INVALID) {
|
||||
return;
|
||||
}
|
||||
|
||||
mavlink_param_value_t msg;
|
||||
|
||||
/*
|
||||
* get param value, since MAVLink encodes float and int params in the same
|
||||
* space during transmission, copy param onto float val_buf
|
||||
*/
|
||||
if (param_get(param, &msg.param_value) != OK) {
|
||||
return;
|
||||
}
|
||||
|
||||
msg.param_count = param_count();
|
||||
msg.param_index = param_get_index(param);
|
||||
|
||||
/* copy parameter name */
|
||||
strncpy(msg.param_id, param_name(param), MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
|
||||
|
||||
/* query parameter type */
|
||||
param_type_t type = param_type(param);
|
||||
|
||||
/*
|
||||
* Map onboard parameter type to MAVLink type,
|
||||
* endianess matches (both little endian)
|
||||
*/
|
||||
if (type == PARAM_TYPE_INT32) {
|
||||
msg.param_type = MAVLINK_TYPE_INT32_T;
|
||||
|
||||
} else if (type == PARAM_TYPE_FLOAT) {
|
||||
msg.param_type = MAVLINK_TYPE_FLOAT;
|
||||
|
||||
} else {
|
||||
msg.param_type = MAVLINK_TYPE_FLOAT;
|
||||
}
|
||||
|
||||
_mavlink->send_message(MAVLINK_MSG_ID_PARAM_VALUE, &msg);
|
||||
}
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2014 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-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
|
||||
@ -32,34 +32,84 @@
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file mavlink_commands.h
|
||||
* Mavlink commands stream definition.
|
||||
* @file mavlink_parameters.h
|
||||
* Mavlink parameters manager definition.
|
||||
*
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#ifndef MAVLINK_COMMANDS_H_
|
||||
#define MAVLINK_COMMANDS_H_
|
||||
#pragma once
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_command.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
class Mavlink;
|
||||
class MavlinkCommansStream;
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include "mavlink_stream.h"
|
||||
|
||||
#include "mavlink_main.h"
|
||||
|
||||
class MavlinkCommandsStream
|
||||
class MavlinkParametersManager : public MavlinkStream
|
||||
{
|
||||
private:
|
||||
MavlinkOrbSubscription *_cmd_sub;
|
||||
struct vehicle_command_s *_cmd;
|
||||
mavlink_channel_t _channel;
|
||||
uint64_t _cmd_time;
|
||||
|
||||
public:
|
||||
MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel);
|
||||
void update(const hrt_abstime t);
|
||||
};
|
||||
const char *get_name() const
|
||||
{
|
||||
return MavlinkParametersManager::get_name_static();
|
||||
}
|
||||
|
||||
#endif /* MAVLINK_COMMANDS_H_ */
|
||||
static const char *get_name_static()
|
||||
{
|
||||
return "PARAM_VALUE";
|
||||
}
|
||||
|
||||
uint8_t get_id()
|
||||
{
|
||||
return MAVLINK_MSG_ID_PARAM_VALUE;
|
||||
}
|
||||
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink)
|
||||
{
|
||||
return new MavlinkParametersManager(mavlink);
|
||||
}
|
||||
|
||||
unsigned get_size();
|
||||
|
||||
void handle_message(const mavlink_message_t *msg);
|
||||
|
||||
/**
|
||||
* Send one parameter identified by index.
|
||||
*
|
||||
* @param index The index of the parameter to send.
|
||||
* @return zero on success, nonzero else.
|
||||
*/
|
||||
void start_send_one(int index);
|
||||
|
||||
|
||||
/**
|
||||
* Send one parameter identified by name.
|
||||
*
|
||||
* @param name The index of the parameter to send.
|
||||
* @return zero on success, nonzero else.
|
||||
*/
|
||||
int start_send_for_name(const char *name);
|
||||
|
||||
/**
|
||||
* Start sending the parameter queue.
|
||||
*
|
||||
* This function will not directly send parameters, but instead
|
||||
* activate the sending of one parameter on each call of
|
||||
* mavlink_pm_queued_send().
|
||||
* @see mavlink_pm_queued_send()
|
||||
*/
|
||||
void start_send_all();
|
||||
|
||||
private:
|
||||
int _send_all_index;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkParametersManager(MavlinkParametersManager &);
|
||||
MavlinkParametersManager& operator = (const MavlinkParametersManager &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkParametersManager(Mavlink *mavlink);
|
||||
|
||||
void send(const hrt_abstime t);
|
||||
|
||||
void send_param(param_t param);
|
||||
};
|
||||
@ -64,7 +64,7 @@ MavlinkRateLimiter::check(hrt_abstime t)
|
||||
uint64_t dt = t - _last_sent;
|
||||
|
||||
if (dt > 0 && dt >= _interval) {
|
||||
_last_sent = (t / _interval) * _interval;
|
||||
_last_sent = t;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
@ -241,7 +241,8 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
|
||||
} else {
|
||||
|
||||
if (msg->sysid == mavlink_system.sysid && msg->compid == mavlink_system.compid) {
|
||||
warnx("ignoring CMD spoofed with same SYS/COMP ID");
|
||||
warnx("ignoring CMD spoofed with same SYS/COMP (%d/%d) ID",
|
||||
mavlink_system.sysid, mavlink_system.compid);
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
@ -43,9 +43,9 @@
|
||||
#include "mavlink_stream.h"
|
||||
#include "mavlink_main.h"
|
||||
|
||||
MavlinkStream::MavlinkStream() :
|
||||
MavlinkStream::MavlinkStream(Mavlink *mavlink) :
|
||||
next(nullptr),
|
||||
_channel(MAVLINK_COMM_0),
|
||||
_mavlink(mavlink),
|
||||
_interval(1000000),
|
||||
_last_sent(0)
|
||||
{
|
||||
@ -64,15 +64,6 @@ MavlinkStream::set_interval(const unsigned int interval)
|
||||
_interval = interval;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set mavlink channel
|
||||
*/
|
||||
void
|
||||
MavlinkStream::set_channel(mavlink_channel_t channel)
|
||||
{
|
||||
_channel = channel;
|
||||
}
|
||||
|
||||
/**
|
||||
* Update subscriptions and send message if necessary
|
||||
*/
|
||||
@ -80,11 +71,21 @@ int
|
||||
MavlinkStream::update(const hrt_abstime t)
|
||||
{
|
||||
uint64_t dt = t - _last_sent;
|
||||
unsigned int interval = _interval;
|
||||
|
||||
if (dt > 0 && dt >= _interval) {
|
||||
if (!const_rate()) {
|
||||
interval /= _mavlink->get_rate_mult();
|
||||
}
|
||||
|
||||
if (dt > 0 && dt >= interval) {
|
||||
/* interval expired, send message */
|
||||
send(t);
|
||||
_last_sent = (t / _interval) * _interval;
|
||||
if (const_rate()) {
|
||||
_last_sent = (t / _interval) * _interval;
|
||||
|
||||
} else {
|
||||
_last_sent = t;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -46,31 +46,50 @@
|
||||
class Mavlink;
|
||||
class MavlinkStream;
|
||||
|
||||
#include "mavlink_main.h"
|
||||
|
||||
class MavlinkStream
|
||||
{
|
||||
|
||||
public:
|
||||
MavlinkStream *next;
|
||||
|
||||
MavlinkStream();
|
||||
MavlinkStream(Mavlink *mavlink);
|
||||
virtual ~MavlinkStream();
|
||||
|
||||
/**
|
||||
* Get the interval
|
||||
*
|
||||
* @param interval the inveral in microseconds (us) between messages
|
||||
*/
|
||||
void set_interval(const unsigned int interval);
|
||||
void set_channel(mavlink_channel_t channel);
|
||||
|
||||
/**
|
||||
* Get the interval
|
||||
*
|
||||
* @return the inveral in microseconds (us) between messages
|
||||
*/
|
||||
unsigned get_interval() { return _interval; }
|
||||
|
||||
/**
|
||||
* @return 0 if updated / sent, -1 if unchanged
|
||||
*/
|
||||
int update(const hrt_abstime t);
|
||||
static MavlinkStream *new_instance();
|
||||
static MavlinkStream *new_instance(const Mavlink *mavlink);
|
||||
static const char *get_name_static();
|
||||
virtual void subscribe(Mavlink *mavlink) = 0;
|
||||
virtual const char *get_name() const = 0;
|
||||
virtual uint8_t get_id() = 0;
|
||||
|
||||
/**
|
||||
* @return true if steam rate shouldn't be adjusted
|
||||
*/
|
||||
virtual bool const_rate() { return false; }
|
||||
|
||||
/**
|
||||
* Get maximal total messages size on update
|
||||
*/
|
||||
virtual unsigned get_size() = 0;
|
||||
|
||||
protected:
|
||||
mavlink_channel_t _channel;
|
||||
Mavlink * _mavlink;
|
||||
unsigned int _interval;
|
||||
|
||||
virtual void send(const hrt_abstime t) = 0;
|
||||
|
||||
@ -40,11 +40,11 @@ SRCS += mavlink_main.cpp \
|
||||
mavlink.c \
|
||||
mavlink_receiver.cpp \
|
||||
mavlink_mission.cpp \
|
||||
mavlink_parameters.cpp \
|
||||
mavlink_orb_subscription.cpp \
|
||||
mavlink_messages.cpp \
|
||||
mavlink_stream.cpp \
|
||||
mavlink_rate_limiter.cpp \
|
||||
mavlink_commands.cpp \
|
||||
mavlink_ftp.cpp
|
||||
|
||||
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
|
||||
|
||||
@ -312,30 +312,36 @@ Mission::set_mission_items()
|
||||
/* set previous position setpoint to current */
|
||||
set_previous_pos_setpoint();
|
||||
|
||||
/* get home distance state */
|
||||
bool home_dist_ok = check_dist_1wp();
|
||||
/* the home dist check provides user feedback, so we initialize it to this */
|
||||
bool user_feedback_done = !home_dist_ok;
|
||||
|
||||
/* try setting onboard mission item */
|
||||
if (_param_onboard_enabled.get() && read_mission_item(true, true, &_mission_item)) {
|
||||
/* if mission type changed, notify */
|
||||
if (_mission_type != MISSION_TYPE_ONBOARD) {
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: onboard mission running");
|
||||
mavlink_log_critical(_navigator->get_mavlink_fd(), "onboard mission now running");
|
||||
}
|
||||
_mission_type = MISSION_TYPE_ONBOARD;
|
||||
|
||||
/* try setting offboard mission item */
|
||||
} else if (check_dist_1wp() && read_mission_item(false, true, &_mission_item)) {
|
||||
} else if (home_dist_ok && read_mission_item(false, true, &_mission_item)) {
|
||||
/* if mission type changed, notify */
|
||||
if (_mission_type != MISSION_TYPE_OFFBOARD) {
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: offboard mission running");
|
||||
mavlink_log_critical(_navigator->get_mavlink_fd(), "offboard mission now running");
|
||||
}
|
||||
_mission_type = MISSION_TYPE_OFFBOARD;
|
||||
|
||||
} else {
|
||||
/* no mission available, switch to loiter */
|
||||
/* no mission available or mission finished, switch to loiter */
|
||||
if (_mission_type != MISSION_TYPE_NONE) {
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(),
|
||||
"#audio: mission finished");
|
||||
} else {
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(),
|
||||
"#audio: no mission available");
|
||||
mavlink_log_critical(_navigator->get_mavlink_fd(), "mission finished, loitering");
|
||||
} else if (!user_feedback_done) {
|
||||
/* only tell users that we got no mission if there has not been any
|
||||
* better, more specific feedback yet
|
||||
*/
|
||||
mavlink_log_critical(_navigator->get_mavlink_fd(), "no valid mission available");
|
||||
}
|
||||
_mission_type = MISSION_TYPE_NONE;
|
||||
|
||||
@ -395,7 +401,7 @@ Mission::set_mission_items()
|
||||
takeoff_alt = fmaxf(takeoff_alt, _navigator->get_home_position()->alt + _param_takeoff_alt.get());
|
||||
}
|
||||
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: takeoff to %.1fm above home", (double)(takeoff_alt - _navigator->get_home_position()->alt));
|
||||
mavlink_log_critical(_navigator->get_mavlink_fd(), "takeoff to %.1f meters above home", (double)(takeoff_alt - _navigator->get_home_position()->alt));
|
||||
|
||||
_mission_item.lat = _navigator->get_global_position()->lat;
|
||||
_mission_item.lon = _navigator->get_global_position()->lon;
|
||||
@ -481,7 +487,7 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s
|
||||
if (dm_read(dm_item, *mission_index_ptr, &mission_item_tmp, len) != len) {
|
||||
/* not supposed to happen unless the datamanager can't access the SD card, etc. */
|
||||
mavlink_log_critical(_navigator->get_mavlink_fd(),
|
||||
"#audio: ERROR waypoint could not be read");
|
||||
"ERROR waypoint could not be read");
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -500,7 +506,7 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s
|
||||
/* not supposed to happen unless the datamanager can't access the
|
||||
* dataman */
|
||||
mavlink_log_critical(_navigator->get_mavlink_fd(),
|
||||
"#audio: ERROR DO JUMP waypoint could not be written");
|
||||
"ERROR DO JUMP waypoint could not be written");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@ -509,8 +515,8 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s
|
||||
*mission_index_ptr = mission_item_tmp.do_jump_mission_index;
|
||||
|
||||
} else {
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(),
|
||||
"#audio: DO JUMP repetitions completed");
|
||||
mavlink_log_critical(_navigator->get_mavlink_fd(),
|
||||
"DO JUMP repetitions completed");
|
||||
/* no more DO_JUMPS, therefore just try to continue with next mission item */
|
||||
(*mission_index_ptr)++;
|
||||
}
|
||||
@ -524,7 +530,7 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s
|
||||
|
||||
/* we have given up, we don't want to cycle forever */
|
||||
mavlink_log_critical(_navigator->get_mavlink_fd(),
|
||||
"#audio: ERROR DO JUMP is cycling, giving up");
|
||||
"ERROR DO JUMP is cycling, giving up");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
@ -83,6 +83,18 @@ PARAM_DEFINE_INT32(CBRK_RATE_CTRL, 0);
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CBRK_IO_SAFETY, 0);
|
||||
|
||||
/**
|
||||
* Circuit breaker for airspeed sensor
|
||||
*
|
||||
* Setting this parameter to 162128 will disable the check for an airspeed sensor.
|
||||
* WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
|
||||
*
|
||||
* @min 0
|
||||
* @max 162128
|
||||
* @group Circuit Breaker
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CBRK_AIRSPD_CHK, 0);
|
||||
|
||||
bool circuit_breaker_enabled(const char* breaker, int32_t magic)
|
||||
{
|
||||
int32_t val;
|
||||
|
||||
@ -52,6 +52,7 @@
|
||||
#define CBRK_SUPPLY_CHK_KEY 894281
|
||||
#define CBRK_RATE_CTRL_KEY 140253
|
||||
#define CBRK_IO_SAFETY_KEY 22027
|
||||
#define CBRK_AIRSPD_CHK_KEY 162128
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
|
||||
@ -70,8 +70,8 @@ struct vehicle_global_position_s {
|
||||
float vel_e; /**< Ground east velocity, m/s */
|
||||
float vel_d; /**< Ground downside velocity, m/s */
|
||||
float yaw; /**< Yaw in radians -PI..+PI. */
|
||||
float eph;
|
||||
float epv;
|
||||
float eph; /**< Standard deviation of position estimate horizontally */
|
||||
float epv; /**< Standard deviation of position vertically */
|
||||
};
|
||||
|
||||
/**
|
||||
|
||||
@ -232,6 +232,7 @@ struct vehicle_status_s {
|
||||
uint16_t errors_count4;
|
||||
|
||||
bool circuit_breaker_engaged_power_check;
|
||||
bool circuit_breaker_engaged_airspd_check;
|
||||
};
|
||||
|
||||
/**
|
||||
|
||||
@ -65,10 +65,6 @@ override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_STM32_NUTTX -DUAVCAN_STM32_NUM
|
||||
|
||||
#
|
||||
# Invoke DSDL compiler
|
||||
# TODO: Add make target for this, or invoke dsdlc manually.
|
||||
# The second option assumes that the generated headers shall be saved
|
||||
# under the version control, which may be undesirable.
|
||||
# The first option requires any Python and the Python Mako library for the sources to be built.
|
||||
#
|
||||
$(info $(shell $(LIBUAVCAN_DSDLC) $(UAVCAN_DSDL_DIR)))
|
||||
INCLUDE_DIRS += dsdlc_generated
|
||||
|
||||
@ -39,6 +39,8 @@
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/mixer/mixer.h>
|
||||
#include <systemlib/board_serial.h>
|
||||
#include <version/version.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <arch/chip/chip.h>
|
||||
|
||||
@ -173,6 +175,44 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate)
|
||||
return OK;
|
||||
}
|
||||
|
||||
void UavcanNode::fill_node_info()
|
||||
{
|
||||
/* software version */
|
||||
uavcan::protocol::SoftwareVersion swver;
|
||||
|
||||
// Extracting the last 8 hex digits of FW_GIT and converting them to int
|
||||
const unsigned fw_git_len = std::strlen(FW_GIT);
|
||||
if (fw_git_len >= 8) {
|
||||
char fw_git_short[9] = {};
|
||||
std::memmove(fw_git_short, FW_GIT + fw_git_len - 8, 8);
|
||||
assert(fw_git_short[8] == '\0');
|
||||
char *end = nullptr;
|
||||
swver.vcs_commit = std::strtol(fw_git_short, &end, 16);
|
||||
swver.optional_field_mask |= swver.OPTIONAL_FIELD_MASK_VCS_COMMIT;
|
||||
}
|
||||
|
||||
warnx("SW version vcs_commit: 0x%08x", unsigned(swver.vcs_commit));
|
||||
|
||||
_node.setSoftwareVersion(swver);
|
||||
|
||||
/* hardware version */
|
||||
uavcan::protocol::HardwareVersion hwver;
|
||||
|
||||
if (!std::strncmp(HW_ARCH, "PX4FMU_V1", 9)) {
|
||||
hwver.major = 1;
|
||||
} else if (!std::strncmp(HW_ARCH, "PX4FMU_V2", 9)) {
|
||||
hwver.major = 2;
|
||||
} else {
|
||||
; // All other values of HW_ARCH resolve to zero
|
||||
}
|
||||
|
||||
uint8_t udid[12] = {}; // Someone seems to love magic numbers
|
||||
get_board_serial(udid);
|
||||
uavcan::copy(udid, udid + sizeof(udid), hwver.unique_id.begin());
|
||||
|
||||
_node.setHardwareVersion(hwver);
|
||||
}
|
||||
|
||||
int UavcanNode::init(uavcan::NodeID node_id)
|
||||
{
|
||||
int ret = -1;
|
||||
@ -183,6 +223,13 @@ int UavcanNode::init(uavcan::NodeID node_id)
|
||||
if (ret != OK)
|
||||
return ret;
|
||||
|
||||
_node.setName("org.pixhawk.pixhawk");
|
||||
|
||||
_node.setNodeID(node_id);
|
||||
|
||||
fill_node_info();
|
||||
|
||||
/* initializing the bridges UAVCAN <--> uORB */
|
||||
ret = _esc_controller.init();
|
||||
if (ret < 0)
|
||||
return ret;
|
||||
@ -191,20 +238,6 @@ int UavcanNode::init(uavcan::NodeID node_id)
|
||||
if (ret < 0)
|
||||
return ret;
|
||||
|
||||
uavcan::protocol::SoftwareVersion swver;
|
||||
swver.major = 12; // TODO fill version info
|
||||
swver.minor = 34;
|
||||
_node.setSoftwareVersion(swver);
|
||||
|
||||
uavcan::protocol::HardwareVersion hwver;
|
||||
hwver.major = 42; // TODO fill version info
|
||||
hwver.minor = 42;
|
||||
_node.setHardwareVersion(hwver);
|
||||
|
||||
_node.setName("org.pixhawk"); // Huh?
|
||||
|
||||
_node.setNodeID(node_id);
|
||||
|
||||
return _node.start();
|
||||
}
|
||||
|
||||
|
||||
@ -94,6 +94,7 @@ public:
|
||||
static UavcanNode* instance() { return _instance; }
|
||||
|
||||
private:
|
||||
void fill_node_info();
|
||||
int init(uavcan::NodeID node_id);
|
||||
void node_spin_once();
|
||||
int run();
|
||||
|
||||
@ -38,4 +38,4 @@
|
||||
MODULE_COMMAND = nshterm
|
||||
SRCS = nshterm.c
|
||||
|
||||
MODULE_STACKSIZE = 1200
|
||||
MODULE_STACKSIZE = 1400
|
||||
|
||||
2
uavcan
2
uavcan
@ -1 +1 @@
|
||||
Subproject commit d84fc8a84678d93f97f93b240c81472797ca5889
|
||||
Subproject commit 6980ee824074aa2f7a62221bf6040ee411119520
|
||||
Loading…
x
Reference in New Issue
Block a user