mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-22 06:14:14 +08:00
Merged
This commit is contained in:
+217
-193
File diff suppressed because it is too large
Load Diff
@@ -99,7 +99,10 @@ ORB_DECLARE(sensor_mag);
|
||||
/** copy the mag scaling constants to the structure pointed to by (arg) */
|
||||
#define MAGIOCGSCALE _MAGIOC(3)
|
||||
|
||||
/** set the measurement range to handle (at least) arg Gauss */
|
||||
#define MAGIOCSRANGE _MAGIOC(4)
|
||||
|
||||
/** perform self-calibration, update scale factors to canonical units */
|
||||
#define MAGIOCCALIBRATE _MAGIOC(4)
|
||||
#define MAGIOCCALIBRATE _MAGIOC(5)
|
||||
|
||||
#endif /* _DRV_MAG_H */
|
||||
|
||||
@@ -37,6 +37,6 @@
|
||||
|
||||
APPNAME = hmc5883
|
||||
PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||
STACKSIZE = 2048
|
||||
STACKSIZE = 4096
|
||||
|
||||
include $(APPDIR)/mk/app.mk
|
||||
|
||||
@@ -175,6 +175,24 @@ private:
|
||||
*/
|
||||
void stop();
|
||||
|
||||
/**
|
||||
* Perform the on-sensor scale calibration routine.
|
||||
*
|
||||
* @note The sensor will continue to provide measurements, these
|
||||
* will however reflect the uncalibrated sensor state until
|
||||
* the calibration routine has been completed.
|
||||
*
|
||||
* @param enable set to 1 to enable self-test strap, 0 to disable
|
||||
*/
|
||||
int calibrate(unsigned enable);
|
||||
|
||||
/**
|
||||
* Set the sensor range.
|
||||
*
|
||||
* Sets the internal range to handle at least the argument in Gauss.
|
||||
*/
|
||||
int set_range(unsigned range);
|
||||
|
||||
/**
|
||||
* Perform a poll cycle; collect from the previous measurement
|
||||
* and start a new one.
|
||||
@@ -255,8 +273,8 @@ HMC5883::HMC5883(int bus) :
|
||||
_oldest_report(0),
|
||||
_reports(nullptr),
|
||||
_mag_topic(-1),
|
||||
_range_scale(1.0f / 1090.0f), /* default range scale from counts to gauss */
|
||||
_range_ga(0.88f),
|
||||
_range_scale(0), /* default range scale from counts to gauss */
|
||||
_range_ga(1.3f),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "hmc5883_read")),
|
||||
_comms_errors(perf_alloc(PC_COUNT, "hmc5883_comms_errors")),
|
||||
_buffer_overflows(perf_alloc(PC_COUNT, "hmc5883_buffer_overflows"))
|
||||
@@ -308,11 +326,71 @@ HMC5883::init()
|
||||
if (_mag_topic < 0)
|
||||
debug("failed to create sensor_mag object");
|
||||
|
||||
/* set range */
|
||||
set_range(_range_ga);
|
||||
|
||||
ret = OK;
|
||||
out:
|
||||
return ret;
|
||||
}
|
||||
|
||||
int HMC5883::set_range(unsigned range)
|
||||
{
|
||||
uint8_t range_bits;
|
||||
|
||||
if (range < 1) {
|
||||
range_bits = 0x00;
|
||||
_range_scale = 1.0f / 1370.0f;
|
||||
_range_ga = 0.88f;
|
||||
} else if (range <= 1) {
|
||||
range_bits = 0x01;
|
||||
_range_scale = 1.0f / 1090.0f;
|
||||
_range_ga = 1.3f;
|
||||
} else if (range <= 2) {
|
||||
range_bits = 0x02;
|
||||
_range_scale = 1.0f / 820.0f;
|
||||
_range_ga = 1.9f;
|
||||
} else if (range <= 3) {
|
||||
range_bits = 0x03;
|
||||
_range_scale = 1.0f / 660.0f;
|
||||
_range_ga = 2.5f;
|
||||
} else if (range <= 4) {
|
||||
range_bits = 0x04;
|
||||
_range_scale = 1.0f / 440.0f;
|
||||
_range_ga = 4.0f;
|
||||
} else if (range <= 4.7f) {
|
||||
range_bits = 0x05;
|
||||
_range_scale = 1.0f / 390.0f;
|
||||
_range_ga = 4.7f;
|
||||
} else if (range <= 5.6f) {
|
||||
range_bits = 0x06;
|
||||
_range_scale = 1.0f / 330.0f;
|
||||
_range_ga = 5.6f;
|
||||
} else {
|
||||
range_bits = 0x07;
|
||||
_range_scale = 1.0f / 230.0f;
|
||||
_range_ga = 8.1f;
|
||||
}
|
||||
|
||||
int ret;
|
||||
|
||||
/*
|
||||
* Send the command to set the range
|
||||
*/
|
||||
ret = write_reg(ADDR_CONF_B, (range_bits << 5));
|
||||
|
||||
if (OK != ret)
|
||||
perf_count(_comms_errors);
|
||||
|
||||
uint8_t range_bits_in;
|
||||
ret = read_reg(ADDR_CONF_B, range_bits_in);
|
||||
|
||||
if (OK != ret)
|
||||
perf_count(_comms_errors);
|
||||
|
||||
return !(range_bits_in == (range_bits << 5));
|
||||
}
|
||||
|
||||
int
|
||||
HMC5883::probe()
|
||||
{
|
||||
@@ -495,6 +573,9 @@ HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
/* not supported, always 1 sample per poll */
|
||||
return -EINVAL;
|
||||
|
||||
case MAGIOCSRANGE:
|
||||
return set_range(arg);
|
||||
|
||||
case MAGIOCSLOWPASS:
|
||||
/* not supported, no internal filtering */
|
||||
return -EINVAL;
|
||||
@@ -510,8 +591,7 @@ HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
return 0;
|
||||
|
||||
case MAGIOCCALIBRATE:
|
||||
/* XXX perform auto-calibration */
|
||||
return -EINVAL;
|
||||
return calibrate(arg);
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
@@ -718,6 +798,29 @@ out:
|
||||
return ret;
|
||||
}
|
||||
|
||||
int HMC5883::calibrate(unsigned enable)
|
||||
{
|
||||
int ret;
|
||||
/* arm the excitement strap */
|
||||
uint8_t conf_reg;
|
||||
ret = read_reg(ADDR_CONF_A, conf_reg);
|
||||
if (OK != ret)
|
||||
perf_count(_comms_errors);
|
||||
if (enable) {
|
||||
conf_reg |= 0x01;
|
||||
} else {
|
||||
conf_reg &= ~0x03;
|
||||
}
|
||||
ret = write_reg(ADDR_CONF_A, conf_reg);
|
||||
if (OK != ret)
|
||||
perf_count(_comms_errors);
|
||||
|
||||
uint8_t conf_reg_ret;
|
||||
read_reg(ADDR_CONF_A, conf_reg_ret);
|
||||
|
||||
return !(conf_reg == conf_reg_ret);
|
||||
}
|
||||
|
||||
int
|
||||
HMC5883::write_reg(uint8_t reg, uint8_t val)
|
||||
{
|
||||
@@ -775,6 +878,7 @@ void start();
|
||||
void test();
|
||||
void reset();
|
||||
void info();
|
||||
int calibrate();
|
||||
|
||||
/**
|
||||
* Start the driver.
|
||||
@@ -872,6 +976,273 @@ test()
|
||||
errx(0, "PASS");
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Automatic scale calibration.
|
||||
*
|
||||
* Basic idea:
|
||||
*
|
||||
* output = (ext field +- 1.1 Ga self-test) * scale factor
|
||||
*
|
||||
* and consequently:
|
||||
*
|
||||
* 1.1 Ga = (excited - normal) * scale factor
|
||||
* scale factor = (excited - normal) / 1.1 Ga
|
||||
*
|
||||
* sxy = (excited - normal) / 766 | for conf reg. B set to 0x60 / Gain = 3
|
||||
* sz = (excited - normal) / 713 | for conf reg. B set to 0x60 / Gain = 3
|
||||
*
|
||||
* By subtracting the non-excited measurement the pure 1.1 Ga reading
|
||||
* can be extracted and the sensitivity of all axes can be matched.
|
||||
*
|
||||
* SELF TEST OPERATION
|
||||
* To check the HMC5883L for proper operation, a self test feature in incorporated
|
||||
* in which the sensor offset straps are excited to create a nominal field strength
|
||||
* (bias field) to be measured. To implement self test, the least significant bits
|
||||
* (MS1 and MS0) of configuration register A are changed from 00 to 01 (positive bias)
|
||||
* or 10 (negetive bias), e.g. 0x11 or 0x12.
|
||||
* Then, by placing the mode register into single-measurement mode (0x01),
|
||||
* two data acquisition cycles will be made on each magnetic vector.
|
||||
* The first acquisition will be a set pulse followed shortly by measurement
|
||||
* data of the external field. The second acquisition will have the offset strap
|
||||
* excited (about 10 mA) in the positive bias mode for X, Y, and Z axes to create
|
||||
* about a ±1.1 gauss self test field plus the external field. The first acquisition
|
||||
* values will be subtracted from the second acquisition, and the net measurement
|
||||
* will be placed into the data output registers.
|
||||
* Since self test adds ~1.1 Gauss additional field to the existing field strength,
|
||||
* using a reduced gain setting prevents sensor from being saturated and data registers
|
||||
* overflowed. For example, if the configuration register B is set to 0x60 (Gain=3),
|
||||
* values around +766 LSB (1.16 Ga * 660 LSB/Ga) will be placed in the X and Y data
|
||||
* output registers and around +713 (1.08 Ga * 660 LSB/Ga) will be placed in Z data
|
||||
* output register. To leave the self test mode, change MS1 and MS0 bit of the
|
||||
* configuration register A back to 00 (Normal Measurement Mode), e.g. 0x10.
|
||||
* Using the self test method described above, the user can scale sensor
|
||||
*/
|
||||
int calibrate()
|
||||
{
|
||||
|
||||
struct mag_report report;
|
||||
ssize_t sz;
|
||||
int ret;
|
||||
|
||||
int fd = open(MAG_DEVICE_PATH, O_RDONLY);
|
||||
if (fd < 0)
|
||||
err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", MAG_DEVICE_PATH);
|
||||
|
||||
/* do a simple demand read */
|
||||
sz = read(fd, &report, sizeof(report));
|
||||
if (sz != sizeof(report))
|
||||
err(1, "immediate read failed");
|
||||
|
||||
warnx("single read");
|
||||
warnx("measurement: %.6f %.6f %.6f", (double)report.x, (double)report.y, (double)report.z);
|
||||
warnx("time: %lld", report.timestamp);
|
||||
|
||||
/* set the queue depth to 10 */
|
||||
if (OK != ioctl(fd, SENSORIOCSQUEUEDEPTH, 10))
|
||||
errx(1, "failed to set queue depth");
|
||||
|
||||
/* start the sensor polling at 10 Hz */
|
||||
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 10))
|
||||
errx(1, "failed to set 2Hz poll rate");
|
||||
|
||||
/* Set to 2.5 Gauss */
|
||||
if (OK != ioctl(fd, MAGIOCSRANGE, 2)) {
|
||||
warnx("failed to set 2.5 Ga range");
|
||||
}
|
||||
|
||||
if (OK != ioctl(fd, MAGIOCCALIBRATE, 1)) {
|
||||
warnx("failed to enable sensor calibration mode");
|
||||
}
|
||||
|
||||
struct mag_scale mscale_null = {
|
||||
0.0f,
|
||||
1.0f,
|
||||
0.0f,
|
||||
1.0f,
|
||||
0.0f,
|
||||
1.0f,
|
||||
};
|
||||
|
||||
if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null)) {
|
||||
warn("WARNING: failed to set null scale / offsets for mag");
|
||||
}
|
||||
|
||||
float avg_excited[3];
|
||||
unsigned i;
|
||||
|
||||
/* read the sensor 10x and report each value */
|
||||
for (i = 0; i < 10; i++) {
|
||||
struct pollfd fds;
|
||||
|
||||
/* wait for data to be ready */
|
||||
fds.fd = fd;
|
||||
fds.events = POLLIN;
|
||||
ret = poll(&fds, 1, 2000);
|
||||
|
||||
if (ret != 1)
|
||||
errx(1, "timed out waiting for sensor data");
|
||||
|
||||
/* now go get it */
|
||||
sz = read(fd, &report, sizeof(report));
|
||||
|
||||
if (sz != sizeof(report)) {
|
||||
err(1, "periodic read failed");
|
||||
} else {
|
||||
avg_excited[0] += report.x;
|
||||
avg_excited[1] += report.y;
|
||||
avg_excited[2] += report.z;
|
||||
}
|
||||
|
||||
warnx("periodic read %u", i);
|
||||
warnx("measurement: %.6f %.6f %.6f", (double)report.x, (double)report.y, (double)report.z);
|
||||
warnx("time: %lld", report.timestamp);
|
||||
}
|
||||
|
||||
// warnx("starting calibration");
|
||||
|
||||
// struct mag_report report;
|
||||
// ssize_t sz;
|
||||
// int ret;
|
||||
|
||||
// int fd = open(MAG_DEVICE_PATH, O_RDONLY);
|
||||
// if (fd < 0)
|
||||
// err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", MAG_DEVICE_PATH);
|
||||
|
||||
// /* do a simple demand read */
|
||||
// sz = read(fd, &report, sizeof(report));
|
||||
// if (sz != sizeof(report))
|
||||
// err(1, "immediate read failed");
|
||||
|
||||
// warnx("single read");
|
||||
// warnx("measurement: %.6f %.6f %.6f", (double)report.x, (double)report.y, (double)report.z);
|
||||
// warnx("time: %lld", report.timestamp);
|
||||
|
||||
// /* get scaling, set to zero */
|
||||
// struct mag_scale mscale_previous;
|
||||
|
||||
// if (OK != ioctl(fd, MAGIOCGSCALE, (long unsigned int)&mscale_previous)) {
|
||||
// warn("WARNING: failed to get scale / offsets for mag");
|
||||
// }
|
||||
|
||||
// struct mag_scale mscale_null = {
|
||||
// 0.0f,
|
||||
// 1.0f,
|
||||
// 0.0f,
|
||||
// 1.0f,
|
||||
// 0.0f,
|
||||
// 1.0f,
|
||||
// };
|
||||
|
||||
// if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null)) {
|
||||
// warn("WARNING: failed to set null scale / offsets for mag");
|
||||
// }
|
||||
|
||||
// warnx("sensor ready");
|
||||
|
||||
// float avg_excited[3] = {0.0f, 0.0f, 0.0f};
|
||||
|
||||
// if (OK != ioctl(fd, MAGIOCCALIBRATE, 1)) {
|
||||
// warnx("failed to enable sensor calibration mode");
|
||||
// }
|
||||
|
||||
// /* Set to 2.5 Gauss */
|
||||
// if (OK != ioctl(fd, MAGIOCSRANGE, 2)) {
|
||||
// warnx("failed to set 2.5 Ga range");
|
||||
// }
|
||||
|
||||
// /* set the queue depth to 10 */
|
||||
// if (OK != ioctl(fd, SENSORIOCSQUEUEDEPTH, 10)) {
|
||||
// warnx("failed to set queue depth");
|
||||
// return 1;
|
||||
// } else {
|
||||
// warnx("set queue depth");
|
||||
// }
|
||||
|
||||
// /* start the sensor polling at 100Hz */
|
||||
// if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 100)) {
|
||||
// warnx("failed to set 100 Hz poll rate");
|
||||
// return 1;
|
||||
// } else {
|
||||
// warnx("set 100 Hz poll rate");
|
||||
// }
|
||||
|
||||
// int i;
|
||||
// for (i = 0; i < 10; i++) {
|
||||
// struct pollfd fds;
|
||||
|
||||
// (void) ioctl(fd, MAGIOCCALIBRATE, 1);
|
||||
|
||||
// /* wait for data to be ready */
|
||||
// fds.fd = fd;
|
||||
// fds.events = POLLIN;
|
||||
// ret = poll(&fds, 1, 2000);
|
||||
|
||||
// if (ret != 1) {
|
||||
// warnx("timed out waiting for sensor data");
|
||||
// return 1;
|
||||
// }
|
||||
|
||||
// /* now go get it */
|
||||
// sz = read(fd, &report, sizeof(report));
|
||||
|
||||
// if (sz != sizeof(report)) {
|
||||
// warn("periodic read failed");
|
||||
// return 1;
|
||||
// } else {
|
||||
// avg_excited[0] += report.x;
|
||||
// avg_excited[1] += report.y;
|
||||
// avg_excited[2] += report.z;
|
||||
// }
|
||||
// warnx("excited read %u", i);
|
||||
// warnx("measurement: %.6f %.6f %.6f", (double)report.x, (double)report.y, (double)report.z);
|
||||
// warnx("time: %lld", report.timestamp);
|
||||
|
||||
// }
|
||||
|
||||
avg_excited[0] /= i;
|
||||
avg_excited[1] /= i;
|
||||
avg_excited[2] /= i;
|
||||
|
||||
warnx("periodic excited reads %u", i);
|
||||
warnx("measurement avg: %.6f %.6f %.6f", (double)avg_excited[0], (double)avg_excited[1], (double)avg_excited[2]);
|
||||
|
||||
/* Set to 1.1 Gauss and end calibration */
|
||||
ret = ioctl(fd, MAGIOCCALIBRATE, 0);
|
||||
ret = ioctl(fd, MAGIOCSRANGE, 1);
|
||||
|
||||
float scaling[3];
|
||||
|
||||
/* calculate axis scaling */
|
||||
scaling[0] = 1.16f / avg_excited[0];
|
||||
/* second axis inverted */
|
||||
scaling[1] = 1.16f / -avg_excited[1];
|
||||
scaling[2] = 1.08f / avg_excited[2];
|
||||
|
||||
warnx("axes scaling: %.6f %.6f %.6f", (double)scaling[0], (double)scaling[1], (double)scaling[2]);
|
||||
|
||||
/* set back to normal mode */
|
||||
/* Set to 1.1 Gauss */
|
||||
if (OK != ioctl(fd, MAGIOCSRANGE, 1)) {
|
||||
warnx("failed to set 1.1 Ga range");
|
||||
}
|
||||
|
||||
if (OK != ioctl(fd, MAGIOCCALIBRATE, 0)) {
|
||||
warnx("failed to disable sensor calibration mode");
|
||||
}
|
||||
|
||||
/* set scaling in device */
|
||||
// mscale_previous.x_scale = scaling[0];
|
||||
// mscale_previous.y_scale = scaling[1];
|
||||
// mscale_previous.z_scale = scaling[2];
|
||||
|
||||
// if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_previous)) {
|
||||
// warn("WARNING: failed to set new scale / offsets for mag");
|
||||
// }
|
||||
|
||||
errx(0, "PASS");
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the driver.
|
||||
*/
|
||||
@@ -930,8 +1301,19 @@ hmc5883_main(int argc, char *argv[])
|
||||
/*
|
||||
* Print driver information.
|
||||
*/
|
||||
if (!strcmp(argv[1], "info"))
|
||||
if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status"))
|
||||
hmc5883::info();
|
||||
|
||||
errx(1, "unrecognised command, try 'start', 'test', 'reset' or 'info'");
|
||||
/*
|
||||
* Autocalibrate the scaling
|
||||
*/
|
||||
if (!strcmp(argv[1], "calibrate")) {
|
||||
if (hmc5883::calibrate() == 0) {
|
||||
errx(0, "calibration successful");
|
||||
} else {
|
||||
errx(1, "calibration failed");
|
||||
}
|
||||
}
|
||||
|
||||
errx(1, "unrecognized command, try 'start', 'test', 'reset' 'calibrate' or 'info'");
|
||||
}
|
||||
|
||||
@@ -864,5 +864,5 @@ l3gd20_main(int argc, char *argv[])
|
||||
if (!strcmp(argv[1], "info"))
|
||||
l3gd20::info();
|
||||
|
||||
errx(1, "unrecognised command, try 'start', 'test', 'reset' or 'info'");
|
||||
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
|
||||
}
|
||||
|
||||
+149
-1348
File diff suppressed because it is too large
Load Diff
@@ -62,28 +62,12 @@
|
||||
*/
|
||||
extern mavlink_system_t mavlink_system;
|
||||
|
||||
|
||||
mqd_t gps_queue;
|
||||
int uart;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Send multiple chars (uint8_t) over a comm channel
|
||||
*
|
||||
* @param chan MAVLink channel to use, usually MAVLINK_COMM_0 = UART0
|
||||
* @param ch Character to send
|
||||
*/
|
||||
static inline void mavlink_send_uart_bytes(mavlink_channel_t chan, uint8_t *ch, uint16_t length)
|
||||
{
|
||||
ssize_t ret;
|
||||
|
||||
if (chan == MAVLINK_COMM_0) {
|
||||
ret = write(uart, ch, (size_t)(sizeof(uint8_t) * length));
|
||||
|
||||
if (ret != length) {
|
||||
printf("[mavlink] Error: Written %u instead of %u\n", ret, length);
|
||||
}
|
||||
}
|
||||
}
|
||||
extern void mavlink_send_uart_bytes(mavlink_channel_t chan, uint8_t *ch, int length);
|
||||
|
||||
#endif /* MAVLINK_BRIDGE_HEADER_H */
|
||||
|
||||
@@ -0,0 +1,57 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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_hil.h
|
||||
* Hardware-in-the-loop simulation support.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
extern bool mavlink_hil_enabled;
|
||||
|
||||
extern struct vehicle_global_position_s hil_global_pos;
|
||||
extern struct vehicle_attitude_s hil_attitude;
|
||||
extern orb_advert_t pub_hil_global_pos;
|
||||
extern orb_advert_t pub_hil_attitude;
|
||||
|
||||
/**
|
||||
* Enable / disable Hardware in the Loop simulation mode.
|
||||
*
|
||||
* @param hil_enabled The new HIL enable/disable state.
|
||||
* @return OK if the HIL state changed, ERROR if the
|
||||
* requested change could not be made or was
|
||||
* redundant.
|
||||
*/
|
||||
extern int set_hil_on_off(bool hil_enabled);
|
||||
@@ -1,7 +1,7 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -35,6 +35,8 @@
|
||||
/**
|
||||
* @file mavlink_parameters.c
|
||||
* MAVLink parameter protocol implementation (BSD-relicensed).
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#include "mavlink_parameters.h"
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -35,6 +35,8 @@
|
||||
/**
|
||||
* @file mavlink_parameters.h
|
||||
* MAVLink parameter protocol definitions (BSD-relicensed).
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
/* This assumes you have the mavlink headers on your include path
|
||||
|
||||
@@ -0,0 +1,495 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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_receiver.c
|
||||
* MAVLink protocol message receive and dispatch
|
||||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <pthread.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <mqueue.h>
|
||||
#include <string.h>
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include <v1.0/common/mavlink.h>
|
||||
#include <arch/board/up_hrt.h>
|
||||
#include <time.h>
|
||||
#include <float.h>
|
||||
#include <unistd.h>
|
||||
#include <nuttx/sched.h>
|
||||
#include <sys/prctl.h>
|
||||
#include <termios.h>
|
||||
#include <errno.h>
|
||||
#include <stdlib.h>
|
||||
#include <poll.h>
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
#include "waypoints.h"
|
||||
#include "mavlink_log.h"
|
||||
#include "orb_topics.h"
|
||||
#include "missionlib.h"
|
||||
#include "mavlink_hil.h"
|
||||
#include "mavlink_parameters.h"
|
||||
#include "util.h"
|
||||
|
||||
/* XXX should be in a header somewhere */
|
||||
pthread_t receive_start(int uart);
|
||||
|
||||
static void handle_message(mavlink_message_t *msg);
|
||||
static void *receive_thread(void *arg);
|
||||
|
||||
static mavlink_status_t status;
|
||||
static struct vehicle_vicon_position_s vicon_position;
|
||||
static struct vehicle_command_s vcmd;
|
||||
static struct offboard_control_setpoint_s offboard_control_sp;
|
||||
|
||||
struct vehicle_global_position_s hil_global_pos;
|
||||
struct vehicle_attitude_s hil_attitude;
|
||||
orb_advert_t pub_hil_global_pos = -1;
|
||||
orb_advert_t pub_hil_attitude = -1;
|
||||
|
||||
static orb_advert_t cmd_pub = -1;
|
||||
static orb_advert_t flow_pub = -1;
|
||||
|
||||
static orb_advert_t offboard_control_sp_pub = -1;
|
||||
static orb_advert_t vicon_position_pub = -1;
|
||||
|
||||
static void
|
||||
handle_message(mavlink_message_t *msg)
|
||||
{
|
||||
if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
|
||||
|
||||
mavlink_command_long_t cmd_mavlink;
|
||||
mavlink_msg_command_long_decode(msg, &cmd_mavlink);
|
||||
|
||||
if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid)
|
||||
|| (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
|
||||
//check for MAVLINK terminate command
|
||||
if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
|
||||
/* This is the link shutdown command, terminate mavlink */
|
||||
printf("[mavlink] Terminating .. \n");
|
||||
fflush(stdout);
|
||||
usleep(50000);
|
||||
|
||||
/* terminate other threads and this thread */
|
||||
thread_should_exit = true;
|
||||
|
||||
} else {
|
||||
|
||||
/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
|
||||
vcmd.param1 = cmd_mavlink.param1;
|
||||
vcmd.param2 = cmd_mavlink.param2;
|
||||
vcmd.param3 = cmd_mavlink.param3;
|
||||
vcmd.param4 = cmd_mavlink.param4;
|
||||
vcmd.param5 = cmd_mavlink.param5;
|
||||
vcmd.param6 = cmd_mavlink.param6;
|
||||
vcmd.param7 = cmd_mavlink.param7;
|
||||
vcmd.command = cmd_mavlink.command;
|
||||
vcmd.target_system = cmd_mavlink.target_system;
|
||||
vcmd.target_component = cmd_mavlink.target_component;
|
||||
vcmd.source_system = msg->sysid;
|
||||
vcmd.source_component = msg->compid;
|
||||
vcmd.confirmation = cmd_mavlink.confirmation;
|
||||
|
||||
/* check if topic is advertised */
|
||||
if (cmd_pub <= 0) {
|
||||
cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
|
||||
}
|
||||
/* publish */
|
||||
orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_OPTICAL_FLOW) {
|
||||
mavlink_optical_flow_t flow;
|
||||
mavlink_msg_optical_flow_decode(msg, &flow);
|
||||
|
||||
struct optical_flow_s f;
|
||||
|
||||
f.timestamp = flow.time_usec;
|
||||
f.flow_raw_x = flow.flow_x;
|
||||
f.flow_raw_y = flow.flow_y;
|
||||
f.flow_comp_x_m = flow.flow_comp_m_x;
|
||||
f.flow_comp_y_m = flow.flow_comp_m_y;
|
||||
f.ground_distance_m = flow.ground_distance;
|
||||
f.quality = flow.quality;
|
||||
f.sensor_id = flow.sensor_id;
|
||||
|
||||
/* check if topic is advertised */
|
||||
if (flow_pub <= 0) {
|
||||
flow_pub = orb_advertise(ORB_ID(optical_flow), &f);
|
||||
} else {
|
||||
/* publish */
|
||||
orb_publish(ORB_ID(optical_flow), flow_pub, &f);
|
||||
}
|
||||
}
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_SET_MODE) {
|
||||
/* Set mode on request */
|
||||
mavlink_set_mode_t new_mode;
|
||||
mavlink_msg_set_mode_decode(msg, &new_mode);
|
||||
|
||||
/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
|
||||
vcmd.param1 = new_mode.base_mode;
|
||||
vcmd.param2 = new_mode.custom_mode;
|
||||
vcmd.param3 = 0;
|
||||
vcmd.param4 = 0;
|
||||
vcmd.param5 = 0;
|
||||
vcmd.param6 = 0;
|
||||
vcmd.param7 = 0;
|
||||
vcmd.command = MAV_CMD_DO_SET_MODE;
|
||||
vcmd.target_system = new_mode.target_system;
|
||||
vcmd.target_component = MAV_COMP_ID_ALL;
|
||||
vcmd.source_system = msg->sysid;
|
||||
vcmd.source_component = msg->compid;
|
||||
vcmd.confirmation = 1;
|
||||
|
||||
/* check if topic is advertised */
|
||||
if (cmd_pub <= 0) {
|
||||
cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
|
||||
} else {
|
||||
/* create command */
|
||||
orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
|
||||
}
|
||||
}
|
||||
|
||||
/* Handle Vicon position estimates */
|
||||
if (msg->msgid == MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE) {
|
||||
mavlink_vicon_position_estimate_t pos;
|
||||
mavlink_msg_vicon_position_estimate_decode(msg, &pos);
|
||||
|
||||
vicon_position.x = pos.x;
|
||||
vicon_position.y = pos.y;
|
||||
vicon_position.z = pos.z;
|
||||
|
||||
if (vicon_position_pub <= 0) {
|
||||
vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position);
|
||||
} else {
|
||||
orb_publish(ORB_ID(vehicle_vicon_position), vicon_position_pub, &vicon_position);
|
||||
}
|
||||
}
|
||||
|
||||
/* Handle quadrotor motor setpoints */
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST) {
|
||||
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint;
|
||||
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint);
|
||||
//printf("got message\n");
|
||||
//printf("got MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT target_system=%u, sysid = %u\n", mavlink_system.sysid, quad_motors_setpoint.mode);
|
||||
|
||||
if (mavlink_system.sysid < 4) {
|
||||
/*
|
||||
* rate control mode - defined by MAVLink
|
||||
*/
|
||||
|
||||
uint8_t ml_mode = 0;
|
||||
bool ml_armed = false;
|
||||
|
||||
// if (quad_motors_setpoint.mode & MAVLINK_OFFBOARD_CONTROL_FLAG_ARMED) {
|
||||
// ml_armed = true;
|
||||
// }
|
||||
|
||||
switch (quad_motors_setpoint.mode) {
|
||||
case 0:
|
||||
ml_armed = false;
|
||||
|
||||
break;
|
||||
case 1:
|
||||
|
||||
ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
|
||||
ml_armed = true;
|
||||
|
||||
break;
|
||||
case 2:
|
||||
|
||||
|
||||
ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
|
||||
ml_armed = true;
|
||||
|
||||
break;
|
||||
case 3:
|
||||
ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
|
||||
break;
|
||||
case 4:
|
||||
ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
|
||||
break;
|
||||
}
|
||||
|
||||
offboard_control_sp.p1 = quad_motors_setpoint.roll[mavlink_system.sysid] / (float)INT16_MAX;
|
||||
offboard_control_sp.p2 = quad_motors_setpoint.pitch[mavlink_system.sysid] / (float)INT16_MAX;
|
||||
offboard_control_sp.p3= quad_motors_setpoint.yaw[mavlink_system.sysid] / (float)INT16_MAX;
|
||||
offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid]/(float)UINT16_MAX;
|
||||
//offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid] ;
|
||||
|
||||
if (quad_motors_setpoint.thrust[mavlink_system.sysid] ==0){
|
||||
ml_armed = false;
|
||||
|
||||
}
|
||||
|
||||
offboard_control_sp.armed = ml_armed;
|
||||
offboard_control_sp.mode = ml_mode;
|
||||
|
||||
offboard_control_sp.timestamp = hrt_absolute_time();
|
||||
|
||||
/* check if topic has to be advertised */
|
||||
if (offboard_control_sp_pub <= 0) {
|
||||
offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);
|
||||
} else {
|
||||
/* Publish */
|
||||
orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp);
|
||||
}
|
||||
|
||||
// /* change armed status if required */
|
||||
// bool cmd_armed = (quad_motors_setpoint.mode & MAVLINK_OFFBOARD_CONTROL_FLAG_ARMED);
|
||||
|
||||
// bool cmd_generated = false;
|
||||
|
||||
// if (v_status.flag_control_offboard_enabled != cmd_armed) {
|
||||
// vcmd.param1 = cmd_armed;
|
||||
// vcmd.param2 = 0;
|
||||
// vcmd.param3 = 0;
|
||||
// vcmd.param4 = 0;
|
||||
// vcmd.param5 = 0;
|
||||
// vcmd.param6 = 0;
|
||||
// vcmd.param7 = 0;
|
||||
// vcmd.command = MAV_CMD_COMPONENT_ARM_DISARM;
|
||||
// vcmd.target_system = mavlink_system.sysid;
|
||||
// vcmd.target_component = MAV_COMP_ID_ALL;
|
||||
// vcmd.source_system = msg->sysid;
|
||||
// vcmd.source_component = msg->compid;
|
||||
// vcmd.confirmation = 1;
|
||||
|
||||
// cmd_generated = true;
|
||||
// }
|
||||
|
||||
// /* check if input has to be enabled */
|
||||
// if ((v_status.flag_control_rates_enabled != (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_RATES)) ||
|
||||
// (v_status.flag_control_attitude_enabled != (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_ATTITUDE)) ||
|
||||
// (v_status.flag_control_velocity_enabled != (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_VELOCITY)) ||
|
||||
// (v_status.flag_control_position_enabled != (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_POSITION))) {
|
||||
// vcmd.param1 = (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_RATES);
|
||||
// vcmd.param2 = (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_ATTITUDE);
|
||||
// vcmd.param3 = (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_VELOCITY);
|
||||
// vcmd.param4 = (quad_motors_setpoint.mode == MAVLINK_OFFBOARD_CONTROL_MODE_POSITION);
|
||||
// vcmd.param5 = 0;
|
||||
// vcmd.param6 = 0;
|
||||
// vcmd.param7 = 0;
|
||||
// vcmd.command = PX4_CMD_CONTROLLER_SELECTION;
|
||||
// vcmd.target_system = mavlink_system.sysid;
|
||||
// vcmd.target_component = MAV_COMP_ID_ALL;
|
||||
// vcmd.source_system = msg->sysid;
|
||||
// vcmd.source_component = msg->compid;
|
||||
// vcmd.confirmation = 1;
|
||||
|
||||
// cmd_generated = true;
|
||||
// }
|
||||
|
||||
// if (cmd_generated) {
|
||||
// /* check if topic is advertised */
|
||||
// if (cmd_pub <= 0) {
|
||||
// cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
|
||||
// } else {
|
||||
// /* create command */
|
||||
// orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
|
||||
// }
|
||||
// }
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Only decode hil messages in HIL mode.
|
||||
*
|
||||
* The HIL mode is enabled by the HIL bit flag
|
||||
* in the system mode. Either send a set mode
|
||||
* COMMAND_LONG message or a SET_MODE message
|
||||
*/
|
||||
|
||||
// printf("\n HIL ENABLED?: %s \n",(mavlink_hil_enabled)?"true":"false");
|
||||
|
||||
if (mavlink_hil_enabled) {
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_HIL_STATE) {
|
||||
|
||||
mavlink_hil_state_t hil_state;
|
||||
mavlink_msg_hil_state_decode(msg, &hil_state);
|
||||
|
||||
// printf("\n HILSTATE : \n LAT: %i \n LON: %i \n ALT: %i \n "
|
||||
// "ROLL %i \n PITCH %i \n YAW %i \n"
|
||||
// "ROLLSPEED: %i \n PITCHSPEED: %i \n, YAWSPEED: %i \n",
|
||||
// hil_state.lat/1000000, // 1e7
|
||||
// hil_state.lon/1000000, // 1e7
|
||||
// hil_state.alt/1000, // mm
|
||||
// hil_state.roll, // float rad
|
||||
// hil_state.pitch, // float rad
|
||||
// hil_state.yaw, // float rad
|
||||
// hil_state.rollspeed, // float rad/s
|
||||
// hil_state.pitchspeed, // float rad/s
|
||||
// hil_state.yawspeed); // float rad/s
|
||||
|
||||
|
||||
hil_global_pos.lat = hil_state.lat;
|
||||
hil_global_pos.lon = hil_state.lon;
|
||||
hil_global_pos.alt = hil_state.alt / 1000.0f;
|
||||
hil_global_pos.vx = hil_state.vx / 100.0f;
|
||||
hil_global_pos.vy = hil_state.vy / 100.0f;
|
||||
hil_global_pos.vz = hil_state.vz / 100.0f;
|
||||
|
||||
/* set timestamp and notify processes (broadcast) */
|
||||
hil_global_pos.timestamp = hrt_absolute_time();
|
||||
orb_publish(ORB_ID(vehicle_global_position), pub_hil_global_pos, &hil_global_pos);
|
||||
|
||||
hil_attitude.roll = hil_state.roll;
|
||||
hil_attitude.pitch = hil_state.pitch;
|
||||
hil_attitude.yaw = hil_state.yaw;
|
||||
hil_attitude.rollspeed = hil_state.rollspeed;
|
||||
hil_attitude.pitchspeed = hil_state.pitchspeed;
|
||||
hil_attitude.yawspeed = hil_state.yawspeed;
|
||||
|
||||
/* set timestamp and notify processes (broadcast) */
|
||||
hil_attitude.counter++;
|
||||
hil_attitude.timestamp = hrt_absolute_time();
|
||||
orb_publish(ORB_ID(vehicle_attitude), pub_hil_attitude, &hil_attitude);
|
||||
}
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
|
||||
mavlink_manual_control_t man;
|
||||
mavlink_msg_manual_control_decode(msg, &man);
|
||||
|
||||
struct rc_channels_s rc_hil;
|
||||
memset(&rc_hil, 0, sizeof(rc_hil));
|
||||
static orb_advert_t rc_pub = 0;
|
||||
|
||||
rc_hil.timestamp = hrt_absolute_time();
|
||||
rc_hil.chan_count = 4;
|
||||
rc_hil.chan[0].raw = 1500 + man.x / 2;
|
||||
rc_hil.chan[1].raw = 1500 + man.y / 2;
|
||||
rc_hil.chan[2].raw = 1500 + man.r / 2;
|
||||
rc_hil.chan[3].raw = 1500 + man.z / 2;
|
||||
|
||||
rc_hil.chan[0].scaled = man.x / 1000.0f;
|
||||
rc_hil.chan[1].scaled = man.y / 1000.0f;
|
||||
rc_hil.chan[2].scaled = man.r / 1000.0f;
|
||||
rc_hil.chan[3].scaled = man.z / 1000.0f;
|
||||
|
||||
struct manual_control_setpoint_s mc;
|
||||
static orb_advert_t mc_pub = 0;
|
||||
|
||||
mc.timestamp = rc_hil.timestamp;
|
||||
mc.roll = man.x / 1000.0f;
|
||||
mc.pitch = man.y / 1000.0f;
|
||||
mc.yaw = man.r / 1000.0f;
|
||||
mc.throttle = man.z / 1000.0f;
|
||||
|
||||
/* fake RC channels with manual control input from simulator */
|
||||
|
||||
|
||||
if (rc_pub == 0) {
|
||||
rc_pub = orb_advertise(ORB_ID(rc_channels), &rc_hil);
|
||||
} else {
|
||||
orb_publish(ORB_ID(rc_channels), rc_pub, &rc_hil);
|
||||
}
|
||||
|
||||
if (mc_pub == 0) {
|
||||
mc_pub = orb_advertise(ORB_ID(manual_control_setpoint), &mc);
|
||||
} else {
|
||||
orb_publish(ORB_ID(manual_control_setpoint), mc_pub, &mc);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Receive data from UART.
|
||||
*/
|
||||
static void *
|
||||
receive_thread(void *arg)
|
||||
{
|
||||
int uart_fd = *((int*)arg);
|
||||
|
||||
const int timeout = 1000;
|
||||
uint8_t ch;
|
||||
|
||||
mavlink_message_t msg;
|
||||
|
||||
prctl(PR_SET_NAME, "mavlink uart rcv", getpid());
|
||||
|
||||
while (!thread_should_exit) {
|
||||
|
||||
struct pollfd fds[] = { { .fd = uart_fd, .events = POLLIN } };
|
||||
|
||||
if (poll(fds, 1, timeout) > 0) {
|
||||
/* non-blocking read until buffer is empty */
|
||||
int nread = 0;
|
||||
|
||||
do {
|
||||
nread = read(uart_fd, &ch, 1);
|
||||
|
||||
if (mavlink_parse_char(chan, ch, &msg, &status)) { //parse the char
|
||||
/* handle generic messages and commands */
|
||||
handle_message(&msg);
|
||||
|
||||
/* Handle packet with waypoint component */
|
||||
mavlink_wpm_message_handler(&msg, &global_pos, &local_pos);
|
||||
|
||||
/* Handle packet with parameter component */
|
||||
mavlink_pm_message_handler(MAVLINK_COMM_0, &msg);
|
||||
}
|
||||
} while (nread > 0);
|
||||
}
|
||||
}
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
pthread_t
|
||||
receive_start(int uart)
|
||||
{
|
||||
pthread_attr_t receiveloop_attr;
|
||||
pthread_attr_init(&receiveloop_attr);
|
||||
pthread_attr_setstacksize(&receiveloop_attr, 2048);
|
||||
|
||||
pthread_t thread;
|
||||
pthread_create(&thread, &receiveloop_attr, receive_thread, &uart);
|
||||
return thread;
|
||||
}
|
||||
@@ -0,0 +1,190 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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 missionlib.h
|
||||
* MAVLink missionlib components
|
||||
*/
|
||||
|
||||
// XXX trim includes
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <pthread.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <mqueue.h>
|
||||
#include <string.h>
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include <v1.0/common/mavlink.h>
|
||||
#include <arch/board/up_hrt.h>
|
||||
#include <time.h>
|
||||
#include <float.h>
|
||||
#include <unistd.h>
|
||||
#include <nuttx/sched.h>
|
||||
#include <sys/prctl.h>
|
||||
#include <termios.h>
|
||||
#include <errno.h>
|
||||
#include <stdlib.h>
|
||||
#include <poll.h>
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
#include "waypoints.h"
|
||||
#include "mavlink_log.h"
|
||||
#include "orb_topics.h"
|
||||
#include "missionlib.h"
|
||||
#include "mavlink_hil.h"
|
||||
#include "util.h"
|
||||
#include "waypoints.h"
|
||||
#include "mavlink_parameters.h"
|
||||
|
||||
static uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
|
||||
|
||||
int
|
||||
mavlink_missionlib_send_message(mavlink_message_t *msg)
|
||||
{
|
||||
uint16_t len = mavlink_msg_to_send_buffer(missionlib_msg_buf, msg);
|
||||
|
||||
mavlink_send_uart_bytes(chan, missionlib_msg_buf, len);
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
mavlink_missionlib_send_gcs_string(const char *string)
|
||||
{
|
||||
const int len = MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN;
|
||||
mavlink_statustext_t statustext;
|
||||
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';
|
||||
mavlink_message_t msg;
|
||||
|
||||
mavlink_msg_statustext_encode(mavlink_system.sysid, mavlink_system.compid, &msg, &statustext);
|
||||
return mavlink_missionlib_send_message(&msg);
|
||||
} else {
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get system time since boot in microseconds
|
||||
*
|
||||
* @return the system time since boot in microseconds
|
||||
*/
|
||||
uint64_t mavlink_missionlib_get_system_timestamp()
|
||||
{
|
||||
return hrt_absolute_time();
|
||||
}
|
||||
|
||||
/**
|
||||
* This callback is executed each time a waypoint changes.
|
||||
*
|
||||
* It publishes the vehicle_global_position_setpoint_s or the
|
||||
* vehicle_local_position_setpoint_s topic, depending on the type of waypoint
|
||||
*/
|
||||
void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
|
||||
float param2, float param3, float param4, float param5_lat_x,
|
||||
float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command)
|
||||
{
|
||||
static orb_advert_t global_position_setpoint_pub = -1;
|
||||
static orb_advert_t local_position_setpoint_pub = -1;
|
||||
char buf[50] = {0};
|
||||
|
||||
/* Update controller setpoints */
|
||||
if (frame == (int)MAV_FRAME_GLOBAL) {
|
||||
/* global, absolute waypoint */
|
||||
struct vehicle_global_position_setpoint_s sp;
|
||||
sp.lat = param5_lat_x * 1e7f;
|
||||
sp.lon = param6_lon_y * 1e7f;
|
||||
sp.altitude = param7_alt_z;
|
||||
sp.altitude_is_relative = false;
|
||||
sp.yaw = (param4 / 180.0f) * M_PI_F - M_PI_F;
|
||||
/* Initialize publication if necessary */
|
||||
if (global_position_setpoint_pub < 0) {
|
||||
global_position_setpoint_pub = orb_advertise(ORB_ID(vehicle_global_position_setpoint), &sp);
|
||||
} else {
|
||||
orb_publish(ORB_ID(vehicle_global_position_setpoint), global_position_setpoint_pub, &sp);
|
||||
}
|
||||
sprintf(buf, "[mp] WP#%i lat: % 3.6f/lon % 3.6f/alt % 4.6f/hdg %3.4f\n", (int)index, (double)param5_lat_x, (double)param6_lon_y, (double)param7_alt_z, (double)param4);
|
||||
|
||||
} else if (frame == (int)MAV_FRAME_GLOBAL_RELATIVE_ALT) {
|
||||
/* global, relative alt (in relation to HOME) waypoint */
|
||||
struct vehicle_global_position_setpoint_s sp;
|
||||
sp.lat = param5_lat_x * 1e7f;
|
||||
sp.lon = param6_lon_y * 1e7f;
|
||||
sp.altitude = param7_alt_z;
|
||||
sp.altitude_is_relative = true;
|
||||
sp.yaw = (param4 / 180.0f) * M_PI_F - M_PI_F;
|
||||
/* Initialize publication if necessary */
|
||||
if (global_position_setpoint_pub < 0) {
|
||||
global_position_setpoint_pub = orb_advertise(ORB_ID(vehicle_global_position_setpoint), &sp);
|
||||
} else {
|
||||
orb_publish(ORB_ID(vehicle_global_position_setpoint), global_position_setpoint_pub, &sp);
|
||||
}
|
||||
sprintf(buf, "[mp] WP#%i (lat: %f/lon %f/rel alt %f/hdg %f\n", (int)index, (double)param5_lat_x, (double)param6_lon_y, (double)param7_alt_z, (double)param4);
|
||||
|
||||
} else if (frame == (int)MAV_FRAME_LOCAL_ENU || frame == (int)MAV_FRAME_LOCAL_NED) {
|
||||
/* local, absolute waypoint */
|
||||
struct vehicle_local_position_setpoint_s sp;
|
||||
sp.x = param5_lat_x;
|
||||
sp.y = param6_lon_y;
|
||||
sp.z = param7_alt_z;
|
||||
sp.yaw = (param4 / 180.0f) * M_PI_F - M_PI_F;
|
||||
/* Initialize publication if necessary */
|
||||
if (local_position_setpoint_pub < 0) {
|
||||
local_position_setpoint_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &sp);
|
||||
} else {
|
||||
orb_publish(ORB_ID(vehicle_local_position_setpoint), local_position_setpoint_pub, &sp);
|
||||
}
|
||||
sprintf(buf, "[mp] WP#%i (x: %f/y %f/z %f/hdg %f\n", (int)index, (double)param5_lat_x, (double)param6_lon_y, (double)param7_alt_z, (double)param4);
|
||||
}
|
||||
|
||||
mavlink_missionlib_send_gcs_string(buf);
|
||||
printf("%s\n", buf);
|
||||
//printf("[mavlink mp] new setpoint\n");//: frame: %d, lat: %d, lon: %d, alt: %d, yaw: %d\n", frame, param5_lat_x*1000, param6_lon_y*1000, param7_alt_z*1000, param4*1000);
|
||||
}
|
||||
@@ -0,0 +1,52 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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 missionlib.h
|
||||
* MAVLink mission helper library
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <v1.0/common/mavlink.h>
|
||||
|
||||
//extern void mavlink_wpm_send_message(mavlink_message_t *msg);
|
||||
//extern void mavlink_wpm_send_gcs_string(const char *string);
|
||||
//extern uint64_t mavlink_wpm_get_system_timestamp(void);
|
||||
extern int mavlink_missionlib_send_message(mavlink_message_t *msg);
|
||||
extern int mavlink_missionlib_send_gcs_string(const char *string);
|
||||
extern uint64_t mavlink_missionlib_get_system_timestamp(void);
|
||||
extern void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
|
||||
float param2, float param3, float param4, float param5_lat_x,
|
||||
float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command);
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,98 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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 orb_topics.h
|
||||
* Common sets of topics subscribed to or published by the MAVLink driver,
|
||||
* and structures maintained by those subscriptions.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
#include <uORB/topics/rc_channels.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/offboard_control_setpoint.h>
|
||||
#include <uORB/topics/vehicle_command.h>
|
||||
#include <uORB/topics/vehicle_local_position_setpoint.h>
|
||||
#include <uORB/topics/vehicle_vicon_position.h>
|
||||
#include <uORB/topics/vehicle_global_position_setpoint.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/optical_flow.h>
|
||||
#include <uORB/topics/actuator_outputs.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <uORB/topics/debug_key_value.h>
|
||||
|
||||
struct mavlink_subscriptions {
|
||||
int sensor_sub;
|
||||
int att_sub;
|
||||
int global_pos_sub;
|
||||
int act_0_sub;
|
||||
int act_1_sub;
|
||||
int act_2_sub;
|
||||
int act_3_sub;
|
||||
int gps_sub;
|
||||
int man_control_sp_sub;
|
||||
int armed_sub;
|
||||
int actuators_sub;
|
||||
int local_pos_sub;
|
||||
int spa_sub;
|
||||
int spl_sub;
|
||||
int spg_sub;
|
||||
int debug_key_value;
|
||||
};
|
||||
|
||||
extern struct mavlink_subscriptions mavlink_subs;
|
||||
|
||||
/** Global position */
|
||||
extern struct vehicle_global_position_s global_pos;
|
||||
|
||||
/** Local position */
|
||||
extern struct vehicle_local_position_s local_pos;
|
||||
|
||||
/** Vehicle status */
|
||||
extern struct vehicle_status_s v_status;
|
||||
|
||||
/** RC channels */
|
||||
extern struct rc_channels_s rc;
|
||||
|
||||
/** Actuator armed state */
|
||||
extern struct actuator_armed_s armed;
|
||||
|
||||
/** Worker thread starter */
|
||||
extern pthread_t uorb_receive_start(void);
|
||||
@@ -0,0 +1,54 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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 util.h
|
||||
* Utility and helper functions and data.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/** MAVLink communications channel */
|
||||
extern uint8_t chan;
|
||||
|
||||
/** Shutdown marker */
|
||||
extern volatile bool thread_should_exit;
|
||||
|
||||
/** Waypoint storage */
|
||||
extern mavlink_wpm_storage *wpm;
|
||||
|
||||
/**
|
||||
* Translate the custom state into standard mavlink modes and state.
|
||||
*/
|
||||
extern void get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_mode);
|
||||
@@ -40,12 +40,15 @@
|
||||
* MAVLink waypoint protocol implementation (BSD-relicensed).
|
||||
*/
|
||||
|
||||
#include "waypoints.h"
|
||||
#include <math.h>
|
||||
#include <sys/prctl.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include "missionlib.h"
|
||||
#include "waypoints.h"
|
||||
#include "util.h"
|
||||
|
||||
#ifndef FM_PI
|
||||
#define FM_PI 3.1415926535897932384626433832795f
|
||||
#endif
|
||||
@@ -53,15 +56,6 @@
|
||||
bool debug = false;
|
||||
bool verbose = false;
|
||||
|
||||
extern mavlink_wpm_storage *wpm;
|
||||
|
||||
extern void mavlink_missionlib_send_message(mavlink_message_t *msg);
|
||||
extern void mavlink_missionlib_send_gcs_string(const char *string);
|
||||
extern uint64_t mavlink_missionlib_get_system_timestamp(void);
|
||||
extern void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
|
||||
float param2, float param3, float param4, float param5_lat_x,
|
||||
float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command);
|
||||
|
||||
|
||||
#define MAVLINK_WPM_NO_PRINTF
|
||||
|
||||
|
||||
@@ -46,7 +46,6 @@
|
||||
or in the same folder as this source file */
|
||||
|
||||
#include <v1.0/mavlink_types.h>
|
||||
extern void mavlink_send_uart_bytes(mavlink_channel_t chan, uint8_t *buffer, uint16_t len);
|
||||
|
||||
#ifndef MAVLINK_SEND_UART_BYTES
|
||||
#define MAVLINK_SEND_UART_BYTES(chan, buffer, len) mavlink_send_uart_bytes(chan, buffer, len)
|
||||
|
||||
+1
-2
@@ -144,7 +144,6 @@ int sdlog_main(int argc, char *argv[])
|
||||
4096,
|
||||
sdlog_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
thread_running = true;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
@@ -215,7 +214,7 @@ int sdlog_thread_main(int argc, char *argv[]) {
|
||||
|
||||
char folder_path[64];
|
||||
if (create_logfolder(folder_path))
|
||||
errx(1, "unable to create logging folder, exiting");
|
||||
errx(1, "unable to create logging folder, exiting.");
|
||||
|
||||
/* create sensorfile */
|
||||
int sensorfile = -1;
|
||||
|
||||
@@ -124,9 +124,9 @@ extern "C"
|
||||
#if 0
|
||||
int getopt (int argc, char **argv, char *optstring);
|
||||
#endif
|
||||
int getopt_long (int argc, char **argv, const char *shortopts,
|
||||
__EXPORT int getopt_long (int argc, char **argv, const char *shortopts,
|
||||
const GETOPT_LONG_OPTION_T * longopts, int *longind);
|
||||
int getopt_long_only (int argc, char **argv, const char *shortopts,
|
||||
__EXPORT int getopt_long_only (int argc, char **argv, const char *shortopts,
|
||||
const GETOPT_LONG_OPTION_T * longopts, int *longind);
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
||||
@@ -54,6 +54,8 @@ struct orb_metadata {
|
||||
const size_t o_size; /**< object size */
|
||||
};
|
||||
|
||||
typedef const struct orb_metadata *orb_id_t;
|
||||
|
||||
/**
|
||||
* Generates a pointer to the uORB metadata structure for
|
||||
* a given topic.
|
||||
|
||||
Reference in New Issue
Block a user