mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 17:07:34 +08:00
Merged move of additional apps out of NuttX folders
This commit is contained in:
@@ -0,0 +1,919 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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 blinkm.cpp
|
||||
*
|
||||
* Driver for the BlinkM LED controller connected via I2C.
|
||||
*
|
||||
* Connect the BlinkM to I2C3 and put the following line to the rc startup-script:
|
||||
* blinkm start
|
||||
*
|
||||
* To start the system monitor put in the next line after the blinkm start:
|
||||
* blinkm systemmonitor
|
||||
*
|
||||
*
|
||||
* Description:
|
||||
* After startup, the Application checked how many lipo cells are connected to the System.
|
||||
* The recognized number off cells, will be blinked 5 times in purple color.
|
||||
* 2 Cells = 2 blinks
|
||||
* ...
|
||||
* 5 Cells = 5 blinks
|
||||
* Now the Application will show the actual selected Flightmode, GPS-Fix and Battery Warnings and Alerts.
|
||||
*
|
||||
* System disarmed:
|
||||
* The BlinkM should lit solid red.
|
||||
*
|
||||
* System armed:
|
||||
* One message is made of 4 Blinks and a pause in the same length as the 4 blinks.
|
||||
*
|
||||
* X-X-X-X-_-_-_-_-_-_-
|
||||
* -------------------------
|
||||
* G G G M
|
||||
* P P P O
|
||||
* S S S D
|
||||
* E
|
||||
*
|
||||
* (X = on, _=off)
|
||||
*
|
||||
* The first 3 blinks indicates the status of the GPS-Signal (red):
|
||||
* 0-4 satellites = X-X-X-X-_-_-_-_-_-_-
|
||||
* 5 satellites = X-X-_-X-_-_-_-_-_-_-
|
||||
* 6 satellites = X-_-_-X-_-_-_-_-_-_-
|
||||
* >=7 satellites = _-_-_-X-_-_-_-_-_-_-
|
||||
* If no GPS is found the first 3 blinks are white
|
||||
*
|
||||
* The fourth Blink indicates the Flightmode:
|
||||
* MANUAL : amber
|
||||
* STABILIZED : yellow
|
||||
* HOLD : blue
|
||||
* AUTO : green
|
||||
*
|
||||
* Battery Warning (low Battery Level):
|
||||
* Continuously blinking in yellow X-X-X-X-X-X-X-X-X-X
|
||||
*
|
||||
* Battery Alert (critical Battery Level)
|
||||
* Continuously blinking in red X-X-X-X-X-X-X-X-X-X
|
||||
*
|
||||
* General Error (no uOrb Data)
|
||||
* Continuously blinking in white X-X-X-X-X-X-X-X-X-X
|
||||
*
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <ctype.h>
|
||||
|
||||
#include <drivers/drv_blinkm.h>
|
||||
|
||||
#include <nuttx/wqueue.h>
|
||||
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <poll.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
|
||||
static const float MAX_CELL_VOLTAGE = 4.3f;
|
||||
static const int LED_ONTIME = 120;
|
||||
static const int LED_OFFTIME = 120;
|
||||
static const int LED_BLINK = 1;
|
||||
static const int LED_NOBLINK = 0;
|
||||
|
||||
class BlinkM : public device::I2C
|
||||
{
|
||||
public:
|
||||
BlinkM(int bus, int blinkm);
|
||||
virtual ~BlinkM();
|
||||
|
||||
|
||||
virtual int init();
|
||||
virtual int probe();
|
||||
virtual int setMode(int mode);
|
||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
|
||||
static const char *const script_names[];
|
||||
|
||||
private:
|
||||
enum ScriptID {
|
||||
USER = 0,
|
||||
RGB,
|
||||
WHITE_FLASH,
|
||||
RED_FLASH,
|
||||
GREEN_FLASH,
|
||||
BLUE_FLASH,
|
||||
CYAN_FLASH,
|
||||
MAGENTA_FLASH,
|
||||
YELLOW_FLASH,
|
||||
BLACK,
|
||||
HUE_CYCLE,
|
||||
MOOD_LIGHT,
|
||||
VIRTUAL_CANDLE,
|
||||
WATER_REFLECTIONS,
|
||||
OLD_NEON,
|
||||
THE_SEASONS,
|
||||
THUNDERSTORM,
|
||||
STOP_LIGHT,
|
||||
MORSE_CODE
|
||||
};
|
||||
|
||||
enum ledColors {
|
||||
LED_OFF,
|
||||
LED_RED,
|
||||
LED_YELLOW,
|
||||
LED_PURPLE,
|
||||
LED_GREEN,
|
||||
LED_BLUE,
|
||||
LED_WHITE,
|
||||
LED_AMBER
|
||||
};
|
||||
|
||||
work_s _work;
|
||||
|
||||
int led_color_1;
|
||||
int led_color_2;
|
||||
int led_color_3;
|
||||
int led_color_4;
|
||||
int led_color_5;
|
||||
int led_color_6;
|
||||
int led_color_7;
|
||||
int led_color_8;
|
||||
int led_blink;
|
||||
|
||||
bool systemstate_run;
|
||||
|
||||
void setLEDColor(int ledcolor);
|
||||
static void led_trampoline(void *arg);
|
||||
void led();
|
||||
|
||||
int set_rgb(uint8_t r, uint8_t g, uint8_t b);
|
||||
|
||||
int fade_rgb(uint8_t r, uint8_t g, uint8_t b);
|
||||
int fade_hsb(uint8_t h, uint8_t s, uint8_t b);
|
||||
|
||||
int fade_rgb_random(uint8_t r, uint8_t g, uint8_t b);
|
||||
int fade_hsb_random(uint8_t h, uint8_t s, uint8_t b);
|
||||
|
||||
int set_fade_speed(uint8_t s);
|
||||
|
||||
int play_script(uint8_t script_id);
|
||||
int play_script(const char *script_name);
|
||||
int stop_script();
|
||||
|
||||
int write_script_line(uint8_t line, uint8_t ticks, uint8_t cmd, uint8_t arg1, uint8_t arg2, uint8_t arg3);
|
||||
int read_script_line(uint8_t line, uint8_t &ticks, uint8_t cmd[4]);
|
||||
int set_script(uint8_t length, uint8_t repeats);
|
||||
|
||||
int get_rgb(uint8_t &r, uint8_t &g, uint8_t &b);
|
||||
|
||||
int get_firmware_version(uint8_t version[2]);
|
||||
};
|
||||
|
||||
/* for now, we only support one BlinkM */
|
||||
namespace
|
||||
{
|
||||
BlinkM *g_blinkm;
|
||||
}
|
||||
|
||||
/* list of script names, must match script ID numbers */
|
||||
const char *const BlinkM::script_names[] = {
|
||||
"USER",
|
||||
"RGB",
|
||||
"WHITE_FLASH",
|
||||
"RED_FLASH",
|
||||
"GREEN_FLASH",
|
||||
"BLUE_FLASH",
|
||||
"CYAN_FLASH",
|
||||
"MAGENTA_FLASH",
|
||||
"YELLOW_FLASH",
|
||||
"BLACK",
|
||||
"HUE_CYCLE",
|
||||
"MOOD_LIGHT",
|
||||
"VIRTUAL_CANDLE",
|
||||
"WATER_REFLECTIONS",
|
||||
"OLD_NEON",
|
||||
"THE_SEASONS",
|
||||
"THUNDERSTORM",
|
||||
"STOP_LIGHT",
|
||||
"MORSE_CODE",
|
||||
nullptr
|
||||
};
|
||||
|
||||
|
||||
extern "C" __EXPORT int blinkm_main(int argc, char *argv[]);
|
||||
|
||||
BlinkM::BlinkM(int bus, int blinkm) :
|
||||
I2C("blinkm", BLINKM_DEVICE_PATH, bus, blinkm, 100000),
|
||||
led_color_1(LED_OFF),
|
||||
led_color_2(LED_OFF),
|
||||
led_color_3(LED_OFF),
|
||||
led_color_4(LED_OFF),
|
||||
led_color_5(LED_OFF),
|
||||
led_color_6(LED_OFF),
|
||||
led_color_7(LED_OFF),
|
||||
led_color_8(LED_OFF),
|
||||
led_blink(LED_NOBLINK),
|
||||
systemstate_run(false)
|
||||
{
|
||||
memset(&_work, 0, sizeof(_work));
|
||||
}
|
||||
|
||||
BlinkM::~BlinkM()
|
||||
{
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::init()
|
||||
{
|
||||
int ret;
|
||||
ret = I2C::init();
|
||||
|
||||
if (ret != OK) {
|
||||
warnx("I2C init failed");
|
||||
return ret;
|
||||
}
|
||||
|
||||
stop_script();
|
||||
set_rgb(0,0,0);
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::setMode(int mode)
|
||||
{
|
||||
if(mode == 1) {
|
||||
if(systemstate_run == false) {
|
||||
stop_script();
|
||||
set_rgb(0,0,0);
|
||||
systemstate_run = true;
|
||||
work_queue(LPWORK, &_work, (worker_t)&BlinkM::led_trampoline, this, 1);
|
||||
}
|
||||
} else {
|
||||
systemstate_run = false;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::probe()
|
||||
{
|
||||
uint8_t version[2];
|
||||
int ret;
|
||||
|
||||
ret = get_firmware_version(version);
|
||||
|
||||
if (ret == OK)
|
||||
log("found BlinkM firmware version %c%c", version[1], version[0]);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
int ret = ENOTTY;
|
||||
|
||||
switch (cmd) {
|
||||
case BLINKM_PLAY_SCRIPT_NAMED:
|
||||
if (arg == 0) {
|
||||
ret = EINVAL;
|
||||
break;
|
||||
}
|
||||
ret = play_script((const char *)arg);
|
||||
break;
|
||||
|
||||
case BLINKM_PLAY_SCRIPT:
|
||||
ret = play_script(arg);
|
||||
break;
|
||||
|
||||
case BLINKM_SET_USER_SCRIPT: {
|
||||
if (arg == 0) {
|
||||
ret = EINVAL;
|
||||
break;
|
||||
}
|
||||
|
||||
unsigned lines = 0;
|
||||
const uint8_t *script = (const uint8_t *)arg;
|
||||
|
||||
while ((lines < 50) && (script[1] != 0)) {
|
||||
ret = write_script_line(lines, script[0], script[1], script[2], script[3], script[4]);
|
||||
if (ret != OK)
|
||||
break;
|
||||
script += 5;
|
||||
}
|
||||
if (ret == OK)
|
||||
ret = set_script(lines, 0);
|
||||
break;
|
||||
}
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
BlinkM::led_trampoline(void *arg)
|
||||
{
|
||||
BlinkM *bm = (BlinkM *)arg;
|
||||
|
||||
bm->led();
|
||||
}
|
||||
|
||||
|
||||
|
||||
void
|
||||
BlinkM::led()
|
||||
{
|
||||
|
||||
static int vehicle_status_sub_fd;
|
||||
static int vehicle_gps_position_sub_fd;
|
||||
|
||||
static int num_of_cells = 0;
|
||||
static int detected_cells_runcount = 0;
|
||||
|
||||
static int t_led_color[8] = { 0, 0, 0, 0, 0, 0, 0, 0};
|
||||
static int t_led_blink = 0;
|
||||
static int led_thread_runcount=0;
|
||||
static int led_interval = 1000;
|
||||
|
||||
static int no_data_vehicle_status = 0;
|
||||
static int no_data_vehicle_gps_position = 0;
|
||||
|
||||
static bool topic_initialized = false;
|
||||
static bool detected_cells_blinked = false;
|
||||
static bool led_thread_ready = true;
|
||||
|
||||
int num_of_used_sats = 0;
|
||||
|
||||
if(!topic_initialized) {
|
||||
vehicle_status_sub_fd = orb_subscribe(ORB_ID(vehicle_status));
|
||||
orb_set_interval(vehicle_status_sub_fd, 1000);
|
||||
|
||||
vehicle_gps_position_sub_fd = orb_subscribe(ORB_ID(vehicle_gps_position));
|
||||
orb_set_interval(vehicle_gps_position_sub_fd, 1000);
|
||||
|
||||
topic_initialized = true;
|
||||
}
|
||||
|
||||
if(led_thread_ready == true) {
|
||||
if(!detected_cells_blinked) {
|
||||
if(num_of_cells > 0) {
|
||||
t_led_color[0] = LED_PURPLE;
|
||||
}
|
||||
if(num_of_cells > 1) {
|
||||
t_led_color[1] = LED_PURPLE;
|
||||
}
|
||||
if(num_of_cells > 2) {
|
||||
t_led_color[2] = LED_PURPLE;
|
||||
}
|
||||
if(num_of_cells > 3) {
|
||||
t_led_color[3] = LED_PURPLE;
|
||||
}
|
||||
if(num_of_cells > 4) {
|
||||
t_led_color[4] = LED_PURPLE;
|
||||
}
|
||||
t_led_color[5] = LED_OFF;
|
||||
t_led_color[6] = LED_OFF;
|
||||
t_led_color[7] = LED_OFF;
|
||||
t_led_blink = LED_BLINK;
|
||||
} else {
|
||||
t_led_color[0] = led_color_1;
|
||||
t_led_color[1] = led_color_2;
|
||||
t_led_color[2] = led_color_3;
|
||||
t_led_color[3] = led_color_4;
|
||||
t_led_color[4] = led_color_5;
|
||||
t_led_color[5] = led_color_6;
|
||||
t_led_color[6] = led_color_7;
|
||||
t_led_color[7] = led_color_8;
|
||||
t_led_blink = led_blink;
|
||||
}
|
||||
led_thread_ready = false;
|
||||
}
|
||||
|
||||
if (led_thread_runcount & 1) {
|
||||
if (t_led_blink)
|
||||
setLEDColor(LED_OFF);
|
||||
led_interval = LED_OFFTIME;
|
||||
} else {
|
||||
setLEDColor(t_led_color[(led_thread_runcount / 2) % 8]);
|
||||
//led_interval = (led_thread_runcount & 1) : LED_ONTIME;
|
||||
led_interval = LED_ONTIME;
|
||||
}
|
||||
|
||||
if (led_thread_runcount == 15) {
|
||||
/* obtained data for the first file descriptor */
|
||||
struct vehicle_status_s vehicle_status_raw;
|
||||
struct vehicle_gps_position_s vehicle_gps_position_raw;
|
||||
|
||||
memset(&vehicle_status_raw, 0, sizeof(vehicle_status_raw));
|
||||
memset(&vehicle_gps_position_raw, 0, sizeof(vehicle_gps_position_raw));
|
||||
|
||||
bool new_data_vehicle_status;
|
||||
bool new_data_vehicle_gps_position;
|
||||
|
||||
orb_check(vehicle_status_sub_fd, &new_data_vehicle_status);
|
||||
|
||||
if (new_data_vehicle_status) {
|
||||
orb_copy(ORB_ID(vehicle_status), vehicle_status_sub_fd, &vehicle_status_raw);
|
||||
no_data_vehicle_status = 0;
|
||||
} else {
|
||||
no_data_vehicle_status++;
|
||||
if(no_data_vehicle_status >= 3)
|
||||
no_data_vehicle_status = 3;
|
||||
}
|
||||
|
||||
orb_check(vehicle_gps_position_sub_fd, &new_data_vehicle_gps_position);
|
||||
|
||||
if (new_data_vehicle_gps_position) {
|
||||
orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_position_sub_fd, &vehicle_gps_position_raw);
|
||||
no_data_vehicle_gps_position = 0;
|
||||
} else {
|
||||
no_data_vehicle_gps_position++;
|
||||
if(no_data_vehicle_gps_position >= 3)
|
||||
no_data_vehicle_gps_position = 3;
|
||||
}
|
||||
|
||||
|
||||
|
||||
/* get number of used satellites in navigation */
|
||||
num_of_used_sats = 0;
|
||||
//for(int satloop=0; satloop<20; satloop++) {
|
||||
for(int satloop=0; satloop<sizeof(vehicle_gps_position_raw.satellite_used); satloop++) {
|
||||
if(vehicle_gps_position_raw.satellite_used[satloop] == 1) {
|
||||
num_of_used_sats++;
|
||||
}
|
||||
}
|
||||
|
||||
if(new_data_vehicle_status || no_data_vehicle_status < 3){
|
||||
if(num_of_cells == 0) {
|
||||
/* looking for lipo cells that are connected */
|
||||
printf("<blinkm> checking cells\n");
|
||||
for(num_of_cells = 2; num_of_cells < 7; num_of_cells++) {
|
||||
if(vehicle_status_raw.voltage_battery < num_of_cells * MAX_CELL_VOLTAGE) break;
|
||||
}
|
||||
printf("<blinkm> cells found:%d\n", num_of_cells);
|
||||
|
||||
} else {
|
||||
if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_WARNING) {
|
||||
/* LED Pattern for battery low warning */
|
||||
led_color_1 = LED_YELLOW;
|
||||
led_color_2 = LED_YELLOW;
|
||||
led_color_3 = LED_YELLOW;
|
||||
led_color_4 = LED_YELLOW;
|
||||
led_color_5 = LED_YELLOW;
|
||||
led_color_6 = LED_YELLOW;
|
||||
led_color_7 = LED_YELLOW;
|
||||
led_color_8 = LED_YELLOW;
|
||||
led_blink = LED_BLINK;
|
||||
|
||||
} else if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_ALERT) {
|
||||
/* LED Pattern for battery critical alerting */
|
||||
led_color_1 = LED_RED;
|
||||
led_color_2 = LED_RED;
|
||||
led_color_3 = LED_RED;
|
||||
led_color_4 = LED_RED;
|
||||
led_color_5 = LED_RED;
|
||||
led_color_6 = LED_RED;
|
||||
led_color_7 = LED_RED;
|
||||
led_color_8 = LED_RED;
|
||||
led_blink = LED_BLINK;
|
||||
|
||||
} else {
|
||||
/* no battery warnings here */
|
||||
|
||||
if(vehicle_status_raw.flag_system_armed == false) {
|
||||
/* system not armed */
|
||||
led_color_1 = LED_RED;
|
||||
led_color_2 = LED_RED;
|
||||
led_color_3 = LED_RED;
|
||||
led_color_4 = LED_RED;
|
||||
led_color_5 = LED_RED;
|
||||
led_color_6 = LED_RED;
|
||||
led_color_7 = LED_RED;
|
||||
led_color_8 = LED_RED;
|
||||
led_blink = LED_NOBLINK;
|
||||
|
||||
} else {
|
||||
/* armed system - initial led pattern */
|
||||
led_color_1 = LED_RED;
|
||||
led_color_2 = LED_RED;
|
||||
led_color_3 = LED_RED;
|
||||
led_color_4 = LED_OFF;
|
||||
led_color_5 = LED_OFF;
|
||||
led_color_6 = LED_OFF;
|
||||
led_color_7 = LED_OFF;
|
||||
led_color_8 = LED_OFF;
|
||||
led_blink = LED_BLINK;
|
||||
|
||||
/* handle 4th led - flightmode indicator */
|
||||
switch((int)vehicle_status_raw.flight_mode) {
|
||||
case VEHICLE_FLIGHT_MODE_MANUAL:
|
||||
led_color_4 = LED_AMBER;
|
||||
break;
|
||||
|
||||
case VEHICLE_FLIGHT_MODE_STAB:
|
||||
led_color_4 = LED_YELLOW;
|
||||
break;
|
||||
|
||||
case VEHICLE_FLIGHT_MODE_HOLD:
|
||||
led_color_4 = LED_BLUE;
|
||||
break;
|
||||
|
||||
case VEHICLE_FLIGHT_MODE_AUTO:
|
||||
led_color_4 = LED_GREEN;
|
||||
break;
|
||||
}
|
||||
|
||||
if(new_data_vehicle_gps_position || no_data_vehicle_gps_position < 3) {
|
||||
/* handling used sat´s */
|
||||
if(num_of_used_sats >= 7) {
|
||||
led_color_1 = LED_OFF;
|
||||
led_color_2 = LED_OFF;
|
||||
led_color_3 = LED_OFF;
|
||||
} else if(num_of_used_sats == 6) {
|
||||
led_color_2 = LED_OFF;
|
||||
led_color_3 = LED_OFF;
|
||||
} else if(num_of_used_sats == 5) {
|
||||
led_color_3 = LED_OFF;
|
||||
}
|
||||
|
||||
} else {
|
||||
/* no vehicle_gps_position data */
|
||||
led_color_1 = LED_WHITE;
|
||||
led_color_2 = LED_WHITE;
|
||||
led_color_3 = LED_WHITE;
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
} else {
|
||||
/* LED Pattern for general Error - no vehicle_status can retrieved */
|
||||
led_color_1 = LED_WHITE;
|
||||
led_color_2 = LED_WHITE;
|
||||
led_color_3 = LED_WHITE;
|
||||
led_color_4 = LED_WHITE;
|
||||
led_color_5 = LED_WHITE;
|
||||
led_color_6 = LED_WHITE;
|
||||
led_color_7 = LED_WHITE;
|
||||
led_color_8 = LED_WHITE;
|
||||
led_blink = LED_BLINK;
|
||||
|
||||
}
|
||||
|
||||
/*
|
||||
printf( "<blinkm> Volt:%8.4f\tArmed:%4u\tMode:%4u\tCells:%4u\tNDVS:%4u\tNDSAT:%4u\tSats:%4u\tFix:%4u\tVisible:%4u\n",
|
||||
vehicle_status_raw.voltage_battery,
|
||||
vehicle_status_raw.flag_system_armed,
|
||||
vehicle_status_raw.flight_mode,
|
||||
num_of_cells,
|
||||
no_data_vehicle_status,
|
||||
no_data_vehicle_gps_position,
|
||||
num_of_used_sats,
|
||||
vehicle_gps_position_raw.fix_type,
|
||||
vehicle_gps_position_raw.satellites_visible);
|
||||
*/
|
||||
|
||||
led_thread_runcount=0;
|
||||
led_thread_ready = true;
|
||||
led_interval = LED_OFFTIME;
|
||||
|
||||
if(detected_cells_runcount < 4){
|
||||
detected_cells_runcount++;
|
||||
} else {
|
||||
detected_cells_blinked = true;
|
||||
}
|
||||
|
||||
} else {
|
||||
led_thread_runcount++;
|
||||
}
|
||||
|
||||
if(systemstate_run == true) {
|
||||
/* re-queue ourselves to run again later */
|
||||
work_queue(LPWORK, &_work, (worker_t)&BlinkM::led_trampoline, this, led_interval);
|
||||
} else {
|
||||
stop_script();
|
||||
set_rgb(0,0,0);
|
||||
}
|
||||
}
|
||||
|
||||
void BlinkM::setLEDColor(int ledcolor) {
|
||||
switch (ledcolor) {
|
||||
case LED_OFF: // off
|
||||
set_rgb(0,0,0);
|
||||
break;
|
||||
case LED_RED: // red
|
||||
set_rgb(255,0,0);
|
||||
break;
|
||||
case LED_YELLOW: // yellow
|
||||
set_rgb(255,70,0);
|
||||
break;
|
||||
case LED_PURPLE: // purple
|
||||
set_rgb(255,0,255);
|
||||
break;
|
||||
case LED_GREEN: // green
|
||||
set_rgb(0,255,0);
|
||||
break;
|
||||
case LED_BLUE: // blue
|
||||
set_rgb(0,0,255);
|
||||
break;
|
||||
case LED_WHITE: // white
|
||||
set_rgb(255,255,255);
|
||||
break;
|
||||
case LED_AMBER: // amber
|
||||
set_rgb(255,20,0);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::set_rgb(uint8_t r, uint8_t g, uint8_t b)
|
||||
{
|
||||
const uint8_t msg[4] = { 'n', r, g, b };
|
||||
|
||||
return transfer(msg, sizeof(msg), nullptr, 0);
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::fade_rgb(uint8_t r, uint8_t g, uint8_t b)
|
||||
{
|
||||
const uint8_t msg[4] = { 'c', r, g, b };
|
||||
|
||||
return transfer(msg, sizeof(msg), nullptr, 0);
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::fade_hsb(uint8_t h, uint8_t s, uint8_t b)
|
||||
{
|
||||
const uint8_t msg[4] = { 'h', h, s, b };
|
||||
|
||||
return transfer(msg, sizeof(msg), nullptr, 0);
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::fade_rgb_random(uint8_t r, uint8_t g, uint8_t b)
|
||||
{
|
||||
const uint8_t msg[4] = { 'C', r, g, b };
|
||||
|
||||
return transfer(msg, sizeof(msg), nullptr, 0);
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::fade_hsb_random(uint8_t h, uint8_t s, uint8_t b)
|
||||
{
|
||||
const uint8_t msg[4] = { 'H', h, s, b };
|
||||
|
||||
return transfer(msg, sizeof(msg), nullptr, 0);
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::set_fade_speed(uint8_t s)
|
||||
{
|
||||
const uint8_t msg[2] = { 'f', s };
|
||||
|
||||
return transfer(msg, sizeof(msg), nullptr, 0);
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::play_script(uint8_t script_id)
|
||||
{
|
||||
const uint8_t msg[4] = { 'p', script_id, 0, 0 };
|
||||
|
||||
return transfer(msg, sizeof(msg), nullptr, 0);
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::play_script(const char *script_name)
|
||||
{
|
||||
/* handle HTML colour encoding */
|
||||
if (isxdigit(script_name[0]) && (strlen(script_name) == 6)) {
|
||||
char code[3];
|
||||
uint8_t r, g, b;
|
||||
|
||||
code[2] = '\0';
|
||||
|
||||
code[0] = script_name[1];
|
||||
code[1] = script_name[2];
|
||||
r = strtol(code, 0, 16);
|
||||
code[0] = script_name[3];
|
||||
code[1] = script_name[4];
|
||||
g = strtol(code, 0, 16);
|
||||
code[0] = script_name[5];
|
||||
code[1] = script_name[6];
|
||||
b = strtol(code, 0, 16);
|
||||
|
||||
stop_script();
|
||||
return set_rgb(r, g, b);
|
||||
}
|
||||
|
||||
for (unsigned i = 0; script_names[i] != nullptr; i++)
|
||||
if (!strcasecmp(script_name, script_names[i]))
|
||||
return play_script(i);
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::stop_script()
|
||||
{
|
||||
const uint8_t msg[1] = { 'o' };
|
||||
|
||||
return transfer(msg, sizeof(msg), nullptr, 0);
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::write_script_line(uint8_t line, uint8_t ticks, uint8_t cmd, uint8_t arg1, uint8_t arg2, uint8_t arg3)
|
||||
{
|
||||
const uint8_t msg[8] = { 'W', 0, line, ticks, cmd, arg1, arg2, arg3 };
|
||||
|
||||
return transfer(msg, sizeof(msg), nullptr, 0);
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::read_script_line(uint8_t line, uint8_t &ticks, uint8_t cmd[4])
|
||||
{
|
||||
const uint8_t msg[3] = { 'R', 0, line };
|
||||
uint8_t result[5];
|
||||
|
||||
int ret = transfer(msg, sizeof(msg), result, sizeof(result));
|
||||
|
||||
if (ret == OK) {
|
||||
ticks = result[0];
|
||||
cmd[0] = result[1];
|
||||
cmd[1] = result[2];
|
||||
cmd[2] = result[3];
|
||||
cmd[3] = result[4];
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::set_script(uint8_t len, uint8_t repeats)
|
||||
{
|
||||
const uint8_t msg[4] = { 'L', 0, len, repeats };
|
||||
|
||||
return transfer(msg, sizeof(msg), nullptr, 0);
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::get_rgb(uint8_t &r, uint8_t &g, uint8_t &b)
|
||||
{
|
||||
const uint8_t msg = 'g';
|
||||
uint8_t result[3];
|
||||
|
||||
int ret = transfer(&msg, sizeof(msg), result, sizeof(result));
|
||||
|
||||
if (ret == OK) {
|
||||
r = result[0];
|
||||
g = result[1];
|
||||
b = result[2];
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
BlinkM::get_firmware_version(uint8_t version[2])
|
||||
{
|
||||
const uint8_t msg = 'Z';
|
||||
|
||||
return transfer(&msg, sizeof(msg), version, 2);
|
||||
}
|
||||
|
||||
void blinkm_usage() {
|
||||
fprintf(stderr, "missing command: try 'start', 'systemstate', 'ledoff', 'list' or a script name {options}\n");
|
||||
fprintf(stderr, "options:\n");
|
||||
fprintf(stderr, "\t-b --bus i2cbus (3)\n");
|
||||
fprintf(stderr, "\t-a --blinkmaddr blinkmaddr (9)\n");
|
||||
}
|
||||
|
||||
int
|
||||
blinkm_main(int argc, char *argv[])
|
||||
{
|
||||
|
||||
int i2cdevice = PX4_I2C_BUS_EXPANSION;
|
||||
int blinkmadr = 9;
|
||||
|
||||
int x;
|
||||
|
||||
for (x = 1; x < argc; x++) {
|
||||
if (strcmp(argv[x], "-b") == 0 || strcmp(argv[x], "--bus") == 0) {
|
||||
if (argc > x + 1) {
|
||||
i2cdevice = atoi(argv[x + 1]);
|
||||
}
|
||||
}
|
||||
|
||||
if (strcmp(argv[x], "-a") == 0 || strcmp(argv[x], "--blinkmaddr") == 0) {
|
||||
if (argc > x + 1) {
|
||||
blinkmadr = atoi(argv[x + 1]);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
if (g_blinkm != nullptr)
|
||||
errx(1, "already started");
|
||||
|
||||
g_blinkm = new BlinkM(i2cdevice, blinkmadr);
|
||||
|
||||
if (g_blinkm == nullptr)
|
||||
errx(1, "new failed");
|
||||
|
||||
if (OK != g_blinkm->init()) {
|
||||
delete g_blinkm;
|
||||
g_blinkm = nullptr;
|
||||
errx(1, "init failed");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
||||
if (g_blinkm == nullptr) {
|
||||
fprintf(stderr, "not started\n");
|
||||
blinkm_usage();
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "systemstate")) {
|
||||
g_blinkm->setMode(1);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "ledoff")) {
|
||||
g_blinkm->setMode(0);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
||||
if (!strcmp(argv[1], "list")) {
|
||||
for (unsigned i = 0; BlinkM::script_names[i] != nullptr; i++)
|
||||
fprintf(stderr, " %s\n", BlinkM::script_names[i]);
|
||||
fprintf(stderr, " <html color number>\n");
|
||||
exit(0);
|
||||
}
|
||||
|
||||
/* things that require access to the device */
|
||||
int fd = open(BLINKM_DEVICE_PATH, 0);
|
||||
if (fd < 0)
|
||||
err(1, "can't open BlinkM device");
|
||||
|
||||
g_blinkm->setMode(0);
|
||||
if (ioctl(fd, BLINKM_PLAY_SCRIPT_NAMED, (unsigned long)argv[1]) == OK)
|
||||
exit(0);
|
||||
|
||||
blinkm_usage();
|
||||
exit(0);
|
||||
}
|
||||
@@ -0,0 +1,40 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# BlinkM I2C LED driver
|
||||
#
|
||||
|
||||
MODULE_COMMAND = blinkm
|
||||
|
||||
SRCS = blinkm.cpp
|
||||
@@ -0,0 +1,929 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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 bma180.cpp
|
||||
* Driver for the Bosch BMA 180 MEMS accelerometer connected via SPI.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include <semaphore.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/wqueue.h>
|
||||
#include <nuttx/clock.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <drivers/device/spi.h>
|
||||
#include <drivers/drv_accel.h>
|
||||
|
||||
|
||||
/* oddly, ERROR is not defined for c++ */
|
||||
#ifdef ERROR
|
||||
# undef ERROR
|
||||
#endif
|
||||
static const int ERROR = -1;
|
||||
|
||||
#define DIR_READ (1<<7)
|
||||
#define DIR_WRITE (0<<7)
|
||||
|
||||
#define ADDR_CHIP_ID 0x00
|
||||
#define CHIP_ID 0x03
|
||||
|
||||
#define ADDR_ACC_X_LSB 0x02
|
||||
#define ADDR_ACC_Y_LSB 0x04
|
||||
#define ADDR_ACC_Z_LSB 0x06
|
||||
#define ADDR_TEMPERATURE 0x08
|
||||
|
||||
#define ADDR_CTRL_REG0 0x0D
|
||||
#define REG0_WRITE_ENABLE 0x10
|
||||
|
||||
#define ADDR_RESET 0x10
|
||||
#define SOFT_RESET 0xB6
|
||||
|
||||
#define ADDR_BW_TCS 0x20
|
||||
#define BW_TCS_BW_MASK (0xf<<4)
|
||||
#define BW_TCS_BW_10HZ (0<<4)
|
||||
#define BW_TCS_BW_20HZ (1<<4)
|
||||
#define BW_TCS_BW_40HZ (2<<4)
|
||||
#define BW_TCS_BW_75HZ (3<<4)
|
||||
#define BW_TCS_BW_150HZ (4<<4)
|
||||
#define BW_TCS_BW_300HZ (5<<4)
|
||||
#define BW_TCS_BW_600HZ (6<<4)
|
||||
#define BW_TCS_BW_1200HZ (7<<4)
|
||||
|
||||
#define ADDR_HIGH_DUR 0x27
|
||||
#define HIGH_DUR_DIS_I2C (1<<0)
|
||||
|
||||
#define ADDR_TCO_Z 0x30
|
||||
#define TCO_Z_MODE_MASK 0x3
|
||||
|
||||
#define ADDR_GAIN_Y 0x33
|
||||
#define GAIN_Y_SHADOW_DIS (1<<0)
|
||||
|
||||
#define ADDR_OFFSET_LSB1 0x35
|
||||
#define OFFSET_LSB1_RANGE_MASK (7<<1)
|
||||
#define OFFSET_LSB1_RANGE_1G (0<<1)
|
||||
#define OFFSET_LSB1_RANGE_2G (2<<1)
|
||||
#define OFFSET_LSB1_RANGE_3G (3<<1)
|
||||
#define OFFSET_LSB1_RANGE_4G (4<<1)
|
||||
#define OFFSET_LSB1_RANGE_8G (5<<1)
|
||||
#define OFFSET_LSB1_RANGE_16G (6<<1)
|
||||
|
||||
#define ADDR_OFFSET_T 0x37
|
||||
#define OFFSET_T_READOUT_12BIT (1<<0)
|
||||
|
||||
extern "C" { __EXPORT int bma180_main(int argc, char *argv[]); }
|
||||
|
||||
class BMA180 : public device::SPI
|
||||
{
|
||||
public:
|
||||
BMA180(int bus, spi_dev_e device);
|
||||
virtual ~BMA180();
|
||||
|
||||
virtual int init();
|
||||
|
||||
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
|
||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Diagnostics - print some basic information about the driver.
|
||||
*/
|
||||
void print_info();
|
||||
|
||||
protected:
|
||||
virtual int probe();
|
||||
|
||||
private:
|
||||
|
||||
struct hrt_call _call;
|
||||
unsigned _call_interval;
|
||||
|
||||
unsigned _num_reports;
|
||||
volatile unsigned _next_report;
|
||||
volatile unsigned _oldest_report;
|
||||
struct accel_report *_reports;
|
||||
|
||||
struct accel_scale _accel_scale;
|
||||
float _accel_range_scale;
|
||||
float _accel_range_m_s2;
|
||||
orb_advert_t _accel_topic;
|
||||
|
||||
unsigned _current_lowpass;
|
||||
unsigned _current_range;
|
||||
|
||||
perf_counter_t _sample_perf;
|
||||
|
||||
/**
|
||||
* Start automatic measurement.
|
||||
*/
|
||||
void start();
|
||||
|
||||
/**
|
||||
* Stop automatic measurement.
|
||||
*/
|
||||
void stop();
|
||||
|
||||
/**
|
||||
* Static trampoline from the hrt_call context; because we don't have a
|
||||
* generic hrt wrapper yet.
|
||||
*
|
||||
* Called by the HRT in interrupt context at the specified rate if
|
||||
* automatic polling is enabled.
|
||||
*
|
||||
* @param arg Instance pointer for the driver that is polling.
|
||||
*/
|
||||
static void measure_trampoline(void *arg);
|
||||
|
||||
/**
|
||||
* Fetch measurements from the sensor and update the report ring.
|
||||
*/
|
||||
void measure();
|
||||
|
||||
/**
|
||||
* Read a register from the BMA180
|
||||
*
|
||||
* @param The register to read.
|
||||
* @return The value that was read.
|
||||
*/
|
||||
uint8_t read_reg(unsigned reg);
|
||||
|
||||
/**
|
||||
* Write a register in the BMA180
|
||||
*
|
||||
* @param reg The register to write.
|
||||
* @param value The new value to write.
|
||||
*/
|
||||
void write_reg(unsigned reg, uint8_t value);
|
||||
|
||||
/**
|
||||
* Modify a register in the BMA180
|
||||
*
|
||||
* Bits are cleared before bits are set.
|
||||
*
|
||||
* @param reg The register to modify.
|
||||
* @param clearbits Bits in the register to clear.
|
||||
* @param setbits Bits in the register to set.
|
||||
*/
|
||||
void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
|
||||
|
||||
/**
|
||||
* Set the BMA180 measurement range.
|
||||
*
|
||||
* @param max_g The maximum G value the range must support.
|
||||
* @return OK if the value can be supported, -ERANGE otherwise.
|
||||
*/
|
||||
int set_range(unsigned max_g);
|
||||
|
||||
/**
|
||||
* Set the BMA180 internal lowpass filter frequency.
|
||||
*
|
||||
* @param frequency The internal lowpass filter frequency is set to a value
|
||||
* equal or greater to this.
|
||||
* Zero selects the highest frequency supported.
|
||||
* @return OK if the value can be supported.
|
||||
*/
|
||||
int set_lowpass(unsigned frequency);
|
||||
};
|
||||
|
||||
/* helper macro for handling report buffer indices */
|
||||
#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
|
||||
|
||||
|
||||
BMA180::BMA180(int bus, spi_dev_e device) :
|
||||
SPI("BMA180", ACCEL_DEVICE_PATH, bus, device, SPIDEV_MODE3, 8000000),
|
||||
_call_interval(0),
|
||||
_num_reports(0),
|
||||
_next_report(0),
|
||||
_oldest_report(0),
|
||||
_reports(nullptr),
|
||||
_accel_range_scale(0.0f),
|
||||
_accel_range_m_s2(0.0f),
|
||||
_accel_topic(-1),
|
||||
_current_lowpass(0),
|
||||
_current_range(0),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "bma180_read"))
|
||||
{
|
||||
// enable debug() calls
|
||||
_debug_enabled = true;
|
||||
|
||||
// default scale factors
|
||||
_accel_scale.x_offset = 0;
|
||||
_accel_scale.x_scale = 1.0f;
|
||||
_accel_scale.y_offset = 0;
|
||||
_accel_scale.y_scale = 1.0f;
|
||||
_accel_scale.z_offset = 0;
|
||||
_accel_scale.z_scale = 1.0f;
|
||||
}
|
||||
|
||||
BMA180::~BMA180()
|
||||
{
|
||||
/* make sure we are truly inactive */
|
||||
stop();
|
||||
|
||||
/* free any existing reports */
|
||||
if (_reports != nullptr)
|
||||
delete[] _reports;
|
||||
|
||||
/* delete the perf counter */
|
||||
perf_free(_sample_perf);
|
||||
}
|
||||
|
||||
int
|
||||
BMA180::init()
|
||||
{
|
||||
int ret = ERROR;
|
||||
|
||||
/* do SPI init (and probe) first */
|
||||
if (SPI::init() != OK)
|
||||
goto out;
|
||||
|
||||
/* allocate basic report buffers */
|
||||
_num_reports = 2;
|
||||
_oldest_report = _next_report = 0;
|
||||
_reports = new struct accel_report[_num_reports];
|
||||
|
||||
if (_reports == nullptr)
|
||||
goto out;
|
||||
|
||||
/* advertise sensor topic */
|
||||
memset(&_reports[0], 0, sizeof(_reports[0]));
|
||||
_accel_topic = orb_advertise(ORB_ID(sensor_accel), &_reports[0]);
|
||||
|
||||
/* perform soft reset (p48) */
|
||||
write_reg(ADDR_RESET, SOFT_RESET);
|
||||
|
||||
/* wait 10 ms (datasheet incorrectly lists 10 us on page 49) */
|
||||
usleep(10000);
|
||||
|
||||
/* enable writing to chip config */
|
||||
modify_reg(ADDR_CTRL_REG0, 0, REG0_WRITE_ENABLE);
|
||||
|
||||
/* disable I2C interface */
|
||||
modify_reg(ADDR_HIGH_DUR, HIGH_DUR_DIS_I2C, 0);
|
||||
|
||||
/* switch to low-noise mode */
|
||||
modify_reg(ADDR_TCO_Z, TCO_Z_MODE_MASK, 0);
|
||||
|
||||
/* disable 12-bit mode */
|
||||
modify_reg(ADDR_OFFSET_T, OFFSET_T_READOUT_12BIT, 0);
|
||||
|
||||
/* disable shadow-disable mode */
|
||||
modify_reg(ADDR_GAIN_Y, GAIN_Y_SHADOW_DIS, 0);
|
||||
|
||||
/* disable writing to chip config */
|
||||
modify_reg(ADDR_CTRL_REG0, REG0_WRITE_ENABLE, 0);
|
||||
|
||||
if (set_range(4)) warnx("Failed setting range");
|
||||
|
||||
if (set_lowpass(75)) warnx("Failed setting lowpass");
|
||||
|
||||
if (read_reg(ADDR_CHIP_ID) == CHIP_ID) {
|
||||
ret = OK;
|
||||
|
||||
} else {
|
||||
ret = ERROR;
|
||||
}
|
||||
|
||||
out:
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
BMA180::probe()
|
||||
{
|
||||
/* dummy read to ensure SPI state machine is sane */
|
||||
read_reg(ADDR_CHIP_ID);
|
||||
|
||||
if (read_reg(ADDR_CHIP_ID) == CHIP_ID)
|
||||
return OK;
|
||||
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
ssize_t
|
||||
BMA180::read(struct file *filp, char *buffer, size_t buflen)
|
||||
{
|
||||
unsigned count = buflen / sizeof(struct accel_report);
|
||||
int ret = 0;
|
||||
|
||||
/* buffer must be large enough */
|
||||
if (count < 1)
|
||||
return -ENOSPC;
|
||||
|
||||
/* if automatic measurement is enabled */
|
||||
if (_call_interval > 0) {
|
||||
|
||||
/*
|
||||
* While there is space in the caller's buffer, and reports, copy them.
|
||||
* Note that we may be pre-empted by the measurement code while we are doing this;
|
||||
* we are careful to avoid racing with it.
|
||||
*/
|
||||
while (count--) {
|
||||
if (_oldest_report != _next_report) {
|
||||
memcpy(buffer, _reports + _oldest_report, sizeof(*_reports));
|
||||
ret += sizeof(_reports[0]);
|
||||
INCREMENT(_oldest_report, _num_reports);
|
||||
}
|
||||
}
|
||||
|
||||
/* if there was no data, warn the caller */
|
||||
return ret ? ret : -EAGAIN;
|
||||
}
|
||||
|
||||
/* manual measurement */
|
||||
_oldest_report = _next_report = 0;
|
||||
measure();
|
||||
|
||||
/* measurement will have generated a report, copy it out */
|
||||
memcpy(buffer, _reports, sizeof(*_reports));
|
||||
ret = sizeof(*_reports);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
BMA180::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
switch (cmd) {
|
||||
|
||||
case SENSORIOCSPOLLRATE: {
|
||||
switch (arg) {
|
||||
|
||||
/* switching to manual polling */
|
||||
case SENSOR_POLLRATE_MANUAL:
|
||||
stop();
|
||||
_call_interval = 0;
|
||||
return OK;
|
||||
|
||||
/* external signalling not supported */
|
||||
case SENSOR_POLLRATE_EXTERNAL:
|
||||
|
||||
/* zero would be bad */
|
||||
case 0:
|
||||
return -EINVAL;
|
||||
|
||||
|
||||
/* set default/max polling rate */
|
||||
case SENSOR_POLLRATE_MAX:
|
||||
case SENSOR_POLLRATE_DEFAULT:
|
||||
/* With internal low pass filters enabled, 250 Hz is sufficient */
|
||||
return ioctl(filp, SENSORIOCSPOLLRATE, 250);
|
||||
|
||||
/* adjust to a legal polling interval in Hz */
|
||||
default: {
|
||||
/* do we need to start internal polling? */
|
||||
bool want_start = (_call_interval == 0);
|
||||
|
||||
/* convert hz to hrt interval via microseconds */
|
||||
unsigned ticks = 1000000 / arg;
|
||||
|
||||
/* check against maximum sane rate */
|
||||
if (ticks < 1000)
|
||||
return -EINVAL;
|
||||
|
||||
/* update interval for next measurement */
|
||||
/* XXX this is a bit shady, but no other way to adjust... */
|
||||
_call.period = _call_interval = ticks;
|
||||
|
||||
/* if we need to start the poll state machine, do it */
|
||||
if (want_start)
|
||||
start();
|
||||
|
||||
return OK;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
case SENSORIOCGPOLLRATE:
|
||||
if (_call_interval == 0)
|
||||
return SENSOR_POLLRATE_MANUAL;
|
||||
|
||||
return 1000000 / _call_interval;
|
||||
|
||||
case SENSORIOCSQUEUEDEPTH: {
|
||||
/* account for sentinel in the ring */
|
||||
arg++;
|
||||
|
||||
/* lower bound is mandatory, upper bound is a sanity check */
|
||||
if ((arg < 2) || (arg > 100))
|
||||
return -EINVAL;
|
||||
|
||||
/* allocate new buffer */
|
||||
struct accel_report *buf = new struct accel_report[arg];
|
||||
|
||||
if (nullptr == buf)
|
||||
return -ENOMEM;
|
||||
|
||||
/* reset the measurement state machine with the new buffer, free the old */
|
||||
stop();
|
||||
delete[] _reports;
|
||||
_num_reports = arg;
|
||||
_reports = buf;
|
||||
start();
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
case SENSORIOCGQUEUEDEPTH:
|
||||
return _num_reports - 1;
|
||||
|
||||
case SENSORIOCRESET:
|
||||
/* XXX implement */
|
||||
return -EINVAL;
|
||||
|
||||
case ACCELIOCSSAMPLERATE: /* sensor sample rate is not (really) adjustable */
|
||||
return -EINVAL;
|
||||
|
||||
case ACCELIOCGSAMPLERATE:
|
||||
return 1200; /* always operating in low-noise mode */
|
||||
|
||||
case ACCELIOCSLOWPASS:
|
||||
return set_lowpass(arg);
|
||||
|
||||
case ACCELIOCGLOWPASS:
|
||||
return _current_lowpass;
|
||||
|
||||
case ACCELIOCSSCALE:
|
||||
/* copy scale in */
|
||||
memcpy(&_accel_scale, (struct accel_scale *) arg, sizeof(_accel_scale));
|
||||
return OK;
|
||||
|
||||
case ACCELIOCGSCALE:
|
||||
/* copy scale out */
|
||||
memcpy((struct accel_scale *) arg, &_accel_scale, sizeof(_accel_scale));
|
||||
return OK;
|
||||
|
||||
case ACCELIOCSRANGE:
|
||||
return set_range(arg);
|
||||
|
||||
case ACCELIOCGRANGE:
|
||||
return _current_range;
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return SPI::ioctl(filp, cmd, arg);
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t
|
||||
BMA180::read_reg(unsigned reg)
|
||||
{
|
||||
uint8_t cmd[2];
|
||||
|
||||
cmd[0] = reg | DIR_READ;
|
||||
|
||||
transfer(cmd, cmd, sizeof(cmd));
|
||||
|
||||
return cmd[1];
|
||||
}
|
||||
|
||||
void
|
||||
BMA180::write_reg(unsigned reg, uint8_t value)
|
||||
{
|
||||
uint8_t cmd[2];
|
||||
|
||||
cmd[0] = reg | DIR_WRITE;
|
||||
cmd[1] = value;
|
||||
|
||||
transfer(cmd, nullptr, sizeof(cmd));
|
||||
}
|
||||
|
||||
void
|
||||
BMA180::modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
|
||||
{
|
||||
uint8_t val;
|
||||
|
||||
val = read_reg(reg);
|
||||
val &= ~clearbits;
|
||||
val |= setbits;
|
||||
write_reg(reg, val);
|
||||
}
|
||||
|
||||
int
|
||||
BMA180::set_range(unsigned max_g)
|
||||
{
|
||||
uint8_t rangebits;
|
||||
|
||||
if (max_g == 0)
|
||||
max_g = 16;
|
||||
|
||||
if (max_g > 16)
|
||||
return -ERANGE;
|
||||
|
||||
if (max_g <= 2) {
|
||||
_current_range = 2;
|
||||
rangebits = OFFSET_LSB1_RANGE_2G;
|
||||
|
||||
} else if (max_g <= 3) {
|
||||
_current_range = 3;
|
||||
rangebits = OFFSET_LSB1_RANGE_3G;
|
||||
|
||||
} else if (max_g <= 4) {
|
||||
_current_range = 4;
|
||||
rangebits = OFFSET_LSB1_RANGE_4G;
|
||||
|
||||
} else if (max_g <= 8) {
|
||||
_current_range = 8;
|
||||
rangebits = OFFSET_LSB1_RANGE_8G;
|
||||
|
||||
} else if (max_g <= 16) {
|
||||
_current_range = 16;
|
||||
rangebits = OFFSET_LSB1_RANGE_16G;
|
||||
|
||||
} else {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
/* set new range scaling factor */
|
||||
_accel_range_m_s2 = _current_range * 9.80665f;
|
||||
_accel_range_scale = _accel_range_m_s2 / 8192.0f;
|
||||
|
||||
/* enable writing to chip config */
|
||||
modify_reg(ADDR_CTRL_REG0, 0, REG0_WRITE_ENABLE);
|
||||
|
||||
/* adjust sensor configuration */
|
||||
modify_reg(ADDR_OFFSET_LSB1, OFFSET_LSB1_RANGE_MASK, rangebits);
|
||||
|
||||
/* block writing to chip config */
|
||||
modify_reg(ADDR_CTRL_REG0, REG0_WRITE_ENABLE, 0);
|
||||
|
||||
/* check if wanted value is now in register */
|
||||
return !((read_reg(ADDR_OFFSET_LSB1) & OFFSET_LSB1_RANGE_MASK) ==
|
||||
(OFFSET_LSB1_RANGE_MASK & rangebits));
|
||||
}
|
||||
|
||||
int
|
||||
BMA180::set_lowpass(unsigned frequency)
|
||||
{
|
||||
uint8_t bwbits;
|
||||
|
||||
if (frequency > 1200) {
|
||||
return -ERANGE;
|
||||
|
||||
} else if (frequency > 600) {
|
||||
bwbits = BW_TCS_BW_1200HZ;
|
||||
|
||||
} else if (frequency > 300) {
|
||||
bwbits = BW_TCS_BW_600HZ;
|
||||
|
||||
} else if (frequency > 150) {
|
||||
bwbits = BW_TCS_BW_300HZ;
|
||||
|
||||
} else if (frequency > 75) {
|
||||
bwbits = BW_TCS_BW_150HZ;
|
||||
|
||||
} else if (frequency > 40) {
|
||||
bwbits = BW_TCS_BW_75HZ;
|
||||
|
||||
} else if (frequency > 20) {
|
||||
bwbits = BW_TCS_BW_40HZ;
|
||||
|
||||
} else if (frequency > 10) {
|
||||
bwbits = BW_TCS_BW_20HZ;
|
||||
|
||||
} else {
|
||||
bwbits = BW_TCS_BW_10HZ;
|
||||
}
|
||||
|
||||
/* enable writing to chip config */
|
||||
modify_reg(ADDR_CTRL_REG0, 0, REG0_WRITE_ENABLE);
|
||||
|
||||
/* adjust sensor configuration */
|
||||
modify_reg(ADDR_BW_TCS, BW_TCS_BW_MASK, bwbits);
|
||||
|
||||
/* block writing to chip config */
|
||||
modify_reg(ADDR_CTRL_REG0, REG0_WRITE_ENABLE, 0);
|
||||
|
||||
/* check if wanted value is now in register */
|
||||
return !((read_reg(ADDR_BW_TCS) & BW_TCS_BW_MASK) ==
|
||||
(BW_TCS_BW_MASK & bwbits));
|
||||
}
|
||||
|
||||
void
|
||||
BMA180::start()
|
||||
{
|
||||
/* make sure we are stopped first */
|
||||
stop();
|
||||
|
||||
/* reset the report ring */
|
||||
_oldest_report = _next_report = 0;
|
||||
|
||||
/* start polling at the specified rate */
|
||||
hrt_call_every(&_call, 1000, _call_interval, (hrt_callout)&BMA180::measure_trampoline, this);
|
||||
}
|
||||
|
||||
void
|
||||
BMA180::stop()
|
||||
{
|
||||
hrt_cancel(&_call);
|
||||
}
|
||||
|
||||
void
|
||||
BMA180::measure_trampoline(void *arg)
|
||||
{
|
||||
BMA180 *dev = (BMA180 *)arg;
|
||||
|
||||
/* make another measurement */
|
||||
dev->measure();
|
||||
}
|
||||
|
||||
void
|
||||
BMA180::measure()
|
||||
{
|
||||
/* BMA180 measurement registers */
|
||||
// #pragma pack(push, 1)
|
||||
// struct {
|
||||
// uint8_t cmd;
|
||||
// int16_t x;
|
||||
// int16_t y;
|
||||
// int16_t z;
|
||||
// } raw_report;
|
||||
// #pragma pack(pop)
|
||||
|
||||
accel_report *report = &_reports[_next_report];
|
||||
|
||||
/* start the performance counter */
|
||||
perf_begin(_sample_perf);
|
||||
|
||||
/*
|
||||
* Fetch the full set of measurements from the BMA180 in one pass;
|
||||
* starting from the X LSB.
|
||||
*/
|
||||
//raw_report.cmd = ADDR_ACC_X_LSB;
|
||||
// XXX PX4DEV transfer((uint8_t *)&raw_report, (uint8_t *)&raw_report, sizeof(raw_report));
|
||||
|
||||
/*
|
||||
* Adjust and scale results to SI units.
|
||||
*
|
||||
* Note that we ignore the "new data" bits. At any time we read, each
|
||||
* of the axis measurements are the "most recent", even if we've seen
|
||||
* them before. There is no good way to synchronise with the internal
|
||||
* measurement flow without using the external interrupt.
|
||||
*/
|
||||
_reports[_next_report].timestamp = hrt_absolute_time();
|
||||
/*
|
||||
* y of board is x of sensor and x of board is -y of sensor
|
||||
* perform only the axis assignment here.
|
||||
* Two non-value bits are discarded directly
|
||||
*/
|
||||
report->y_raw = read_reg(ADDR_ACC_X_LSB + 0);
|
||||
report->y_raw |= read_reg(ADDR_ACC_X_LSB + 1) << 8;
|
||||
report->x_raw = read_reg(ADDR_ACC_X_LSB + 2);
|
||||
report->x_raw |= read_reg(ADDR_ACC_X_LSB + 3) << 8;
|
||||
report->z_raw = read_reg(ADDR_ACC_X_LSB + 4);
|
||||
report->z_raw |= read_reg(ADDR_ACC_X_LSB + 5) << 8;
|
||||
|
||||
/* discard two non-value bits in the 16 bit measurement */
|
||||
report->x_raw = (report->x_raw / 4);
|
||||
report->y_raw = (report->y_raw / 4);
|
||||
report->z_raw = (report->z_raw / 4);
|
||||
|
||||
/* invert y axis, due to 14 bit data no overflow can occur in the negation */
|
||||
report->y_raw = -report->y_raw;
|
||||
|
||||
report->x = ((report->x_raw * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
|
||||
report->y = ((report->y_raw * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
|
||||
report->z = ((report->z_raw * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
|
||||
report->scaling = _accel_range_scale;
|
||||
report->range_m_s2 = _accel_range_m_s2;
|
||||
|
||||
/* post a report to the ring - note, not locked */
|
||||
INCREMENT(_next_report, _num_reports);
|
||||
|
||||
/* if we are running up against the oldest report, fix it */
|
||||
if (_next_report == _oldest_report)
|
||||
INCREMENT(_oldest_report, _num_reports);
|
||||
|
||||
/* notify anyone waiting for data */
|
||||
poll_notify(POLLIN);
|
||||
|
||||
/* publish for subscribers */
|
||||
orb_publish(ORB_ID(sensor_accel), _accel_topic, report);
|
||||
|
||||
/* stop the perf counter */
|
||||
perf_end(_sample_perf);
|
||||
}
|
||||
|
||||
void
|
||||
BMA180::print_info()
|
||||
{
|
||||
perf_print_counter(_sample_perf);
|
||||
printf("report queue: %u (%u/%u @ %p)\n",
|
||||
_num_reports, _oldest_report, _next_report, _reports);
|
||||
}
|
||||
|
||||
/**
|
||||
* Local functions in support of the shell command.
|
||||
*/
|
||||
namespace bma180
|
||||
{
|
||||
|
||||
BMA180 *g_dev;
|
||||
|
||||
void start();
|
||||
void test();
|
||||
void reset();
|
||||
void info();
|
||||
|
||||
/**
|
||||
* Start the driver.
|
||||
*/
|
||||
void
|
||||
start()
|
||||
{
|
||||
int fd;
|
||||
|
||||
if (g_dev != nullptr)
|
||||
errx(1, "already started");
|
||||
|
||||
/* create the driver */
|
||||
g_dev = new BMA180(1 /* XXX magic number */, (spi_dev_e)PX4_SPIDEV_ACCEL);
|
||||
|
||||
if (g_dev == nullptr)
|
||||
goto fail;
|
||||
|
||||
if (OK != g_dev->init())
|
||||
goto fail;
|
||||
|
||||
/* set the poll rate to default, starts automatic data collection */
|
||||
fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0)
|
||||
goto fail;
|
||||
|
||||
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
|
||||
goto fail;
|
||||
|
||||
exit(0);
|
||||
fail:
|
||||
|
||||
if (g_dev != nullptr) {
|
||||
delete g_dev;
|
||||
g_dev = nullptr;
|
||||
}
|
||||
|
||||
errx(1, "driver start failed");
|
||||
}
|
||||
|
||||
/**
|
||||
* Perform some basic functional tests on the driver;
|
||||
* make sure we can collect data from the sensor in polled
|
||||
* and automatic modes.
|
||||
*/
|
||||
void
|
||||
test()
|
||||
{
|
||||
int fd = -1;
|
||||
struct accel_report a_report;
|
||||
ssize_t sz;
|
||||
|
||||
/* get the driver */
|
||||
fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0)
|
||||
err(1, "%s open failed (try 'bma180 start' if the driver is not running)",
|
||||
ACCEL_DEVICE_PATH);
|
||||
|
||||
/* reset to manual polling */
|
||||
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MANUAL) < 0)
|
||||
err(1, "reset to manual polling");
|
||||
|
||||
/* do a simple demand read */
|
||||
sz = read(fd, &a_report, sizeof(a_report));
|
||||
|
||||
if (sz != sizeof(a_report))
|
||||
err(1, "immediate acc read failed");
|
||||
|
||||
warnx("single read");
|
||||
warnx("time: %lld", a_report.timestamp);
|
||||
warnx("acc x: \t%8.4f\tm/s^2", (double)a_report.x);
|
||||
warnx("acc y: \t%8.4f\tm/s^2", (double)a_report.y);
|
||||
warnx("acc z: \t%8.4f\tm/s^2", (double)a_report.z);
|
||||
warnx("acc x: \t%d\traw 0x%0x", (short)a_report.x_raw, (unsigned short)a_report.x_raw);
|
||||
warnx("acc y: \t%d\traw 0x%0x", (short)a_report.y_raw, (unsigned short)a_report.y_raw);
|
||||
warnx("acc z: \t%d\traw 0x%0x", (short)a_report.z_raw, (unsigned short)a_report.z_raw);
|
||||
warnx("acc range: %8.4f m/s^2 (%8.4f g)", (double)a_report.range_m_s2,
|
||||
(double)(a_report.range_m_s2 / 9.81f));
|
||||
|
||||
/* XXX add poll-rate tests here too */
|
||||
|
||||
reset();
|
||||
errx(0, "PASS");
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the driver.
|
||||
*/
|
||||
void
|
||||
reset()
|
||||
{
|
||||
int fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0)
|
||||
err(1, "failed ");
|
||||
|
||||
if (ioctl(fd, SENSORIOCRESET, 0) < 0)
|
||||
err(1, "driver reset failed");
|
||||
|
||||
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
|
||||
err(1, "driver poll restart failed");
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Print a little info about the driver.
|
||||
*/
|
||||
void
|
||||
info()
|
||||
{
|
||||
if (g_dev == nullptr)
|
||||
errx(1, "BMA180: driver not running");
|
||||
|
||||
printf("state @ %p\n", g_dev);
|
||||
g_dev->print_info();
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
||||
} // namespace
|
||||
|
||||
int
|
||||
bma180_main(int argc, char *argv[])
|
||||
{
|
||||
/*
|
||||
* Start/load the driver.
|
||||
|
||||
*/
|
||||
if (!strcmp(argv[1], "start"))
|
||||
bma180::start();
|
||||
|
||||
/*
|
||||
* Test the driver/device.
|
||||
*/
|
||||
if (!strcmp(argv[1], "test"))
|
||||
bma180::test();
|
||||
|
||||
/*
|
||||
* Reset the driver.
|
||||
*/
|
||||
if (!strcmp(argv[1], "reset"))
|
||||
bma180::reset();
|
||||
|
||||
/*
|
||||
* Print driver information.
|
||||
*/
|
||||
if (!strcmp(argv[1], "info"))
|
||||
bma180::info();
|
||||
|
||||
errx(1, "unrecognised command, try 'start', 'test', 'reset' or 'info'");
|
||||
}
|
||||
@@ -0,0 +1,40 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Makefile to build the BMA180 driver.
|
||||
#
|
||||
|
||||
MODULE_COMMAND = bma180
|
||||
|
||||
SRCS = bma180.cpp
|
||||
@@ -0,0 +1,536 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file gps.cpp
|
||||
* Driver for the GPS on a serial port
|
||||
*/
|
||||
|
||||
#include <nuttx/clock.h>
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
#include <semaphore.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/scheduling_priorities.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <drivers/drv_gps.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
|
||||
#include "ubx.h"
|
||||
#include "mtk.h"
|
||||
|
||||
|
||||
#define TIMEOUT_5HZ 500
|
||||
#define RATE_MEASUREMENT_PERIOD 5000000
|
||||
|
||||
/* oddly, ERROR is not defined for c++ */
|
||||
#ifdef ERROR
|
||||
# undef ERROR
|
||||
#endif
|
||||
static const int ERROR = -1;
|
||||
|
||||
#ifndef CONFIG_SCHED_WORKQUEUE
|
||||
# error This requires CONFIG_SCHED_WORKQUEUE.
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
class GPS : public device::CDev
|
||||
{
|
||||
public:
|
||||
GPS(const char* uart_path);
|
||||
virtual ~GPS();
|
||||
|
||||
virtual int init();
|
||||
|
||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Diagnostics - print some basic information about the driver.
|
||||
*/
|
||||
void print_info();
|
||||
|
||||
private:
|
||||
|
||||
bool _task_should_exit; ///< flag to make the main worker task exit
|
||||
int _serial_fd; ///< serial interface to GPS
|
||||
unsigned _baudrate; ///< current baudrate
|
||||
char _port[20]; ///< device / serial port path
|
||||
volatile int _task; //< worker task
|
||||
bool _healthy; ///< flag to signal if the GPS is ok
|
||||
bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed
|
||||
bool _mode_changed; ///< flag that the GPS mode has changed
|
||||
gps_driver_mode_t _mode; ///< current mode
|
||||
GPS_Helper *_Helper; ///< instance of GPS parser
|
||||
struct vehicle_gps_position_s _report; ///< uORB topic for gps position
|
||||
orb_advert_t _report_pub; ///< uORB pub for gps position
|
||||
float _rate; ///< position update rate
|
||||
|
||||
|
||||
/**
|
||||
* Try to configure the GPS, handle outgoing communication to the GPS
|
||||
*/
|
||||
void config();
|
||||
|
||||
/**
|
||||
* Trampoline to the worker task
|
||||
*/
|
||||
static void task_main_trampoline(void *arg);
|
||||
|
||||
|
||||
/**
|
||||
* Worker task: main GPS thread that configures the GPS and parses incoming data, always running
|
||||
*/
|
||||
void task_main(void);
|
||||
|
||||
/**
|
||||
* Set the baudrate of the UART to the GPS
|
||||
*/
|
||||
int set_baudrate(unsigned baud);
|
||||
|
||||
/**
|
||||
* Send a reset command to the GPS
|
||||
*/
|
||||
void cmd_reset();
|
||||
|
||||
};
|
||||
|
||||
|
||||
/*
|
||||
* Driver 'main' command.
|
||||
*/
|
||||
extern "C" __EXPORT int gps_main(int argc, char *argv[]);
|
||||
|
||||
namespace
|
||||
{
|
||||
|
||||
GPS *g_dev;
|
||||
|
||||
}
|
||||
|
||||
|
||||
GPS::GPS(const char* uart_path) :
|
||||
CDev("gps", GPS_DEVICE_PATH),
|
||||
_task_should_exit(false),
|
||||
_healthy(false),
|
||||
_mode_changed(false),
|
||||
_mode(GPS_DRIVER_MODE_UBX),
|
||||
_Helper(nullptr),
|
||||
_report_pub(-1),
|
||||
_rate(0.0f)
|
||||
{
|
||||
/* store port name */
|
||||
strncpy(_port, uart_path, sizeof(_port));
|
||||
/* enforce null termination */
|
||||
_port[sizeof(_port) - 1] = '\0';
|
||||
|
||||
/* we need this potentially before it could be set in task_main */
|
||||
g_dev = this;
|
||||
memset(&_report, 0, sizeof(_report));
|
||||
|
||||
_debug_enabled = true;
|
||||
}
|
||||
|
||||
GPS::~GPS()
|
||||
{
|
||||
/* tell the task we want it to go away */
|
||||
_task_should_exit = true;
|
||||
|
||||
/* spin waiting for the task to stop */
|
||||
for (unsigned i = 0; (i < 10) && (_task != -1); i++) {
|
||||
/* give it another 100ms */
|
||||
usleep(100000);
|
||||
}
|
||||
|
||||
/* well, kill it anyway, though this will probably crash */
|
||||
if (_task != -1)
|
||||
task_delete(_task);
|
||||
g_dev = nullptr;
|
||||
|
||||
}
|
||||
|
||||
int
|
||||
GPS::init()
|
||||
{
|
||||
int ret = ERROR;
|
||||
|
||||
/* do regular cdev init */
|
||||
if (CDev::init() != OK)
|
||||
goto out;
|
||||
|
||||
/* start the GPS driver worker task */
|
||||
_task = task_create("gps", SCHED_PRIORITY_SLOW_DRIVER, 2048, (main_t)&GPS::task_main_trampoline, nullptr);
|
||||
|
||||
if (_task < 0) {
|
||||
warnx("task start failed: %d", errno);
|
||||
return -errno;
|
||||
}
|
||||
|
||||
ret = OK;
|
||||
out:
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
GPS::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
lock();
|
||||
|
||||
int ret = OK;
|
||||
|
||||
switch (cmd) {
|
||||
case SENSORIOCRESET:
|
||||
cmd_reset();
|
||||
break;
|
||||
}
|
||||
|
||||
unlock();
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void
|
||||
GPS::task_main_trampoline(void *arg)
|
||||
{
|
||||
g_dev->task_main();
|
||||
}
|
||||
|
||||
void
|
||||
GPS::task_main()
|
||||
{
|
||||
log("starting");
|
||||
|
||||
/* open the serial port */
|
||||
_serial_fd = ::open(_port, O_RDWR);
|
||||
|
||||
if (_serial_fd < 0) {
|
||||
log("failed to open serial port: %s err: %d", _port, errno);
|
||||
/* tell the dtor that we are exiting, set error code */
|
||||
_task = -1;
|
||||
_exit(1);
|
||||
}
|
||||
|
||||
uint64_t last_rate_measurement = hrt_absolute_time();
|
||||
unsigned last_rate_count = 0;
|
||||
|
||||
/* loop handling received serial bytes and also configuring in between */
|
||||
while (!_task_should_exit) {
|
||||
|
||||
if (_Helper != nullptr) {
|
||||
delete(_Helper);
|
||||
/* set to zero to ensure parser is not used while not instantiated */
|
||||
_Helper = nullptr;
|
||||
}
|
||||
|
||||
switch (_mode) {
|
||||
case GPS_DRIVER_MODE_UBX:
|
||||
_Helper = new UBX(_serial_fd, &_report);
|
||||
break;
|
||||
case GPS_DRIVER_MODE_MTK:
|
||||
_Helper = new MTK(_serial_fd, &_report);
|
||||
break;
|
||||
case GPS_DRIVER_MODE_NMEA:
|
||||
//_Helper = new NMEA(); //TODO: add NMEA
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
unlock();
|
||||
if (_Helper->configure(_baudrate) == 0) {
|
||||
unlock();
|
||||
while (_Helper->receive(TIMEOUT_5HZ) > 0 && !_task_should_exit) {
|
||||
// lock();
|
||||
/* opportunistic publishing - else invalid data would end up on the bus */
|
||||
if (_report_pub > 0) {
|
||||
orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
|
||||
} else {
|
||||
_report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
|
||||
}
|
||||
|
||||
last_rate_count++;
|
||||
|
||||
/* measure update rate every 5 seconds */
|
||||
if (hrt_absolute_time() - last_rate_measurement > RATE_MEASUREMENT_PERIOD) {
|
||||
_rate = last_rate_count / ((float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f);
|
||||
last_rate_measurement = hrt_absolute_time();
|
||||
last_rate_count = 0;
|
||||
}
|
||||
|
||||
if (!_healthy) {
|
||||
warnx("module found");
|
||||
_healthy = true;
|
||||
}
|
||||
}
|
||||
if (_healthy) {
|
||||
warnx("module lost");
|
||||
_healthy = false;
|
||||
_rate = 0.0f;
|
||||
}
|
||||
|
||||
lock();
|
||||
}
|
||||
lock();
|
||||
|
||||
/* select next mode */
|
||||
switch (_mode) {
|
||||
case GPS_DRIVER_MODE_UBX:
|
||||
_mode = GPS_DRIVER_MODE_MTK;
|
||||
break;
|
||||
case GPS_DRIVER_MODE_MTK:
|
||||
_mode = GPS_DRIVER_MODE_UBX;
|
||||
break;
|
||||
// case GPS_DRIVER_MODE_NMEA:
|
||||
// _mode = GPS_DRIVER_MODE_UBX;
|
||||
// break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
}
|
||||
debug("exiting");
|
||||
|
||||
::close(_serial_fd);
|
||||
|
||||
/* tell the dtor that we are exiting */
|
||||
_task = -1;
|
||||
_exit(0);
|
||||
}
|
||||
|
||||
|
||||
|
||||
void
|
||||
GPS::cmd_reset()
|
||||
{
|
||||
//XXX add reset?
|
||||
}
|
||||
|
||||
void
|
||||
GPS::print_info()
|
||||
{
|
||||
switch (_mode) {
|
||||
case GPS_DRIVER_MODE_UBX:
|
||||
warnx("protocol: UBX");
|
||||
break;
|
||||
case GPS_DRIVER_MODE_MTK:
|
||||
warnx("protocol: MTK");
|
||||
break;
|
||||
case GPS_DRIVER_MODE_NMEA:
|
||||
warnx("protocol: NMEA");
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_healthy) ? "OK" : "NOT OK");
|
||||
if (_report.timestamp_position != 0) {
|
||||
warnx("position lock: %dD, last update %4.2f seconds ago", (int)_report.fix_type,
|
||||
(double)((float)(hrt_absolute_time() - _report.timestamp_position) / 1000000.0f));
|
||||
warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt);
|
||||
warnx("update rate: %6.2f Hz", (double)_rate);
|
||||
}
|
||||
|
||||
usleep(100000);
|
||||
}
|
||||
|
||||
/**
|
||||
* Local functions in support of the shell command.
|
||||
*/
|
||||
namespace gps
|
||||
{
|
||||
|
||||
GPS *g_dev;
|
||||
|
||||
void start(const char *uart_path);
|
||||
void stop();
|
||||
void test();
|
||||
void reset();
|
||||
void info();
|
||||
|
||||
/**
|
||||
* Start the driver.
|
||||
*/
|
||||
void
|
||||
start(const char *uart_path)
|
||||
{
|
||||
int fd;
|
||||
|
||||
if (g_dev != nullptr)
|
||||
errx(1, "already started");
|
||||
|
||||
/* create the driver */
|
||||
g_dev = new GPS(uart_path);
|
||||
|
||||
if (g_dev == nullptr)
|
||||
goto fail;
|
||||
|
||||
if (OK != g_dev->init())
|
||||
goto fail;
|
||||
|
||||
/* set the poll rate to default, starts automatic data collection */
|
||||
fd = open(GPS_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
errx(1, "Could not open device path: %s\n", GPS_DEVICE_PATH);
|
||||
goto fail;
|
||||
}
|
||||
exit(0);
|
||||
|
||||
fail:
|
||||
|
||||
if (g_dev != nullptr) {
|
||||
delete g_dev;
|
||||
g_dev = nullptr;
|
||||
}
|
||||
|
||||
errx(1, "driver start failed");
|
||||
}
|
||||
|
||||
/**
|
||||
* Stop the driver.
|
||||
*/
|
||||
void
|
||||
stop()
|
||||
{
|
||||
delete g_dev;
|
||||
g_dev = nullptr;
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Perform some basic functional tests on the driver;
|
||||
* make sure we can collect data from the sensor in polled
|
||||
* and automatic modes.
|
||||
*/
|
||||
void
|
||||
test()
|
||||
{
|
||||
|
||||
errx(0, "PASS");
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the driver.
|
||||
*/
|
||||
void
|
||||
reset()
|
||||
{
|
||||
int fd = open(GPS_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0)
|
||||
err(1, "failed ");
|
||||
|
||||
if (ioctl(fd, SENSORIOCRESET, 0) < 0)
|
||||
err(1, "driver reset failed");
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Print the status of the driver.
|
||||
*/
|
||||
void
|
||||
info()
|
||||
{
|
||||
if (g_dev == nullptr)
|
||||
errx(1, "driver not running");
|
||||
|
||||
g_dev->print_info();
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
|
||||
int
|
||||
gps_main(int argc, char *argv[])
|
||||
{
|
||||
|
||||
/* set to default */
|
||||
char* device_name = GPS_DEFAULT_UART_PORT;
|
||||
|
||||
/*
|
||||
* Start/load the driver.
|
||||
*/
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
/* work around getopt unreliability */
|
||||
if (argc > 3) {
|
||||
if (!strcmp(argv[2], "-d")) {
|
||||
device_name = argv[3];
|
||||
} else {
|
||||
goto out;
|
||||
}
|
||||
}
|
||||
gps::start(device_name);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "stop"))
|
||||
gps::stop();
|
||||
/*
|
||||
* Test the driver/device.
|
||||
*/
|
||||
if (!strcmp(argv[1], "test"))
|
||||
gps::test();
|
||||
|
||||
/*
|
||||
* Reset the driver.
|
||||
*/
|
||||
if (!strcmp(argv[1], "reset"))
|
||||
gps::reset();
|
||||
|
||||
/*
|
||||
* Print driver status.
|
||||
*/
|
||||
if (!strcmp(argv[1], "status"))
|
||||
gps::info();
|
||||
|
||||
out:
|
||||
errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status' [-d /dev/ttyS0-n]");
|
||||
}
|
||||
@@ -0,0 +1,92 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* Julian Oes <joes@student.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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <termios.h>
|
||||
#include <errno.h>
|
||||
#include <systemlib/err.h>
|
||||
#include "gps_helper.h"
|
||||
|
||||
/* @file gps_helper.cpp */
|
||||
|
||||
int
|
||||
GPS_Helper::set_baudrate(const int &fd, unsigned baud)
|
||||
{
|
||||
/* process baud rate */
|
||||
int speed;
|
||||
|
||||
switch (baud) {
|
||||
case 9600: speed = B9600; break;
|
||||
|
||||
case 19200: speed = B19200; break;
|
||||
|
||||
case 38400: speed = B38400; break;
|
||||
|
||||
case 57600: speed = B57600; break;
|
||||
|
||||
case 115200: speed = B115200; break;
|
||||
|
||||
warnx("try baudrate: %d\n", speed);
|
||||
|
||||
default:
|
||||
warnx("ERROR: Unsupported baudrate: %d\n", baud);
|
||||
return -EINVAL;
|
||||
}
|
||||
struct termios uart_config;
|
||||
int termios_state;
|
||||
|
||||
/* fill the struct for the new configuration */
|
||||
tcgetattr(fd, &uart_config);
|
||||
|
||||
/* clear ONLCR flag (which appends a CR for every LF) */
|
||||
uart_config.c_oflag &= ~ONLCR;
|
||||
/* no parity, one stop bit */
|
||||
uart_config.c_cflag &= ~(CSTOPB | PARENB);
|
||||
|
||||
/* set baud rate */
|
||||
if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
|
||||
warnx("ERROR setting config: %d (cfsetispeed)\n", termios_state);
|
||||
return -1;
|
||||
}
|
||||
if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
|
||||
warnx("ERROR setting config: %d (cfsetospeed)\n", termios_state);
|
||||
return -1;
|
||||
}
|
||||
if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) {
|
||||
warnx("ERROR setting baudrate (tcsetattr)\n");
|
||||
return -1;
|
||||
}
|
||||
/* XXX if resetting the parser here, ensure it does exist (check for null pointer) */
|
||||
return 0;
|
||||
}
|
||||
@@ -0,0 +1,52 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* Julian Oes <joes@student.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 gps_helper.h */
|
||||
|
||||
#ifndef GPS_HELPER_H
|
||||
#define GPS_HELPER_H
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
|
||||
class GPS_Helper
|
||||
{
|
||||
public:
|
||||
virtual int configure(unsigned &baud) = 0;
|
||||
virtual int receive(unsigned timeout) = 0;
|
||||
int set_baudrate(const int &fd, unsigned baud);
|
||||
};
|
||||
|
||||
#endif /* GPS_HELPER_H */
|
||||
@@ -0,0 +1,43 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# GPS driver
|
||||
#
|
||||
|
||||
MODULE_COMMAND = gps
|
||||
|
||||
SRCS = gps.cpp \
|
||||
gps_helper.cpp \
|
||||
mtk.cpp \
|
||||
ubx.cpp
|
||||
@@ -0,0 +1,274 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* Julian Oes <joes@student.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 mkt.cpp */
|
||||
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <poll.h>
|
||||
#include <math.h>
|
||||
#include <string.h>
|
||||
#include <assert.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include "mtk.h"
|
||||
|
||||
|
||||
MTK::MTK(const int &fd, struct vehicle_gps_position_s *gps_position) :
|
||||
_fd(fd),
|
||||
_gps_position(gps_position),
|
||||
_mtk_revision(0)
|
||||
{
|
||||
decode_init();
|
||||
}
|
||||
|
||||
MTK::~MTK()
|
||||
{
|
||||
}
|
||||
|
||||
int
|
||||
MTK::configure(unsigned &baudrate)
|
||||
{
|
||||
/* set baudrate first */
|
||||
if (GPS_Helper::set_baudrate(_fd, MTK_BAUDRATE) != 0)
|
||||
return -1;
|
||||
|
||||
baudrate = MTK_BAUDRATE;
|
||||
|
||||
/* Write config messages, don't wait for an answer */
|
||||
if (strlen(MTK_OUTPUT_5HZ) != write(_fd, MTK_OUTPUT_5HZ, strlen(MTK_OUTPUT_5HZ))) {
|
||||
warnx("mtk: config write failed");
|
||||
return -1;
|
||||
}
|
||||
usleep(10000);
|
||||
|
||||
if (strlen(MTK_SET_BINARY) != write(_fd, MTK_SET_BINARY, strlen(MTK_SET_BINARY))) {
|
||||
warnx("mtk: config write failed");
|
||||
return -1;
|
||||
}
|
||||
usleep(10000);
|
||||
|
||||
if (strlen(SBAS_ON) != write(_fd, SBAS_ON, strlen(SBAS_ON))) {
|
||||
warnx("mtk: config write failed");
|
||||
return -1;
|
||||
}
|
||||
usleep(10000);
|
||||
|
||||
if (strlen(WAAS_ON) != write(_fd, WAAS_ON, strlen(WAAS_ON))) {
|
||||
warnx("mtk: config write failed");
|
||||
return -1;
|
||||
}
|
||||
usleep(10000);
|
||||
|
||||
if (strlen(MTK_NAVTHRES_OFF) != write(_fd, MTK_NAVTHRES_OFF, strlen(MTK_NAVTHRES_OFF))) {
|
||||
warnx("mtk: config write failed");
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
MTK::receive(unsigned timeout)
|
||||
{
|
||||
/* poll descriptor */
|
||||
pollfd fds[1];
|
||||
fds[0].fd = _fd;
|
||||
fds[0].events = POLLIN;
|
||||
|
||||
uint8_t buf[32];
|
||||
gps_mtk_packet_t packet;
|
||||
|
||||
/* timeout additional to poll */
|
||||
uint64_t time_started = hrt_absolute_time();
|
||||
|
||||
int j = 0;
|
||||
ssize_t count = 0;
|
||||
|
||||
while (true) {
|
||||
|
||||
/* first read whatever is left */
|
||||
if (j < count) {
|
||||
/* pass received bytes to the packet decoder */
|
||||
while (j < count) {
|
||||
if (parse_char(buf[j], packet) > 0) {
|
||||
handle_message(packet);
|
||||
return 1;
|
||||
}
|
||||
/* in case we keep trying but only get crap from GPS */
|
||||
if (time_started + timeout*1000 < hrt_absolute_time() ) {
|
||||
return -1;
|
||||
}
|
||||
j++;
|
||||
}
|
||||
/* everything is read */
|
||||
j = count = 0;
|
||||
}
|
||||
|
||||
/* then poll for new data */
|
||||
int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), timeout);
|
||||
|
||||
if (ret < 0) {
|
||||
/* something went wrong when polling */
|
||||
return -1;
|
||||
|
||||
} else if (ret == 0) {
|
||||
/* Timeout */
|
||||
return -1;
|
||||
|
||||
} else if (ret > 0) {
|
||||
/* if we have new data from GPS, go handle it */
|
||||
if (fds[0].revents & POLLIN) {
|
||||
/*
|
||||
* We are here because poll says there is some data, so this
|
||||
* won't block even on a blocking device. If more bytes are
|
||||
* available, we'll go back to poll() again...
|
||||
*/
|
||||
count = ::read(_fd, buf, sizeof(buf));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
MTK::decode_init(void)
|
||||
{
|
||||
_rx_ck_a = 0;
|
||||
_rx_ck_b = 0;
|
||||
_rx_count = 0;
|
||||
_decode_state = MTK_DECODE_UNINIT;
|
||||
}
|
||||
int
|
||||
MTK::parse_char(uint8_t b, gps_mtk_packet_t &packet)
|
||||
{
|
||||
int ret = 0;
|
||||
|
||||
if (_decode_state == MTK_DECODE_UNINIT) {
|
||||
|
||||
if (b == MTK_SYNC1_V16) {
|
||||
_decode_state = MTK_DECODE_GOT_CK_A;
|
||||
_mtk_revision = 16;
|
||||
} else if (b == MTK_SYNC1_V19) {
|
||||
_decode_state = MTK_DECODE_GOT_CK_A;
|
||||
_mtk_revision = 19;
|
||||
}
|
||||
|
||||
} else if (_decode_state == MTK_DECODE_GOT_CK_A) {
|
||||
if (b == MTK_SYNC2) {
|
||||
_decode_state = MTK_DECODE_GOT_CK_B;
|
||||
|
||||
} else {
|
||||
// Second start symbol was wrong, reset state machine
|
||||
decode_init();
|
||||
}
|
||||
|
||||
} else if (_decode_state == MTK_DECODE_GOT_CK_B) {
|
||||
// Add to checksum
|
||||
if (_rx_count < 33)
|
||||
add_byte_to_checksum(b);
|
||||
|
||||
// Fill packet buffer
|
||||
((uint8_t*)(&packet))[_rx_count] = b;
|
||||
_rx_count++;
|
||||
|
||||
/* Packet size minus checksum, XXX ? */
|
||||
if (_rx_count >= sizeof(packet)) {
|
||||
/* Compare checksum */
|
||||
if (_rx_ck_a == packet.ck_a && _rx_ck_b == packet.ck_b) {
|
||||
ret = 1;
|
||||
} else {
|
||||
warnx("MTK Checksum invalid");
|
||||
ret = -1;
|
||||
}
|
||||
// Reset state machine to decode next packet
|
||||
decode_init();
|
||||
}
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
void
|
||||
MTK::handle_message(gps_mtk_packet_t &packet)
|
||||
{
|
||||
if (_mtk_revision == 16) {
|
||||
_gps_position->lat = packet.latitude * 10; // from degrees*1e6 to degrees*1e7
|
||||
_gps_position->lon = packet.longitude * 10; // from degrees*1e6 to degrees*1e7
|
||||
} else if (_mtk_revision == 19) {
|
||||
_gps_position->lat = packet.latitude; // both degrees*1e7
|
||||
_gps_position->lon = packet.longitude; // both degrees*1e7
|
||||
} else {
|
||||
warnx("mtk: unknown revision");
|
||||
_gps_position->lat = 0;
|
||||
_gps_position->lon = 0;
|
||||
}
|
||||
_gps_position->alt = (int32_t)(packet.msl_altitude * 10); // from cm to mm
|
||||
_gps_position->fix_type = packet.fix_type;
|
||||
_gps_position->eph_m = packet.hdop; // XXX: Check this because eph_m is in m and hdop is without unit
|
||||
_gps_position->epv_m = 0.0; //unknown in mtk custom mode
|
||||
_gps_position->vel_m_s = ((float)packet.ground_speed)*1e-2f; // from cm/s to m/s
|
||||
_gps_position->cog_rad = ((float)packet.heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad
|
||||
_gps_position->satellites_visible = packet.satellites;
|
||||
|
||||
/* convert time and date information to unix timestamp */
|
||||
struct tm timeinfo; //TODO: test this conversion
|
||||
uint32_t timeinfo_conversion_temp;
|
||||
|
||||
timeinfo.tm_mday = packet.date * 1e-4;
|
||||
timeinfo_conversion_temp = packet.date - timeinfo.tm_mday * 1e4;
|
||||
timeinfo.tm_mon = timeinfo_conversion_temp * 1e-2 - 1;
|
||||
timeinfo.tm_year = (timeinfo_conversion_temp - (timeinfo.tm_mon + 1) * 1e2) + 100;
|
||||
|
||||
timeinfo.tm_hour = packet.utc_time * 1e-7;
|
||||
timeinfo_conversion_temp = packet.utc_time - timeinfo.tm_hour * 1e7;
|
||||
timeinfo.tm_min = timeinfo_conversion_temp * 1e-5;
|
||||
timeinfo_conversion_temp -= timeinfo.tm_min * 1e5;
|
||||
timeinfo.tm_sec = timeinfo_conversion_temp * 1e-3;
|
||||
timeinfo_conversion_temp -= timeinfo.tm_sec * 1e3;
|
||||
time_t epoch = mktime(&timeinfo);
|
||||
|
||||
_gps_position->time_gps_usec = epoch * 1e6; //TODO: test this
|
||||
_gps_position->time_gps_usec += timeinfo_conversion_temp * 1e3;
|
||||
_gps_position->timestamp_position = _gps_position->timestamp_time = hrt_absolute_time();
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
void
|
||||
MTK::add_byte_to_checksum(uint8_t b)
|
||||
{
|
||||
_rx_ck_a = _rx_ck_a + b;
|
||||
_rx_ck_b = _rx_ck_b + _rx_ck_a;
|
||||
}
|
||||
@@ -0,0 +1,124 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* Julian Oes <joes@student.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 mtk.h */
|
||||
|
||||
#ifndef MTK_H_
|
||||
#define MTK_H_
|
||||
|
||||
#include "gps_helper.h"
|
||||
|
||||
#define MTK_SYNC1_V16 0xd0
|
||||
#define MTK_SYNC1_V19 0xd1
|
||||
#define MTK_SYNC2 0xdd
|
||||
|
||||
#define MTK_OUTPUT_5HZ "$PMTK220,200*2C\r\n"
|
||||
#define MTK_SET_BINARY "$PGCMD,16,0,0,0,0,0*6A\r\n"
|
||||
#define SBAS_ON "$PMTK313,1*2E\r\n"
|
||||
#define WAAS_ON "$PMTK301,2*2E\r\n"
|
||||
#define MTK_NAVTHRES_OFF "$PMTK397,0*23\r\n"
|
||||
|
||||
#define MTK_TIMEOUT_5HZ 400
|
||||
#define MTK_BAUDRATE 38400
|
||||
|
||||
typedef enum {
|
||||
MTK_DECODE_UNINIT = 0,
|
||||
MTK_DECODE_GOT_CK_A = 1,
|
||||
MTK_DECODE_GOT_CK_B = 2
|
||||
} mtk_decode_state_t;
|
||||
|
||||
/** the structures of the binary packets */
|
||||
#pragma pack(push, 1)
|
||||
|
||||
typedef struct {
|
||||
uint8_t payload; ///< Number of payload bytes
|
||||
int32_t latitude; ///< Latitude in degrees * 10^7
|
||||
int32_t longitude; ///< Longitude in degrees * 10^7
|
||||
uint32_t msl_altitude; ///< MSL altitude in meters * 10^2
|
||||
uint32_t ground_speed; ///< velocity in m/s
|
||||
int32_t heading; ///< heading in degrees * 10^2
|
||||
uint8_t satellites; ///< number of sattelites used
|
||||
uint8_t fix_type; ///< fix type: XXX correct for that
|
||||
uint32_t date;
|
||||
uint32_t utc_time;
|
||||
uint16_t hdop; ///< horizontal dilution of position (without unit)
|
||||
uint8_t ck_a;
|
||||
uint8_t ck_b;
|
||||
} gps_mtk_packet_t;
|
||||
|
||||
#pragma pack(pop)
|
||||
|
||||
#define MTK_RECV_BUFFER_SIZE 40
|
||||
|
||||
class MTK : public GPS_Helper
|
||||
{
|
||||
public:
|
||||
MTK(const int &fd, struct vehicle_gps_position_s *gps_position);
|
||||
~MTK();
|
||||
int receive(unsigned timeout);
|
||||
int configure(unsigned &baudrate);
|
||||
|
||||
private:
|
||||
/**
|
||||
* Parse the binary MTK packet
|
||||
*/
|
||||
int parse_char(uint8_t b, gps_mtk_packet_t &packet);
|
||||
|
||||
/**
|
||||
* Handle the package once it has arrived
|
||||
*/
|
||||
void handle_message(gps_mtk_packet_t &packet);
|
||||
|
||||
/**
|
||||
* Reset the parse state machine for a fresh start
|
||||
*/
|
||||
void decode_init(void);
|
||||
|
||||
/**
|
||||
* While parsing add every byte (except the sync bytes) to the checksum
|
||||
*/
|
||||
void add_byte_to_checksum(uint8_t);
|
||||
|
||||
int _fd;
|
||||
struct vehicle_gps_position_s *_gps_position;
|
||||
mtk_decode_state_t _decode_state;
|
||||
uint8_t _mtk_revision;
|
||||
uint8_t _rx_buffer[MTK_RECV_BUFFER_SIZE];
|
||||
unsigned _rx_count;
|
||||
uint8_t _rx_ck_a;
|
||||
uint8_t _rx_ck_b;
|
||||
};
|
||||
|
||||
#endif /* MTK_H_ */
|
||||
@@ -0,0 +1,755 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* Julian Oes <joes@student.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 ubx.cpp
|
||||
*
|
||||
* U-Blox protocol implementation. Following u-blox 6/7 Receiver Description
|
||||
* including Prototol Specification.
|
||||
*
|
||||
* @see http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
|
||||
*/
|
||||
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <poll.h>
|
||||
#include <math.h>
|
||||
#include <string.h>
|
||||
#include <assert.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include "ubx.h"
|
||||
|
||||
#define UBX_CONFIG_TIMEOUT 100
|
||||
|
||||
UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position) :
|
||||
_fd(fd),
|
||||
_gps_position(gps_position),
|
||||
_waiting_for_ack(false)
|
||||
{
|
||||
decode_init();
|
||||
}
|
||||
|
||||
UBX::~UBX()
|
||||
{
|
||||
}
|
||||
|
||||
int
|
||||
UBX::configure(unsigned &baudrate)
|
||||
{
|
||||
_waiting_for_ack = true;
|
||||
|
||||
/* try different baudrates */
|
||||
const unsigned baudrates_to_try[] = {9600, 38400, 19200, 57600, 115200};
|
||||
|
||||
for (int baud_i = 0; baud_i < 5; baud_i++) {
|
||||
baudrate = baudrates_to_try[baud_i];
|
||||
set_baudrate(_fd, baudrate);
|
||||
|
||||
/* Send a CFG-PRT message to set the UBX protocol for in and out
|
||||
* and leave the baudrate as it is, we just want an ACK-ACK from this
|
||||
*/
|
||||
type_gps_bin_cfg_prt_packet_t cfg_prt_packet;
|
||||
/* Set everything else of the packet to 0, otherwise the module wont accept it */
|
||||
memset(&cfg_prt_packet, 0, sizeof(cfg_prt_packet));
|
||||
|
||||
_clsID_needed = UBX_CLASS_CFG;
|
||||
_msgID_needed = UBX_MESSAGE_CFG_PRT;
|
||||
|
||||
/* Define the package contents, don't change the baudrate */
|
||||
cfg_prt_packet.clsID = UBX_CLASS_CFG;
|
||||
cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT;
|
||||
cfg_prt_packet.length = UBX_CFG_PRT_LENGTH;
|
||||
cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID;
|
||||
cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE;
|
||||
cfg_prt_packet.baudRate = baudrate;
|
||||
cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK;
|
||||
cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK;
|
||||
|
||||
send_config_packet(_fd, (uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet));
|
||||
|
||||
if (receive(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
/* try next baudrate */
|
||||
continue;
|
||||
}
|
||||
|
||||
/* Send a CFG-PRT message again, this time change the baudrate */
|
||||
|
||||
cfg_prt_packet.clsID = UBX_CLASS_CFG;
|
||||
cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT;
|
||||
cfg_prt_packet.length = UBX_CFG_PRT_LENGTH;
|
||||
cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID;
|
||||
cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE;
|
||||
cfg_prt_packet.baudRate = UBX_CFG_PRT_PAYLOAD_BAUDRATE;
|
||||
cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK;
|
||||
cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK;
|
||||
|
||||
send_config_packet(_fd, (uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet));
|
||||
|
||||
/* no ACK is expected here, but read the buffer anyway in case we actually get an ACK */
|
||||
receive(UBX_CONFIG_TIMEOUT);
|
||||
|
||||
if (UBX_CFG_PRT_PAYLOAD_BAUDRATE != baudrate) {
|
||||
set_baudrate(_fd, UBX_CFG_PRT_PAYLOAD_BAUDRATE);
|
||||
baudrate = UBX_CFG_PRT_PAYLOAD_BAUDRATE;
|
||||
}
|
||||
|
||||
/* send a CFT-RATE message to define update rate */
|
||||
type_gps_bin_cfg_rate_packet_t cfg_rate_packet;
|
||||
memset(&cfg_rate_packet, 0, sizeof(cfg_rate_packet));
|
||||
|
||||
_clsID_needed = UBX_CLASS_CFG;
|
||||
_msgID_needed = UBX_MESSAGE_CFG_RATE;
|
||||
|
||||
cfg_rate_packet.clsID = UBX_CLASS_CFG;
|
||||
cfg_rate_packet.msgID = UBX_MESSAGE_CFG_RATE;
|
||||
cfg_rate_packet.length = UBX_CFG_RATE_LENGTH;
|
||||
cfg_rate_packet.measRate = UBX_CFG_RATE_PAYLOAD_MEASRATE;
|
||||
cfg_rate_packet.navRate = UBX_CFG_RATE_PAYLOAD_NAVRATE;
|
||||
cfg_rate_packet.timeRef = UBX_CFG_RATE_PAYLOAD_TIMEREF;
|
||||
|
||||
send_config_packet(_fd, (uint8_t*)&cfg_rate_packet, sizeof(cfg_rate_packet));
|
||||
if (receive(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
/* try next baudrate */
|
||||
continue;
|
||||
}
|
||||
|
||||
/* send a NAV5 message to set the options for the internal filter */
|
||||
type_gps_bin_cfg_nav5_packet_t cfg_nav5_packet;
|
||||
memset(&cfg_nav5_packet, 0, sizeof(cfg_nav5_packet));
|
||||
|
||||
_clsID_needed = UBX_CLASS_CFG;
|
||||
_msgID_needed = UBX_MESSAGE_CFG_NAV5;
|
||||
|
||||
cfg_nav5_packet.clsID = UBX_CLASS_CFG;
|
||||
cfg_nav5_packet.msgID = UBX_MESSAGE_CFG_NAV5;
|
||||
cfg_nav5_packet.length = UBX_CFG_NAV5_LENGTH;
|
||||
cfg_nav5_packet.mask = UBX_CFG_NAV5_PAYLOAD_MASK;
|
||||
cfg_nav5_packet.dynModel = UBX_CFG_NAV5_PAYLOAD_DYNMODEL;
|
||||
cfg_nav5_packet.fixMode = UBX_CFG_NAV5_PAYLOAD_FIXMODE;
|
||||
|
||||
send_config_packet(_fd, (uint8_t*)&cfg_nav5_packet, sizeof(cfg_nav5_packet));
|
||||
if (receive(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
/* try next baudrate */
|
||||
continue;
|
||||
}
|
||||
|
||||
type_gps_bin_cfg_msg_packet_t cfg_msg_packet;
|
||||
memset(&cfg_msg_packet, 0, sizeof(cfg_msg_packet));
|
||||
|
||||
_clsID_needed = UBX_CLASS_CFG;
|
||||
_msgID_needed = UBX_MESSAGE_CFG_MSG;
|
||||
|
||||
cfg_msg_packet.clsID = UBX_CLASS_CFG;
|
||||
cfg_msg_packet.msgID = UBX_MESSAGE_CFG_MSG;
|
||||
cfg_msg_packet.length = UBX_CFG_MSG_LENGTH;
|
||||
/* Choose fast 5Hz rate for all messages except SVINFO which is big and not important */
|
||||
cfg_msg_packet.rate[1] = UBX_CFG_MSG_PAYLOAD_RATE1_5HZ;
|
||||
|
||||
cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
|
||||
cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_POSLLH;
|
||||
|
||||
send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet));
|
||||
if (receive(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
/* try next baudrate */
|
||||
continue;
|
||||
}
|
||||
|
||||
cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
|
||||
cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_TIMEUTC;
|
||||
|
||||
send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet));
|
||||
if (receive(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
/* try next baudrate */
|
||||
continue;
|
||||
}
|
||||
|
||||
cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
|
||||
cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SVINFO;
|
||||
/* For satelites info 1Hz is enough */
|
||||
cfg_msg_packet.rate[1] = UBX_CFG_MSG_PAYLOAD_RATE1_1HZ;
|
||||
|
||||
send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet));
|
||||
if (receive(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
/* try next baudrate */
|
||||
continue;
|
||||
}
|
||||
|
||||
cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
|
||||
cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SOL;
|
||||
|
||||
send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet));
|
||||
if (receive(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
/* try next baudrate */
|
||||
continue;
|
||||
}
|
||||
|
||||
cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
|
||||
cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_VELNED;
|
||||
|
||||
send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet));
|
||||
if (receive(UBX_CONFIG_TIMEOUT) < 0) {
|
||||
/* try next baudrate */
|
||||
continue;
|
||||
}
|
||||
// cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
|
||||
// cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_DOP;
|
||||
|
||||
// cfg_msg_packet.msgClass_payload = UBX_CLASS_RXM;
|
||||
// cfg_msg_packet.msgID_payload = UBX_MESSAGE_RXM_SVSI;
|
||||
|
||||
_waiting_for_ack = false;
|
||||
return 0;
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
int
|
||||
UBX::receive(unsigned timeout)
|
||||
{
|
||||
/* poll descriptor */
|
||||
pollfd fds[1];
|
||||
fds[0].fd = _fd;
|
||||
fds[0].events = POLLIN;
|
||||
|
||||
uint8_t buf[32];
|
||||
|
||||
/* timeout additional to poll */
|
||||
uint64_t time_started = hrt_absolute_time();
|
||||
|
||||
int j = 0;
|
||||
ssize_t count = 0;
|
||||
|
||||
while (true) {
|
||||
|
||||
/* pass received bytes to the packet decoder */
|
||||
while (j < count) {
|
||||
if (parse_char(buf[j]) > 0) {
|
||||
/* return to configure during configuration or to the gps driver during normal work
|
||||
* if a packet has arrived */
|
||||
if (handle_message() > 0)
|
||||
return 1;
|
||||
}
|
||||
/* in case we keep trying but only get crap from GPS */
|
||||
if (time_started + timeout*1000 < hrt_absolute_time() ) {
|
||||
return -1;
|
||||
}
|
||||
j++;
|
||||
}
|
||||
|
||||
/* everything is read */
|
||||
j = count = 0;
|
||||
|
||||
/* then poll for new data */
|
||||
int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), timeout);
|
||||
|
||||
if (ret < 0) {
|
||||
/* something went wrong when polling */
|
||||
return -1;
|
||||
|
||||
} else if (ret == 0) {
|
||||
/* Timeout */
|
||||
return -1;
|
||||
|
||||
} else if (ret > 0) {
|
||||
/* if we have new data from GPS, go handle it */
|
||||
if (fds[0].revents & POLLIN) {
|
||||
/*
|
||||
* We are here because poll says there is some data, so this
|
||||
* won't block even on a blocking device. If more bytes are
|
||||
* available, we'll go back to poll() again...
|
||||
*/
|
||||
count = ::read(_fd, buf, sizeof(buf));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
UBX::parse_char(uint8_t b)
|
||||
{
|
||||
switch (_decode_state) {
|
||||
/* First, look for sync1 */
|
||||
case UBX_DECODE_UNINIT:
|
||||
if (b == UBX_SYNC1) {
|
||||
_decode_state = UBX_DECODE_GOT_SYNC1;
|
||||
}
|
||||
break;
|
||||
/* Second, look for sync2 */
|
||||
case UBX_DECODE_GOT_SYNC1:
|
||||
if (b == UBX_SYNC2) {
|
||||
_decode_state = UBX_DECODE_GOT_SYNC2;
|
||||
} else {
|
||||
/* Second start symbol was wrong, reset state machine */
|
||||
decode_init();
|
||||
}
|
||||
break;
|
||||
/* Now look for class */
|
||||
case UBX_DECODE_GOT_SYNC2:
|
||||
/* everything except sync1 and sync2 needs to be added to the checksum */
|
||||
add_byte_to_checksum(b);
|
||||
/* check for known class */
|
||||
switch (b) {
|
||||
case UBX_CLASS_ACK:
|
||||
_decode_state = UBX_DECODE_GOT_CLASS;
|
||||
_message_class = ACK;
|
||||
break;
|
||||
|
||||
case UBX_CLASS_NAV:
|
||||
_decode_state = UBX_DECODE_GOT_CLASS;
|
||||
_message_class = NAV;
|
||||
break;
|
||||
|
||||
// case UBX_CLASS_RXM:
|
||||
// _decode_state = UBX_DECODE_GOT_CLASS;
|
||||
// _message_class = RXM;
|
||||
// break;
|
||||
|
||||
case UBX_CLASS_CFG:
|
||||
_decode_state = UBX_DECODE_GOT_CLASS;
|
||||
_message_class = CFG;
|
||||
break;
|
||||
default: //unknown class: reset state machine
|
||||
decode_init();
|
||||
break;
|
||||
}
|
||||
break;
|
||||
case UBX_DECODE_GOT_CLASS:
|
||||
add_byte_to_checksum(b);
|
||||
switch (_message_class) {
|
||||
case NAV:
|
||||
switch (b) {
|
||||
case UBX_MESSAGE_NAV_POSLLH:
|
||||
_decode_state = UBX_DECODE_GOT_MESSAGEID;
|
||||
_message_id = NAV_POSLLH;
|
||||
break;
|
||||
|
||||
case UBX_MESSAGE_NAV_SOL:
|
||||
_decode_state = UBX_DECODE_GOT_MESSAGEID;
|
||||
_message_id = NAV_SOL;
|
||||
break;
|
||||
|
||||
case UBX_MESSAGE_NAV_TIMEUTC:
|
||||
_decode_state = UBX_DECODE_GOT_MESSAGEID;
|
||||
_message_id = NAV_TIMEUTC;
|
||||
break;
|
||||
|
||||
// case UBX_MESSAGE_NAV_DOP:
|
||||
// _decode_state = UBX_DECODE_GOT_MESSAGEID;
|
||||
// _message_id = NAV_DOP;
|
||||
// break;
|
||||
|
||||
case UBX_MESSAGE_NAV_SVINFO:
|
||||
_decode_state = UBX_DECODE_GOT_MESSAGEID;
|
||||
_message_id = NAV_SVINFO;
|
||||
break;
|
||||
|
||||
case UBX_MESSAGE_NAV_VELNED:
|
||||
_decode_state = UBX_DECODE_GOT_MESSAGEID;
|
||||
_message_id = NAV_VELNED;
|
||||
break;
|
||||
|
||||
default: //unknown class: reset state machine, should not happen
|
||||
decode_init();
|
||||
break;
|
||||
}
|
||||
break;
|
||||
// case RXM:
|
||||
// switch (b) {
|
||||
// case UBX_MESSAGE_RXM_SVSI:
|
||||
// _decode_state = UBX_DECODE_GOT_MESSAGEID;
|
||||
// _message_id = RXM_SVSI;
|
||||
// break;
|
||||
//
|
||||
// default: //unknown class: reset state machine, should not happen
|
||||
// decode_init();
|
||||
// break;
|
||||
// }
|
||||
// break;
|
||||
|
||||
case CFG:
|
||||
switch (b) {
|
||||
case UBX_MESSAGE_CFG_NAV5:
|
||||
_decode_state = UBX_DECODE_GOT_MESSAGEID;
|
||||
_message_id = CFG_NAV5;
|
||||
break;
|
||||
|
||||
default: //unknown class: reset state machine, should not happen
|
||||
decode_init();
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
case ACK:
|
||||
switch (b) {
|
||||
case UBX_MESSAGE_ACK_ACK:
|
||||
_decode_state = UBX_DECODE_GOT_MESSAGEID;
|
||||
_message_id = ACK_ACK;
|
||||
break;
|
||||
case UBX_MESSAGE_ACK_NAK:
|
||||
_decode_state = UBX_DECODE_GOT_MESSAGEID;
|
||||
_message_id = ACK_NAK;
|
||||
break;
|
||||
default: //unknown class: reset state machine, should not happen
|
||||
decode_init();
|
||||
break;
|
||||
}
|
||||
break;
|
||||
default: //should not happen because we set the class
|
||||
warnx("UBX Error, we set a class that we don't know");
|
||||
decode_init();
|
||||
// config_needed = true;
|
||||
break;
|
||||
}
|
||||
break;
|
||||
case UBX_DECODE_GOT_MESSAGEID:
|
||||
add_byte_to_checksum(b);
|
||||
_payload_size = b; //this is the first length byte
|
||||
_decode_state = UBX_DECODE_GOT_LENGTH1;
|
||||
break;
|
||||
case UBX_DECODE_GOT_LENGTH1:
|
||||
add_byte_to_checksum(b);
|
||||
_payload_size += b << 8; // here comes the second byte of length
|
||||
_decode_state = UBX_DECODE_GOT_LENGTH2;
|
||||
break;
|
||||
case UBX_DECODE_GOT_LENGTH2:
|
||||
/* Add to checksum if not yet at checksum byte */
|
||||
if (_rx_count < _payload_size)
|
||||
add_byte_to_checksum(b);
|
||||
_rx_buffer[_rx_count] = b;
|
||||
/* once the payload has arrived, we can process the information */
|
||||
if (_rx_count >= _payload_size + 1) { //+1 because of 2 checksum bytes
|
||||
|
||||
/* compare checksum */
|
||||
if (_rx_ck_a == _rx_buffer[_rx_count-1] && _rx_ck_b == _rx_buffer[_rx_count]) {
|
||||
return 1;
|
||||
} else {
|
||||
decode_init();
|
||||
return -1;
|
||||
warnx("ubx: Checksum wrong");
|
||||
}
|
||||
|
||||
return 1;
|
||||
} else if (_rx_count < RECV_BUFFER_SIZE) {
|
||||
_rx_count++;
|
||||
} else {
|
||||
warnx("ubx: buffer full");
|
||||
decode_init();
|
||||
return -1;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
return 0; //XXX ?
|
||||
}
|
||||
|
||||
|
||||
int
|
||||
UBX::handle_message()
|
||||
{
|
||||
int ret = 0;
|
||||
|
||||
switch (_message_id) { //this enum is unique for all ids --> no need to check the class
|
||||
case NAV_POSLLH: {
|
||||
// printf("GOT NAV_POSLLH MESSAGE\n");
|
||||
if (!_waiting_for_ack) {
|
||||
gps_bin_nav_posllh_packet_t *packet = (gps_bin_nav_posllh_packet_t *) _rx_buffer;
|
||||
|
||||
_gps_position->lat = packet->lat;
|
||||
_gps_position->lon = packet->lon;
|
||||
_gps_position->alt = packet->height_msl;
|
||||
|
||||
_gps_position->eph_m = (float)packet->hAcc * 1e-3f; // from mm to m
|
||||
_gps_position->epv_m = (float)packet->vAcc * 1e-3f; // from mm to m
|
||||
|
||||
/* Add timestamp to finish the report */
|
||||
_gps_position->timestamp_position = hrt_absolute_time();
|
||||
/* only return 1 when new position is available */
|
||||
ret = 1;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case NAV_SOL: {
|
||||
// printf("GOT NAV_SOL MESSAGE\n");
|
||||
if (!_waiting_for_ack) {
|
||||
gps_bin_nav_sol_packet_t *packet = (gps_bin_nav_sol_packet_t *) _rx_buffer;
|
||||
|
||||
_gps_position->fix_type = packet->gpsFix;
|
||||
_gps_position->s_variance_m_s = packet->sAcc;
|
||||
_gps_position->p_variance_m = packet->pAcc;
|
||||
|
||||
_gps_position->timestamp_variance = hrt_absolute_time();
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
// case NAV_DOP: {
|
||||
//// printf("GOT NAV_DOP MESSAGE\n");
|
||||
// gps_bin_nav_dop_packet_t *packet = (gps_bin_nav_dop_packet_t *) _rx_buffer;
|
||||
//
|
||||
// _gps_position->eph_m = packet->hDOP;
|
||||
// _gps_position->epv = packet->vDOP;
|
||||
//
|
||||
// _gps_position->timestamp_posdilution = hrt_absolute_time();
|
||||
//
|
||||
// _new_nav_dop = true;
|
||||
//
|
||||
// break;
|
||||
// }
|
||||
|
||||
case NAV_TIMEUTC: {
|
||||
// printf("GOT NAV_TIMEUTC MESSAGE\n");
|
||||
|
||||
if (!_waiting_for_ack) {
|
||||
gps_bin_nav_timeutc_packet_t *packet = (gps_bin_nav_timeutc_packet_t *) _rx_buffer;
|
||||
|
||||
//convert to unix timestamp
|
||||
struct tm timeinfo;
|
||||
timeinfo.tm_year = packet->year - 1900;
|
||||
timeinfo.tm_mon = packet->month - 1;
|
||||
timeinfo.tm_mday = packet->day;
|
||||
timeinfo.tm_hour = packet->hour;
|
||||
timeinfo.tm_min = packet->min;
|
||||
timeinfo.tm_sec = packet->sec;
|
||||
|
||||
time_t epoch = mktime(&timeinfo);
|
||||
|
||||
_gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
|
||||
_gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f);
|
||||
|
||||
_gps_position->timestamp_time = hrt_absolute_time();
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case NAV_SVINFO: {
|
||||
// printf("GOT NAV_SVINFO MESSAGE\n");
|
||||
|
||||
if (!_waiting_for_ack) {
|
||||
//this is a more complicated message: the length depends on the number of satellites. This number is extracted from the first part of the message
|
||||
const int length_part1 = 8;
|
||||
char _rx_buffer_part1[length_part1];
|
||||
memcpy(_rx_buffer_part1, _rx_buffer, length_part1);
|
||||
gps_bin_nav_svinfo_part1_packet_t *packet_part1 = (gps_bin_nav_svinfo_part1_packet_t *) _rx_buffer_part1;
|
||||
|
||||
//read checksum
|
||||
const int length_part3 = 2;
|
||||
char _rx_buffer_part3[length_part3];
|
||||
memcpy(_rx_buffer_part3, &(_rx_buffer[_rx_count - 1]), length_part3);
|
||||
|
||||
//definitions needed to read numCh elements from the buffer:
|
||||
const int length_part2 = 12;
|
||||
gps_bin_nav_svinfo_part2_packet_t *packet_part2;
|
||||
char _rx_buffer_part2[length_part2]; //for temporal storage
|
||||
|
||||
uint8_t satellites_used = 0;
|
||||
int i;
|
||||
|
||||
for (i = 0; i < packet_part1->numCh; i++) { //for each channel
|
||||
|
||||
/* Get satellite information from the buffer */
|
||||
memcpy(_rx_buffer_part2, &(_rx_buffer[length_part1 + i * length_part2]), length_part2);
|
||||
packet_part2 = (gps_bin_nav_svinfo_part2_packet_t *) _rx_buffer_part2;
|
||||
|
||||
|
||||
/* Write satellite information in the global storage */
|
||||
_gps_position->satellite_prn[i] = packet_part2->svid;
|
||||
|
||||
//if satellite information is healthy store the data
|
||||
uint8_t unhealthy = packet_part2->flags & 1 << 4; //flags is a bitfield
|
||||
|
||||
if (!unhealthy) {
|
||||
if ((packet_part2->flags) & 1) { //flags is a bitfield
|
||||
_gps_position->satellite_used[i] = 1;
|
||||
satellites_used++;
|
||||
|
||||
} else {
|
||||
_gps_position->satellite_used[i] = 0;
|
||||
}
|
||||
|
||||
_gps_position->satellite_snr[i] = packet_part2->cno;
|
||||
_gps_position->satellite_elevation[i] = (uint8_t)(packet_part2->elev);
|
||||
_gps_position->satellite_azimuth[i] = (uint8_t)((float)packet_part2->azim * 255.0f / 360.0f);
|
||||
|
||||
} else {
|
||||
_gps_position->satellite_used[i] = 0;
|
||||
_gps_position->satellite_snr[i] = 0;
|
||||
_gps_position->satellite_elevation[i] = 0;
|
||||
_gps_position->satellite_azimuth[i] = 0;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
for (i = packet_part1->numCh; i < 20; i++) { //these channels are unused
|
||||
/* Unused channels have to be set to zero for e.g. MAVLink */
|
||||
_gps_position->satellite_prn[i] = 0;
|
||||
_gps_position->satellite_used[i] = 0;
|
||||
_gps_position->satellite_snr[i] = 0;
|
||||
_gps_position->satellite_elevation[i] = 0;
|
||||
_gps_position->satellite_azimuth[i] = 0;
|
||||
}
|
||||
_gps_position->satellites_visible = satellites_used; // visible ~= used but we are interested in the used ones
|
||||
|
||||
/* set timestamp if any sat info is available */
|
||||
if (packet_part1->numCh > 0) {
|
||||
_gps_position->satellite_info_available = true;
|
||||
} else {
|
||||
_gps_position->satellite_info_available = false;
|
||||
}
|
||||
_gps_position->timestamp_satellites = hrt_absolute_time();
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
case NAV_VELNED: {
|
||||
|
||||
if (!_waiting_for_ack) {
|
||||
/* 35.15 NAV-VELNED (0x01 0x12) message (page 181 / 210 of reference manual */
|
||||
gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer;
|
||||
|
||||
_gps_position->vel_m_s = (float)packet->speed * 1e-2f;
|
||||
_gps_position->vel_n_m_s = (float)packet->velN * 1e-2f; /* NED NORTH velocity */
|
||||
_gps_position->vel_e_m_s = (float)packet->velE * 1e-2f; /* NED EAST velocity */
|
||||
_gps_position->vel_d_m_s = (float)packet->velD * 1e-2f; /* NED DOWN velocity */
|
||||
_gps_position->cog_rad = (float)packet->heading * M_DEG_TO_RAD_F * 1e-5f;
|
||||
_gps_position->c_variance_rad = (float)packet->cAcc * M_DEG_TO_RAD_F * 1e-5f;
|
||||
_gps_position->vel_ned_valid = true;
|
||||
_gps_position->timestamp_velocity = hrt_absolute_time();
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
// case RXM_SVSI: {
|
||||
// printf("GOT RXM_SVSI MESSAGE\n");
|
||||
// const int length_part1 = 7;
|
||||
// char _rx_buffer_part1[length_part1];
|
||||
// memcpy(_rx_buffer_part1, _rx_buffer, length_part1);
|
||||
// gps_bin_rxm_svsi_packet_t *packet = (gps_bin_rxm_svsi_packet_t *) _rx_buffer_part1;
|
||||
//
|
||||
// _gps_position->satellites_visible = packet->numVis;
|
||||
// _gps_position->counter++;
|
||||
// _last_message_timestamps[RXM_SVSI - 1] = hrt_absolute_time();
|
||||
//
|
||||
// break;
|
||||
// }
|
||||
case ACK_ACK: {
|
||||
// printf("GOT ACK_ACK\n");
|
||||
gps_bin_ack_ack_packet_t *packet = (gps_bin_ack_ack_packet_t *) _rx_buffer;
|
||||
|
||||
if (_waiting_for_ack) {
|
||||
if (packet->clsID == _clsID_needed && packet->msgID == _msgID_needed) {
|
||||
ret = 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case ACK_NAK: {
|
||||
// printf("GOT ACK_NAK\n");
|
||||
warnx("UBX: Received: Not Acknowledged");
|
||||
/* configuration obviously not successful */
|
||||
ret = -1;
|
||||
break;
|
||||
}
|
||||
|
||||
default: //we don't know the message
|
||||
warnx("UBX: Unknown message received: %d-%d\n",_message_class,_message_id);
|
||||
ret = -1;
|
||||
break;
|
||||
}
|
||||
// end if _rx_count high enough
|
||||
decode_init();
|
||||
return ret; //XXX?
|
||||
}
|
||||
|
||||
void
|
||||
UBX::decode_init(void)
|
||||
{
|
||||
_rx_ck_a = 0;
|
||||
_rx_ck_b = 0;
|
||||
_rx_count = 0;
|
||||
_decode_state = UBX_DECODE_UNINIT;
|
||||
_message_class = CLASS_UNKNOWN;
|
||||
_message_id = ID_UNKNOWN;
|
||||
_payload_size = 0;
|
||||
}
|
||||
|
||||
void
|
||||
UBX::add_byte_to_checksum(uint8_t b)
|
||||
{
|
||||
_rx_ck_a = _rx_ck_a + b;
|
||||
_rx_ck_b = _rx_ck_b + _rx_ck_a;
|
||||
}
|
||||
|
||||
void
|
||||
UBX::add_checksum_to_message(uint8_t* message, const unsigned length)
|
||||
{
|
||||
uint8_t ck_a = 0;
|
||||
uint8_t ck_b = 0;
|
||||
unsigned i;
|
||||
|
||||
for (i = 0; i < length-2; i++) {
|
||||
ck_a = ck_a + message[i];
|
||||
ck_b = ck_b + ck_a;
|
||||
}
|
||||
/* The checksum is written to the last to bytes of a message */
|
||||
message[length-2] = ck_a;
|
||||
message[length-1] = ck_b;
|
||||
}
|
||||
|
||||
void
|
||||
UBX::send_config_packet(const int &fd, uint8_t *packet, const unsigned length)
|
||||
{
|
||||
ssize_t ret = 0;
|
||||
|
||||
/* Calculate the checksum now */
|
||||
add_checksum_to_message(packet, length);
|
||||
|
||||
const uint8_t sync_bytes[] = {UBX_SYNC1, UBX_SYNC2};
|
||||
|
||||
/* Start with the two sync bytes */
|
||||
ret += write(fd, sync_bytes, sizeof(sync_bytes));
|
||||
ret += write(fd, packet, length);
|
||||
|
||||
if (ret != (int)length + (int)sizeof(sync_bytes)) // XXX is there a neater way to get rid of the unsigned signed warning?
|
||||
warnx("ubx: config write fail");
|
||||
}
|
||||
@@ -0,0 +1,395 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* Julian Oes <joes@student.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 U-Blox protocol definitions */
|
||||
|
||||
#ifndef UBX_H_
|
||||
#define UBX_H_
|
||||
|
||||
#include "gps_helper.h"
|
||||
|
||||
#define UBX_SYNC1 0xB5
|
||||
#define UBX_SYNC2 0x62
|
||||
|
||||
/* ClassIDs (the ones that are used) */
|
||||
#define UBX_CLASS_NAV 0x01
|
||||
//#define UBX_CLASS_RXM 0x02
|
||||
#define UBX_CLASS_ACK 0x05
|
||||
#define UBX_CLASS_CFG 0x06
|
||||
|
||||
/* MessageIDs (the ones that are used) */
|
||||
#define UBX_MESSAGE_NAV_POSLLH 0x02
|
||||
#define UBX_MESSAGE_NAV_SOL 0x06
|
||||
#define UBX_MESSAGE_NAV_TIMEUTC 0x21
|
||||
//#define UBX_MESSAGE_NAV_DOP 0x04
|
||||
#define UBX_MESSAGE_NAV_SVINFO 0x30
|
||||
#define UBX_MESSAGE_NAV_VELNED 0x12
|
||||
//#define UBX_MESSAGE_RXM_SVSI 0x20
|
||||
#define UBX_MESSAGE_ACK_ACK 0x01
|
||||
#define UBX_MESSAGE_ACK_NAK 0x00
|
||||
#define UBX_MESSAGE_CFG_PRT 0x00
|
||||
#define UBX_MESSAGE_CFG_NAV5 0x24
|
||||
#define UBX_MESSAGE_CFG_MSG 0x01
|
||||
#define UBX_MESSAGE_CFG_RATE 0x08
|
||||
|
||||
#define UBX_CFG_PRT_LENGTH 20
|
||||
#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< UART1 */
|
||||
#define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */
|
||||
#define UBX_CFG_PRT_PAYLOAD_BAUDRATE 38400 /**< always choose 38400 as GPS baudrate */
|
||||
#define UBX_CFG_PRT_PAYLOAD_INPROTOMASK 0x01 /**< UBX in */
|
||||
#define UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK 0x01 /**< UBX out */
|
||||
|
||||
#define UBX_CFG_RATE_LENGTH 6
|
||||
#define UBX_CFG_RATE_PAYLOAD_MEASRATE 200 /**< 200ms for 5Hz */
|
||||
#define UBX_CFG_RATE_PAYLOAD_NAVRATE 1 /**< cannot be changed */
|
||||
#define UBX_CFG_RATE_PAYLOAD_TIMEREF 0 /**< 0: UTC, 1: GPS time */
|
||||
|
||||
|
||||
#define UBX_CFG_NAV5_LENGTH 36
|
||||
#define UBX_CFG_NAV5_PAYLOAD_MASK 0x0001 /**< only update dynamic model and fix mode */
|
||||
#define UBX_CFG_NAV5_PAYLOAD_DYNMODEL 7 /**< 0: portable, 2: stationary, 3: pedestrian, 4: automotive, 5: sea, 6: airborne <1g, 7: airborne <2g, 8: airborne <4g */
|
||||
#define UBX_CFG_NAV5_PAYLOAD_FIXMODE 2 /**< 1: 2D only, 2: 3D only, 3: Auto 2D/3D */
|
||||
|
||||
#define UBX_CFG_MSG_LENGTH 8
|
||||
#define UBX_CFG_MSG_PAYLOAD_RATE1_5HZ 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
|
||||
#define UBX_CFG_MSG_PAYLOAD_RATE1_1HZ 0x05 /**< {0x00, 0x05, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
|
||||
|
||||
#define UBX_MAX_PAYLOAD_LENGTH 500
|
||||
|
||||
// ************
|
||||
/** the structures of the binary packets */
|
||||
#pragma pack(push, 1)
|
||||
|
||||
typedef struct {
|
||||
uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
|
||||
int32_t lon; /**< Longitude * 1e-7, deg */
|
||||
int32_t lat; /**< Latitude * 1e-7, deg */
|
||||
int32_t height; /**< Height above Ellipsoid, mm */
|
||||
int32_t height_msl; /**< Height above mean sea level, mm */
|
||||
uint32_t hAcc; /**< Horizontal Accuracy Estimate, mm */
|
||||
uint32_t vAcc; /**< Vertical Accuracy Estimate, mm */
|
||||
uint8_t ck_a;
|
||||
uint8_t ck_b;
|
||||
} gps_bin_nav_posllh_packet_t;
|
||||
|
||||
typedef struct {
|
||||
uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
|
||||
int32_t time_nanoseconds; /**< Fractional Nanoseconds remainder of rounded ms above, range -500000 .. 500000 */
|
||||
int16_t week; /**< GPS week (GPS time) */
|
||||
uint8_t gpsFix; /**< GPS Fix: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix */
|
||||
uint8_t flags;
|
||||
int32_t ecefX;
|
||||
int32_t ecefY;
|
||||
int32_t ecefZ;
|
||||
uint32_t pAcc;
|
||||
int32_t ecefVX;
|
||||
int32_t ecefVY;
|
||||
int32_t ecefVZ;
|
||||
uint32_t sAcc;
|
||||
uint16_t pDOP;
|
||||
uint8_t reserved1;
|
||||
uint8_t numSV;
|
||||
uint32_t reserved2;
|
||||
uint8_t ck_a;
|
||||
uint8_t ck_b;
|
||||
} gps_bin_nav_sol_packet_t;
|
||||
|
||||
typedef struct {
|
||||
uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
|
||||
uint32_t time_accuracy; /**< Time Accuracy Estimate, ns */
|
||||
int32_t time_nanoseconds; /**< Nanoseconds of second, range -1e9 .. 1e9 (UTC) */
|
||||
uint16_t year; /**< Year, range 1999..2099 (UTC) */
|
||||
uint8_t month; /**< Month, range 1..12 (UTC) */
|
||||
uint8_t day; /**< Day of Month, range 1..31 (UTC) */
|
||||
uint8_t hour; /**< Hour of Day, range 0..23 (UTC) */
|
||||
uint8_t min; /**< Minute of Hour, range 0..59 (UTC) */
|
||||
uint8_t sec; /**< Seconds of Minute, range 0..59 (UTC) */
|
||||
uint8_t valid_flag; /**< Validity Flags (see ubx documentation) */
|
||||
uint8_t ck_a;
|
||||
uint8_t ck_b;
|
||||
} gps_bin_nav_timeutc_packet_t;
|
||||
|
||||
//typedef struct {
|
||||
// uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
|
||||
// uint16_t gDOP; /**< Geometric DOP (scaling 0.01) */
|
||||
// uint16_t pDOP; /**< Position DOP (scaling 0.01) */
|
||||
// uint16_t tDOP; /**< Time DOP (scaling 0.01) */
|
||||
// uint16_t vDOP; /**< Vertical DOP (scaling 0.01) */
|
||||
// uint16_t hDOP; /**< Horizontal DOP (scaling 0.01) */
|
||||
// uint16_t nDOP; /**< Northing DOP (scaling 0.01) */
|
||||
// uint16_t eDOP; /**< Easting DOP (scaling 0.01) */
|
||||
// uint8_t ck_a;
|
||||
// uint8_t ck_b;
|
||||
//} gps_bin_nav_dop_packet_t;
|
||||
|
||||
typedef struct {
|
||||
uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
|
||||
uint8_t numCh; /**< Number of channels */
|
||||
uint8_t globalFlags;
|
||||
uint16_t reserved2;
|
||||
|
||||
} gps_bin_nav_svinfo_part1_packet_t;
|
||||
|
||||
typedef struct {
|
||||
uint8_t chn; /**< Channel number, 255 for SVs not assigned to a channel */
|
||||
uint8_t svid; /**< Satellite ID */
|
||||
uint8_t flags;
|
||||
uint8_t quality;
|
||||
uint8_t cno; /**< Carrier to Noise Ratio (Signal Strength), dbHz */
|
||||
int8_t elev; /**< Elevation in integer degrees */
|
||||
int16_t azim; /**< Azimuth in integer degrees */
|
||||
int32_t prRes; /**< Pseudo range residual in centimetres */
|
||||
|
||||
} gps_bin_nav_svinfo_part2_packet_t;
|
||||
|
||||
typedef struct {
|
||||
uint8_t ck_a;
|
||||
uint8_t ck_b;
|
||||
} gps_bin_nav_svinfo_part3_packet_t;
|
||||
|
||||
typedef struct {
|
||||
uint32_t time_milliseconds; // GPS Millisecond Time of Week
|
||||
int32_t velN; //NED north velocity, cm/s
|
||||
int32_t velE; //NED east velocity, cm/s
|
||||
int32_t velD; //NED down velocity, cm/s
|
||||
uint32_t speed; //Speed (3-D), cm/s
|
||||
uint32_t gSpeed; //Ground Speed (2-D), cm/s
|
||||
int32_t heading; //Heading of motion 2-D, deg, scaling: 1e-5
|
||||
uint32_t sAcc; //Speed Accuracy Estimate, cm/s
|
||||
uint32_t cAcc; //Course / Heading Accuracy Estimate, scaling: 1e-5
|
||||
uint8_t ck_a;
|
||||
uint8_t ck_b;
|
||||
} gps_bin_nav_velned_packet_t;
|
||||
|
||||
//typedef struct {
|
||||
// int32_t time_milliseconds; /**< Measurement integer millisecond GPS time of week */
|
||||
// int16_t week; /**< Measurement GPS week number */
|
||||
// uint8_t numVis; /**< Number of visible satellites */
|
||||
//
|
||||
// //... rest of package is not used in this implementation
|
||||
//
|
||||
//} gps_bin_rxm_svsi_packet_t;
|
||||
|
||||
typedef struct {
|
||||
uint8_t clsID;
|
||||
uint8_t msgID;
|
||||
uint8_t ck_a;
|
||||
uint8_t ck_b;
|
||||
} gps_bin_ack_ack_packet_t;
|
||||
|
||||
typedef struct {
|
||||
uint8_t clsID;
|
||||
uint8_t msgID;
|
||||
uint8_t ck_a;
|
||||
uint8_t ck_b;
|
||||
} gps_bin_ack_nak_packet_t;
|
||||
|
||||
typedef struct {
|
||||
uint8_t clsID;
|
||||
uint8_t msgID;
|
||||
uint16_t length;
|
||||
uint8_t portID;
|
||||
uint8_t res0;
|
||||
uint16_t res1;
|
||||
uint32_t mode;
|
||||
uint32_t baudRate;
|
||||
uint16_t inProtoMask;
|
||||
uint16_t outProtoMask;
|
||||
uint16_t flags;
|
||||
uint16_t pad;
|
||||
uint8_t ck_a;
|
||||
uint8_t ck_b;
|
||||
} type_gps_bin_cfg_prt_packet_t;
|
||||
|
||||
typedef struct {
|
||||
uint8_t clsID;
|
||||
uint8_t msgID;
|
||||
uint16_t length;
|
||||
uint16_t measRate;
|
||||
uint16_t navRate;
|
||||
uint16_t timeRef;
|
||||
uint8_t ck_a;
|
||||
uint8_t ck_b;
|
||||
} type_gps_bin_cfg_rate_packet_t;
|
||||
|
||||
typedef struct {
|
||||
uint8_t clsID;
|
||||
uint8_t msgID;
|
||||
uint16_t length;
|
||||
uint16_t mask;
|
||||
uint8_t dynModel;
|
||||
uint8_t fixMode;
|
||||
int32_t fixedAlt;
|
||||
uint32_t fixedAltVar;
|
||||
int8_t minElev;
|
||||
uint8_t drLimit;
|
||||
uint16_t pDop;
|
||||
uint16_t tDop;
|
||||
uint16_t pAcc;
|
||||
uint16_t tAcc;
|
||||
uint8_t staticHoldThresh;
|
||||
uint8_t dgpsTimeOut;
|
||||
uint32_t reserved2;
|
||||
uint32_t reserved3;
|
||||
uint32_t reserved4;
|
||||
uint8_t ck_a;
|
||||
uint8_t ck_b;
|
||||
} type_gps_bin_cfg_nav5_packet_t;
|
||||
|
||||
typedef struct {
|
||||
uint8_t clsID;
|
||||
uint8_t msgID;
|
||||
uint16_t length;
|
||||
uint8_t msgClass_payload;
|
||||
uint8_t msgID_payload;
|
||||
uint8_t rate[6];
|
||||
uint8_t ck_a;
|
||||
uint8_t ck_b;
|
||||
} type_gps_bin_cfg_msg_packet_t;
|
||||
|
||||
|
||||
// END the structures of the binary packets
|
||||
// ************
|
||||
|
||||
typedef enum {
|
||||
UBX_CONFIG_STATE_PRT = 0,
|
||||
UBX_CONFIG_STATE_PRT_NEW_BAUDRATE,
|
||||
UBX_CONFIG_STATE_RATE,
|
||||
UBX_CONFIG_STATE_NAV5,
|
||||
UBX_CONFIG_STATE_MSG_NAV_POSLLH,
|
||||
UBX_CONFIG_STATE_MSG_NAV_TIMEUTC,
|
||||
UBX_CONFIG_STATE_MSG_NAV_DOP,
|
||||
UBX_CONFIG_STATE_MSG_NAV_SVINFO,
|
||||
UBX_CONFIG_STATE_MSG_NAV_SOL,
|
||||
UBX_CONFIG_STATE_MSG_NAV_VELNED,
|
||||
// UBX_CONFIG_STATE_MSG_RXM_SVSI,
|
||||
UBX_CONFIG_STATE_CONFIGURED
|
||||
} ubx_config_state_t;
|
||||
|
||||
typedef enum {
|
||||
CLASS_UNKNOWN = 0,
|
||||
NAV = 1,
|
||||
RXM = 2,
|
||||
ACK = 3,
|
||||
CFG = 4
|
||||
} ubx_message_class_t;
|
||||
|
||||
typedef enum {
|
||||
//these numbers do NOT correspond to the message id numbers of the ubx protocol
|
||||
ID_UNKNOWN = 0,
|
||||
NAV_POSLLH,
|
||||
NAV_SOL,
|
||||
NAV_TIMEUTC,
|
||||
// NAV_DOP,
|
||||
NAV_SVINFO,
|
||||
NAV_VELNED,
|
||||
// RXM_SVSI,
|
||||
CFG_NAV5,
|
||||
ACK_ACK,
|
||||
ACK_NAK,
|
||||
} ubx_message_id_t;
|
||||
|
||||
typedef enum {
|
||||
UBX_DECODE_UNINIT = 0,
|
||||
UBX_DECODE_GOT_SYNC1,
|
||||
UBX_DECODE_GOT_SYNC2,
|
||||
UBX_DECODE_GOT_CLASS,
|
||||
UBX_DECODE_GOT_MESSAGEID,
|
||||
UBX_DECODE_GOT_LENGTH1,
|
||||
UBX_DECODE_GOT_LENGTH2
|
||||
} ubx_decode_state_t;
|
||||
|
||||
//typedef type_gps_bin_ubx_state gps_bin_ubx_state_t;
|
||||
#pragma pack(pop)
|
||||
|
||||
#define RECV_BUFFER_SIZE 500 //The NAV-SOL messages really need such a big buffer
|
||||
|
||||
class UBX : public GPS_Helper
|
||||
{
|
||||
public:
|
||||
UBX(const int &fd, struct vehicle_gps_position_s *gps_position);
|
||||
~UBX();
|
||||
int receive(unsigned timeout);
|
||||
int configure(unsigned &baudrate);
|
||||
|
||||
private:
|
||||
|
||||
/**
|
||||
* Parse the binary MTK packet
|
||||
*/
|
||||
int parse_char(uint8_t b);
|
||||
|
||||
/**
|
||||
* Handle the package once it has arrived
|
||||
*/
|
||||
int handle_message(void);
|
||||
|
||||
/**
|
||||
* Reset the parse state machine for a fresh start
|
||||
*/
|
||||
void decode_init(void);
|
||||
|
||||
/**
|
||||
* While parsing add every byte (except the sync bytes) to the checksum
|
||||
*/
|
||||
void add_byte_to_checksum(uint8_t);
|
||||
|
||||
/**
|
||||
* Add the two checksum bytes to an outgoing message
|
||||
*/
|
||||
void add_checksum_to_message(uint8_t* message, const unsigned length);
|
||||
|
||||
/**
|
||||
* Helper to send a config packet
|
||||
*/
|
||||
void send_config_packet(const int &fd, uint8_t *packet, const unsigned length);
|
||||
|
||||
int _fd;
|
||||
struct vehicle_gps_position_s *_gps_position;
|
||||
ubx_config_state_t _config_state;
|
||||
bool _waiting_for_ack;
|
||||
uint8_t _clsID_needed;
|
||||
uint8_t _msgID_needed;
|
||||
ubx_decode_state_t _decode_state;
|
||||
uint8_t _rx_buffer[RECV_BUFFER_SIZE];
|
||||
unsigned _rx_count;
|
||||
uint8_t _rx_ck_a;
|
||||
uint8_t _rx_ck_b;
|
||||
ubx_message_class_t _message_class;
|
||||
ubx_message_id_t _message_id;
|
||||
unsigned _payload_size;
|
||||
};
|
||||
|
||||
#endif /* UBX_H_ */
|
||||
@@ -0,0 +1,851 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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 hil.cpp
|
||||
*
|
||||
* Driver/configurator for the virtual HIL port.
|
||||
*
|
||||
* This virtual driver emulates PWM / servo outputs for setups where
|
||||
* the connected hardware does not provide enough or no PWM outputs.
|
||||
*
|
||||
* Its only function is to take actuator_control uORB messages,
|
||||
* mix them with any loaded mixer and output the result to the
|
||||
* actuator_output uORB topic. HIL can also be performed with normal
|
||||
* PWM outputs, a special flag prevents the outputs to be operated
|
||||
* during HIL mode. If HIL is not performed with a standalone FMU,
|
||||
* but in a real system, it is NOT recommended to use this virtual
|
||||
* driver. Use instead the normal FMU or IO driver.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
#include <semaphore.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
|
||||
#include <drivers/device/device.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <drivers/drv_gpio.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_mixer.h>
|
||||
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/mixer/mixer.h>
|
||||
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/actuator_outputs.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
|
||||
class HIL : public device::CDev
|
||||
{
|
||||
public:
|
||||
enum Mode {
|
||||
MODE_2PWM,
|
||||
MODE_4PWM,
|
||||
MODE_8PWM,
|
||||
MODE_12PWM,
|
||||
MODE_16PWM,
|
||||
MODE_NONE
|
||||
};
|
||||
HIL();
|
||||
virtual ~HIL();
|
||||
|
||||
virtual int ioctl(file *filp, int cmd, unsigned long arg);
|
||||
|
||||
virtual int init();
|
||||
|
||||
int set_mode(Mode mode);
|
||||
int set_pwm_rate(unsigned rate);
|
||||
|
||||
private:
|
||||
static const unsigned _max_actuators = 4;
|
||||
|
||||
Mode _mode;
|
||||
int _update_rate;
|
||||
int _current_update_rate;
|
||||
int _task;
|
||||
int _t_actuators;
|
||||
int _t_armed;
|
||||
orb_advert_t _t_outputs;
|
||||
unsigned _num_outputs;
|
||||
bool _primary_pwm_device;
|
||||
|
||||
volatile bool _task_should_exit;
|
||||
bool _armed;
|
||||
|
||||
MixerGroup *_mixers;
|
||||
|
||||
actuator_controls_s _controls;
|
||||
|
||||
static void task_main_trampoline(int argc, char *argv[]);
|
||||
void task_main() __attribute__((noreturn));
|
||||
|
||||
static int control_callback(uintptr_t handle,
|
||||
uint8_t control_group,
|
||||
uint8_t control_index,
|
||||
float &input);
|
||||
|
||||
int pwm_ioctl(file *filp, int cmd, unsigned long arg);
|
||||
|
||||
struct GPIOConfig {
|
||||
uint32_t input;
|
||||
uint32_t output;
|
||||
uint32_t alt;
|
||||
};
|
||||
|
||||
static const GPIOConfig _gpio_tab[];
|
||||
static const unsigned _ngpio;
|
||||
|
||||
void gpio_reset(void);
|
||||
void gpio_set_function(uint32_t gpios, int function);
|
||||
void gpio_write(uint32_t gpios, int function);
|
||||
uint32_t gpio_read(void);
|
||||
int gpio_ioctl(file *filp, int cmd, unsigned long arg);
|
||||
|
||||
};
|
||||
|
||||
namespace
|
||||
{
|
||||
|
||||
HIL *g_hil;
|
||||
|
||||
} // namespace
|
||||
|
||||
HIL::HIL() :
|
||||
CDev("hilservo", PWM_OUTPUT_DEVICE_PATH/*"/dev/hil" XXXL*/),
|
||||
_mode(MODE_NONE),
|
||||
_update_rate(50),
|
||||
_current_update_rate(0),
|
||||
_task(-1),
|
||||
_t_actuators(-1),
|
||||
_t_armed(-1),
|
||||
_t_outputs(0),
|
||||
_num_outputs(0),
|
||||
_primary_pwm_device(false),
|
||||
_task_should_exit(false),
|
||||
_armed(false),
|
||||
_mixers(nullptr)
|
||||
{
|
||||
_debug_enabled = true;
|
||||
}
|
||||
|
||||
HIL::~HIL()
|
||||
{
|
||||
if (_task != -1) {
|
||||
/* tell the task we want it to go away */
|
||||
_task_should_exit = true;
|
||||
|
||||
unsigned i = 10;
|
||||
do {
|
||||
/* wait 50ms - it should wake every 100ms or so worst-case */
|
||||
usleep(50000);
|
||||
|
||||
/* if we have given up, kill it */
|
||||
if (--i == 0) {
|
||||
task_delete(_task);
|
||||
break;
|
||||
}
|
||||
|
||||
} while (_task != -1);
|
||||
}
|
||||
|
||||
/* clean up the alternate device node */
|
||||
if (_primary_pwm_device)
|
||||
unregister_driver(PWM_OUTPUT_DEVICE_PATH);
|
||||
|
||||
g_hil = nullptr;
|
||||
}
|
||||
|
||||
int
|
||||
HIL::init()
|
||||
{
|
||||
int ret;
|
||||
|
||||
ASSERT(_task == -1);
|
||||
|
||||
/* do regular cdev init */
|
||||
ret = CDev::init();
|
||||
|
||||
if (ret != OK)
|
||||
return ret;
|
||||
|
||||
// XXX already claimed with CDEV
|
||||
///* try to claim the generic PWM output device node as well - it's OK if we fail at this */
|
||||
//ret = register_driver(PWM_OUTPUT_DEVICE_PATH, &fops, 0666, (void *)this);
|
||||
if (ret == OK) {
|
||||
log("default PWM output device");
|
||||
_primary_pwm_device = true;
|
||||
}
|
||||
|
||||
/* reset GPIOs */
|
||||
// gpio_reset();
|
||||
|
||||
/* start the HIL interface task */
|
||||
_task = task_spawn("fmuhil",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
2048,
|
||||
(main_t)&HIL::task_main_trampoline,
|
||||
nullptr);
|
||||
|
||||
if (_task < 0) {
|
||||
debug("task start failed: %d", errno);
|
||||
return -errno;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
void
|
||||
HIL::task_main_trampoline(int argc, char *argv[])
|
||||
{
|
||||
g_hil->task_main();
|
||||
}
|
||||
|
||||
int
|
||||
HIL::set_mode(Mode mode)
|
||||
{
|
||||
/*
|
||||
* Configure for PWM output.
|
||||
*
|
||||
* Note that regardless of the configured mode, the task is always
|
||||
* listening and mixing; the mode just selects which of the channels
|
||||
* are presented on the output pins.
|
||||
*/
|
||||
switch (mode) {
|
||||
case MODE_2PWM:
|
||||
debug("MODE_2PWM");
|
||||
/* multi-port with flow control lines as PWM */
|
||||
_update_rate = 50; /* default output rate */
|
||||
break;
|
||||
|
||||
case MODE_4PWM:
|
||||
debug("MODE_4PWM");
|
||||
/* multi-port as 4 PWM outs */
|
||||
_update_rate = 50; /* default output rate */
|
||||
break;
|
||||
|
||||
case MODE_8PWM:
|
||||
debug("MODE_8PWM");
|
||||
/* multi-port as 8 PWM outs */
|
||||
_update_rate = 50; /* default output rate */
|
||||
break;
|
||||
|
||||
case MODE_12PWM:
|
||||
debug("MODE_12PWM");
|
||||
/* multi-port as 12 PWM outs */
|
||||
_update_rate = 50; /* default output rate */
|
||||
break;
|
||||
|
||||
case MODE_16PWM:
|
||||
debug("MODE_16PWM");
|
||||
/* multi-port as 16 PWM outs */
|
||||
_update_rate = 50; /* default output rate */
|
||||
break;
|
||||
|
||||
case MODE_NONE:
|
||||
debug("MODE_NONE");
|
||||
/* disable servo outputs and set a very low update rate */
|
||||
_update_rate = 10;
|
||||
break;
|
||||
|
||||
default:
|
||||
return -EINVAL;
|
||||
}
|
||||
_mode = mode;
|
||||
return OK;
|
||||
}
|
||||
|
||||
int
|
||||
HIL::set_pwm_rate(unsigned rate)
|
||||
{
|
||||
if ((rate > 500) || (rate < 10))
|
||||
return -EINVAL;
|
||||
|
||||
_update_rate = rate;
|
||||
return OK;
|
||||
}
|
||||
|
||||
void
|
||||
HIL::task_main()
|
||||
{
|
||||
/*
|
||||
* Subscribe to the appropriate PWM output topic based on whether we are the
|
||||
* primary PWM output or not.
|
||||
*/
|
||||
_t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
|
||||
ORB_ID(actuator_controls_1));
|
||||
/* force a reset of the update rate */
|
||||
_current_update_rate = 0;
|
||||
|
||||
_t_armed = orb_subscribe(ORB_ID(actuator_armed));
|
||||
orb_set_interval(_t_armed, 200); /* 5Hz update rate */
|
||||
|
||||
/* advertise the mixed control outputs */
|
||||
actuator_outputs_s outputs;
|
||||
memset(&outputs, 0, sizeof(outputs));
|
||||
/* advertise the mixed control outputs */
|
||||
_t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1),
|
||||
&outputs);
|
||||
|
||||
pollfd fds[2];
|
||||
fds[0].fd = _t_actuators;
|
||||
fds[0].events = POLLIN;
|
||||
fds[1].fd = _t_armed;
|
||||
fds[1].events = POLLIN;
|
||||
|
||||
unsigned num_outputs;
|
||||
|
||||
/* select the number of virtual outputs */
|
||||
switch (_mode) {
|
||||
case MODE_2PWM:
|
||||
num_outputs = 2;
|
||||
break;
|
||||
|
||||
case MODE_4PWM:
|
||||
num_outputs = 4;
|
||||
break;
|
||||
|
||||
case MODE_8PWM:
|
||||
case MODE_12PWM:
|
||||
case MODE_16PWM:
|
||||
// XXX only support the lower 8 - trivial to extend
|
||||
num_outputs = 8;
|
||||
break;
|
||||
|
||||
case MODE_NONE:
|
||||
default:
|
||||
num_outputs = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
log("starting");
|
||||
|
||||
/* loop until killed */
|
||||
while (!_task_should_exit) {
|
||||
|
||||
/* handle update rate changes */
|
||||
if (_current_update_rate != _update_rate) {
|
||||
int update_rate_in_ms = int(1000 / _update_rate);
|
||||
if (update_rate_in_ms < 2)
|
||||
update_rate_in_ms = 2;
|
||||
orb_set_interval(_t_actuators, update_rate_in_ms);
|
||||
// up_pwm_servo_set_rate(_update_rate);
|
||||
_current_update_rate = _update_rate;
|
||||
}
|
||||
|
||||
/* sleep waiting for data, but no more than a second */
|
||||
int ret = ::poll(&fds[0], 2, 1000);
|
||||
|
||||
/* this would be bad... */
|
||||
if (ret < 0) {
|
||||
log("poll error %d", errno);
|
||||
continue;
|
||||
}
|
||||
|
||||
/* do we have a control update? */
|
||||
if (fds[0].revents & POLLIN) {
|
||||
|
||||
/* get controls - must always do this to avoid spinning */
|
||||
orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _t_actuators, &_controls);
|
||||
|
||||
/* can we mix? */
|
||||
if (_mixers != nullptr) {
|
||||
|
||||
/* do mixing */
|
||||
outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs);
|
||||
outputs.timestamp = hrt_absolute_time();
|
||||
|
||||
/* iterate actuators */
|
||||
for (unsigned i = 0; i < num_outputs; i++) {
|
||||
|
||||
/* last resort: catch NaN, INF and out-of-band errors */
|
||||
if (i < (unsigned)outputs.noutputs &&
|
||||
isfinite(outputs.output[i]) &&
|
||||
outputs.output[i] >= -1.0f &&
|
||||
outputs.output[i] <= 1.0f) {
|
||||
/* scale for PWM output 900 - 2100us */
|
||||
outputs.output[i] = 1500 + (600 * outputs.output[i]);
|
||||
} else {
|
||||
/*
|
||||
* Value is NaN, INF or out of band - set to the minimum value.
|
||||
* This will be clearly visible on the servo status and will limit the risk of accidentally
|
||||
* spinning motors. It would be deadly in flight.
|
||||
*/
|
||||
outputs.output[i] = 900;
|
||||
}
|
||||
}
|
||||
|
||||
/* and publish for anyone that cares to see */
|
||||
orb_publish(ORB_ID_VEHICLE_CONTROLS, _t_outputs, &outputs);
|
||||
}
|
||||
}
|
||||
|
||||
/* how about an arming update? */
|
||||
if (fds[1].revents & POLLIN) {
|
||||
actuator_armed_s aa;
|
||||
|
||||
/* get new value */
|
||||
orb_copy(ORB_ID(actuator_armed), _t_armed, &aa);
|
||||
}
|
||||
}
|
||||
|
||||
::close(_t_actuators);
|
||||
::close(_t_armed);
|
||||
|
||||
/* make sure servos are off */
|
||||
// up_pwm_servo_deinit();
|
||||
|
||||
log("stopping");
|
||||
|
||||
/* note - someone else is responsible for restoring the GPIO config */
|
||||
|
||||
/* tell the dtor that we are exiting */
|
||||
_task = -1;
|
||||
_exit(0);
|
||||
}
|
||||
|
||||
int
|
||||
HIL::control_callback(uintptr_t handle,
|
||||
uint8_t control_group,
|
||||
uint8_t control_index,
|
||||
float &input)
|
||||
{
|
||||
const actuator_controls_s *controls = (actuator_controls_s *)handle;
|
||||
|
||||
input = controls->control[control_index];
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
HIL::ioctl(file *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
int ret;
|
||||
|
||||
debug("ioctl 0x%04x 0x%08x", cmd, arg);
|
||||
|
||||
// /* try it as a GPIO ioctl first */
|
||||
// ret = HIL::gpio_ioctl(filp, cmd, arg);
|
||||
// if (ret != -ENOTTY)
|
||||
// return ret;
|
||||
|
||||
/* if we are in valid PWM mode, try it as a PWM ioctl as well */
|
||||
switch(_mode) {
|
||||
case MODE_2PWM:
|
||||
case MODE_4PWM:
|
||||
case MODE_8PWM:
|
||||
case MODE_12PWM:
|
||||
case MODE_16PWM:
|
||||
ret = HIL::pwm_ioctl(filp, cmd, arg);
|
||||
break;
|
||||
default:
|
||||
ret = -ENOTTY;
|
||||
debug("not in a PWM mode");
|
||||
break;
|
||||
}
|
||||
|
||||
/* if nobody wants it, let CDev have it */
|
||||
if (ret == -ENOTTY)
|
||||
ret = CDev::ioctl(filp, cmd, arg);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
HIL::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
int ret = OK;
|
||||
// int channel;
|
||||
|
||||
lock();
|
||||
|
||||
switch (cmd) {
|
||||
case PWM_SERVO_ARM:
|
||||
// up_pwm_servo_arm(true);
|
||||
break;
|
||||
|
||||
case PWM_SERVO_DISARM:
|
||||
// up_pwm_servo_arm(false);
|
||||
break;
|
||||
|
||||
case PWM_SERVO_SET_UPDATE_RATE:
|
||||
// HIL always outputs at the alternate (usually faster) rate
|
||||
g_hil->set_pwm_rate(arg);
|
||||
break;
|
||||
|
||||
case PWM_SERVO_SELECT_UPDATE_RATE:
|
||||
// HIL always outputs at the alternate (usually faster) rate
|
||||
break;
|
||||
|
||||
case PWM_SERVO_SET(2):
|
||||
case PWM_SERVO_SET(3):
|
||||
if (_mode != MODE_4PWM) {
|
||||
ret = -EINVAL;
|
||||
break;
|
||||
}
|
||||
|
||||
/* FALLTHROUGH */
|
||||
case PWM_SERVO_SET(0):
|
||||
case PWM_SERVO_SET(1):
|
||||
if (arg < 2100) {
|
||||
// channel = cmd - PWM_SERVO_SET(0);
|
||||
// up_pwm_servo_set(channel, arg); XXX
|
||||
|
||||
} else {
|
||||
ret = -EINVAL;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case PWM_SERVO_GET(2):
|
||||
case PWM_SERVO_GET(3):
|
||||
if (_mode != MODE_4PWM) {
|
||||
ret = -EINVAL;
|
||||
break;
|
||||
}
|
||||
|
||||
/* FALLTHROUGH */
|
||||
case PWM_SERVO_GET(0):
|
||||
case PWM_SERVO_GET(1): {
|
||||
// channel = cmd - PWM_SERVO_SET(0);
|
||||
// *(servo_position_t *)arg = up_pwm_servo_get(channel);
|
||||
break;
|
||||
}
|
||||
|
||||
case PWM_SERVO_GET_RATEGROUP(0) ... PWM_SERVO_GET_RATEGROUP(PWM_OUTPUT_MAX_CHANNELS - 1): {
|
||||
// no restrictions on output grouping
|
||||
unsigned channel = cmd - PWM_SERVO_GET_RATEGROUP(0);
|
||||
|
||||
*(uint32_t *)arg = (1 << channel);
|
||||
break;
|
||||
}
|
||||
|
||||
case MIXERIOCGETOUTPUTCOUNT:
|
||||
if (_mode == MODE_4PWM) {
|
||||
*(unsigned *)arg = 4;
|
||||
|
||||
} else {
|
||||
*(unsigned *)arg = 2;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case MIXERIOCRESET:
|
||||
if (_mixers != nullptr) {
|
||||
delete _mixers;
|
||||
_mixers = nullptr;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case MIXERIOCADDSIMPLE: {
|
||||
mixer_simple_s *mixinfo = (mixer_simple_s *)arg;
|
||||
|
||||
SimpleMixer *mixer = new SimpleMixer(control_callback,
|
||||
(uintptr_t)&_controls, mixinfo);
|
||||
|
||||
if (mixer->check()) {
|
||||
delete mixer;
|
||||
ret = -EINVAL;
|
||||
|
||||
} else {
|
||||
if (_mixers == nullptr)
|
||||
_mixers = new MixerGroup(control_callback,
|
||||
(uintptr_t)&_controls);
|
||||
|
||||
_mixers->add_mixer(mixer);
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
case MIXERIOCLOADBUF: {
|
||||
const char *buf = (const char *)arg;
|
||||
unsigned buflen = strnlen(buf, 1024);
|
||||
|
||||
if (_mixers == nullptr)
|
||||
_mixers = new MixerGroup(control_callback, (uintptr_t)&_controls);
|
||||
|
||||
if (_mixers == nullptr) {
|
||||
ret = -ENOMEM;
|
||||
|
||||
} else {
|
||||
|
||||
ret = _mixers->load_from_buf(buf, buflen);
|
||||
|
||||
if (ret != 0) {
|
||||
debug("mixer load failed with %d", ret);
|
||||
delete _mixers;
|
||||
_mixers = nullptr;
|
||||
ret = -EINVAL;
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
default:
|
||||
ret = -ENOTTY;
|
||||
break;
|
||||
}
|
||||
|
||||
unlock();
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
namespace
|
||||
{
|
||||
|
||||
enum PortMode {
|
||||
PORT_MODE_UNDEFINED = 0,
|
||||
PORT1_MODE_UNSET,
|
||||
PORT1_FULL_PWM,
|
||||
PORT1_PWM_AND_SERIAL,
|
||||
PORT1_PWM_AND_GPIO,
|
||||
PORT2_MODE_UNSET,
|
||||
PORT2_8PWM,
|
||||
PORT2_12PWM,
|
||||
PORT2_16PWM,
|
||||
};
|
||||
|
||||
PortMode g_port_mode;
|
||||
|
||||
int
|
||||
hil_new_mode(PortMode new_mode)
|
||||
{
|
||||
// uint32_t gpio_bits;
|
||||
|
||||
|
||||
// /* reset to all-inputs */
|
||||
// g_hil->ioctl(0, GPIO_RESET, 0);
|
||||
|
||||
// gpio_bits = 0;
|
||||
|
||||
HIL::Mode servo_mode = HIL::MODE_NONE;
|
||||
|
||||
switch (new_mode) {
|
||||
case PORT_MODE_UNDEFINED:
|
||||
case PORT1_MODE_UNSET:
|
||||
case PORT2_MODE_UNSET:
|
||||
/* nothing more to do here */
|
||||
break;
|
||||
|
||||
case PORT1_FULL_PWM:
|
||||
/* select 4-pin PWM mode */
|
||||
servo_mode = HIL::MODE_4PWM;
|
||||
break;
|
||||
|
||||
case PORT1_PWM_AND_SERIAL:
|
||||
/* select 2-pin PWM mode */
|
||||
servo_mode = HIL::MODE_2PWM;
|
||||
// /* set RX/TX multi-GPIOs to serial mode */
|
||||
// gpio_bits = GPIO_MULTI_3 | GPIO_MULTI_4;
|
||||
break;
|
||||
|
||||
case PORT1_PWM_AND_GPIO:
|
||||
/* select 2-pin PWM mode */
|
||||
servo_mode = HIL::MODE_2PWM;
|
||||
break;
|
||||
|
||||
case PORT2_8PWM:
|
||||
/* select 8-pin PWM mode */
|
||||
servo_mode = HIL::MODE_8PWM;
|
||||
break;
|
||||
|
||||
case PORT2_12PWM:
|
||||
/* select 12-pin PWM mode */
|
||||
servo_mode = HIL::MODE_12PWM;
|
||||
break;
|
||||
|
||||
case PORT2_16PWM:
|
||||
/* select 16-pin PWM mode */
|
||||
servo_mode = HIL::MODE_16PWM;
|
||||
break;
|
||||
}
|
||||
|
||||
// /* adjust GPIO config for serial mode(s) */
|
||||
// if (gpio_bits != 0)
|
||||
// g_hil->ioctl(0, GPIO_SET_ALT_1, gpio_bits);
|
||||
|
||||
/* (re)set the PWM output mode */
|
||||
g_hil->set_mode(servo_mode);
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int
|
||||
hil_start(void)
|
||||
{
|
||||
int ret = OK;
|
||||
|
||||
if (g_hil == nullptr) {
|
||||
|
||||
g_hil = new HIL;
|
||||
|
||||
if (g_hil == nullptr) {
|
||||
ret = -ENOMEM;
|
||||
|
||||
} else {
|
||||
ret = g_hil->init();
|
||||
|
||||
if (ret != OK) {
|
||||
delete g_hil;
|
||||
g_hil = nullptr;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void
|
||||
test(void)
|
||||
{
|
||||
int fd;
|
||||
|
||||
fd = open(PWM_OUTPUT_DEVICE_PATH, 0);
|
||||
|
||||
if (fd < 0) {
|
||||
puts("open fail");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
ioctl(fd, PWM_SERVO_ARM, 0);
|
||||
ioctl(fd, PWM_SERVO_SET(0), 1000);
|
||||
|
||||
close(fd);
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
void
|
||||
fake(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 5) {
|
||||
puts("hil fake <roll> <pitch> <yaw> <thrust> (values -100 .. 100)");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
actuator_controls_s ac;
|
||||
|
||||
ac.control[0] = strtol(argv[1], 0, 0) / 100.0f;
|
||||
|
||||
ac.control[1] = strtol(argv[2], 0, 0) / 100.0f;
|
||||
|
||||
ac.control[2] = strtol(argv[3], 0, 0) / 100.0f;
|
||||
|
||||
ac.control[3] = strtol(argv[4], 0, 0) / 100.0f;
|
||||
|
||||
orb_advert_t handle = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &ac);
|
||||
|
||||
if (handle < 0) {
|
||||
puts("advertise failed");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
extern "C" __EXPORT int hil_main(int argc, char *argv[]);
|
||||
|
||||
int
|
||||
hil_main(int argc, char *argv[])
|
||||
{
|
||||
PortMode new_mode = PORT_MODE_UNDEFINED;
|
||||
const char *verb = argv[1];
|
||||
|
||||
if (hil_start() != OK)
|
||||
errx(1, "failed to start the HIL driver");
|
||||
|
||||
/*
|
||||
* Mode switches.
|
||||
*/
|
||||
|
||||
// this was all cut-and-pasted from the FMU driver; it's junk
|
||||
if (!strcmp(verb, "mode_pwm")) {
|
||||
new_mode = PORT1_FULL_PWM;
|
||||
|
||||
} else if (!strcmp(verb, "mode_pwm_serial")) {
|
||||
new_mode = PORT1_PWM_AND_SERIAL;
|
||||
|
||||
} else if (!strcmp(verb, "mode_pwm_gpio")) {
|
||||
new_mode = PORT1_PWM_AND_GPIO;
|
||||
|
||||
} else if (!strcmp(verb, "mode_port2_pwm8")) {
|
||||
new_mode = PORT2_8PWM;
|
||||
|
||||
} else if (!strcmp(verb, "mode_port2_pwm12")) {
|
||||
new_mode = PORT2_8PWM;
|
||||
|
||||
} else if (!strcmp(verb, "mode_port2_pwm16")) {
|
||||
new_mode = PORT2_8PWM;
|
||||
}
|
||||
|
||||
/* was a new mode set? */
|
||||
if (new_mode != PORT_MODE_UNDEFINED) {
|
||||
|
||||
/* yes but it's the same mode */
|
||||
if (new_mode == g_port_mode)
|
||||
return OK;
|
||||
|
||||
/* switch modes */
|
||||
return hil_new_mode(new_mode);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "test"))
|
||||
test();
|
||||
|
||||
if (!strcmp(verb, "fake"))
|
||||
fake(argc - 1, argv + 1);
|
||||
|
||||
|
||||
fprintf(stderr, "HIL: unrecognized command, try:\n");
|
||||
fprintf(stderr, " mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio, mode_port2_pwm8, mode_port2_pwm12, mode_port2_pwm16\n");
|
||||
return -EINVAL;
|
||||
}
|
||||
@@ -0,0 +1,40 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Hardware in the Loop (HIL) simulation actuator output bank
|
||||
#
|
||||
|
||||
MODULE_COMMAND = hil
|
||||
|
||||
SRCS = hil.cpp
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,43 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# HMC5883 driver
|
||||
#
|
||||
|
||||
MODULE_COMMAND = hmc5883
|
||||
|
||||
# XXX seems excessive, check if 2048 is sufficient
|
||||
MODULE_STACKSIZE = 4096
|
||||
|
||||
SRCS = hmc5883.cpp
|
||||
@@ -0,0 +1,306 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Simon Wilks <sjwilks@gmail.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file hott_telemetry_main.c
|
||||
* @author Simon Wilks <sjwilks@gmail.com>
|
||||
*
|
||||
* Graupner HoTT Telemetry implementation.
|
||||
*
|
||||
* The HoTT receiver polls each device at a regular interval at which point
|
||||
* a data packet can be returned if necessary.
|
||||
*
|
||||
* TODO: Add support for at least the vario and GPS sensor data.
|
||||
*/
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <poll.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <termios.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <unistd.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
#include "messages.h"
|
||||
|
||||
static int thread_should_exit = false; /**< Deamon exit flag */
|
||||
static int thread_running = false; /**< Deamon status flag */
|
||||
static int deamon_task; /**< Handle of deamon task / thread */
|
||||
static char *daemon_name = "hott_telemetry";
|
||||
static char *commandline_usage = "usage: hott_telemetry start|status|stop [-d <device>]";
|
||||
|
||||
|
||||
/* A little console messaging experiment - console helper macro */
|
||||
#define FATAL_MSG(_msg) fprintf(stderr, "[%s] %s\n", daemon_name, _msg); exit(1);
|
||||
#define ERROR_MSG(_msg) fprintf(stderr, "[%s] %s\n", daemon_name, _msg);
|
||||
#define INFO_MSG(_msg) printf("[%s] %s\n", daemon_name, _msg);
|
||||
/**
|
||||
* Deamon management function.
|
||||
*/
|
||||
__EXPORT int hott_telemetry_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Mainloop of deamon.
|
||||
*/
|
||||
int hott_telemetry_thread_main(int argc, char *argv[]);
|
||||
|
||||
static int read_data(int uart, int *id);
|
||||
static int send_data(int uart, uint8_t *buffer, int size);
|
||||
|
||||
static int open_uart(const char *device, struct termios *uart_config_original)
|
||||
{
|
||||
/* baud rate */
|
||||
int speed = B19200;
|
||||
int uart;
|
||||
|
||||
/* open uart */
|
||||
uart = open(device, O_RDWR | O_NOCTTY);
|
||||
|
||||
if (uart < 0) {
|
||||
char msg[80];
|
||||
sprintf(msg, "Error opening port: %s\n", device);
|
||||
FATAL_MSG(msg);
|
||||
}
|
||||
|
||||
/* Try to set baud rate */
|
||||
struct termios uart_config;
|
||||
int termios_state;
|
||||
|
||||
/* Back up the original uart configuration to restore it after exit */
|
||||
char msg[80];
|
||||
|
||||
if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
|
||||
sprintf(msg, "Error getting baudrate / termios config for %s: %d\n", device, termios_state);
|
||||
close(uart);
|
||||
FATAL_MSG(msg);
|
||||
}
|
||||
|
||||
/* Fill the struct for the new configuration */
|
||||
tcgetattr(uart, &uart_config);
|
||||
|
||||
/* Clear ONLCR flag (which appends a CR for every LF) */
|
||||
uart_config.c_oflag &= ~ONLCR;
|
||||
|
||||
/* Set baud rate */
|
||||
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
|
||||
sprintf(msg, "Error setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n",
|
||||
device, termios_state);
|
||||
close(uart);
|
||||
FATAL_MSG(msg);
|
||||
}
|
||||
|
||||
if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
|
||||
sprintf(msg, "Error setting baudrate / termios config for %s (tcsetattr)\n", device);
|
||||
close(uart);
|
||||
FATAL_MSG(msg);
|
||||
}
|
||||
|
||||
/* Activate single wire mode */
|
||||
ioctl(uart, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED);
|
||||
|
||||
return uart;
|
||||
}
|
||||
|
||||
int read_data(int uart, int *id)
|
||||
{
|
||||
const int timeout = 1000;
|
||||
struct pollfd fds[] = { { .fd = uart, .events = POLLIN } };
|
||||
|
||||
char mode;
|
||||
|
||||
if (poll(fds, 1, timeout) > 0) {
|
||||
/* Get the mode: binary or text */
|
||||
read(uart, &mode, 1);
|
||||
/* Read the device ID being polled */
|
||||
read(uart, id, 1);
|
||||
|
||||
/* if we have a binary mode request */
|
||||
if (mode != BINARY_MODE_REQUEST_ID) {
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
} else {
|
||||
ERROR_MSG("UART timeout on TX/RX port");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int send_data(int uart, uint8_t *buffer, int size)
|
||||
{
|
||||
usleep(POST_READ_DELAY_IN_USECS);
|
||||
|
||||
uint16_t checksum = 0;
|
||||
|
||||
for (int i = 0; i < size; i++) {
|
||||
if (i == size - 1) {
|
||||
/* Set the checksum: the first uint8_t is taken as the checksum. */
|
||||
buffer[i] = checksum & 0xff;
|
||||
|
||||
} else {
|
||||
checksum += buffer[i];
|
||||
}
|
||||
|
||||
write(uart, &buffer[i], 1);
|
||||
|
||||
/* Sleep before sending the next byte. */
|
||||
usleep(POST_WRITE_DELAY_IN_USECS);
|
||||
}
|
||||
|
||||
/* A hack the reads out what was written so the next read from the receiver doesn't get it. */
|
||||
/* TODO: Fix this!! */
|
||||
uint8_t dummy[size];
|
||||
read(uart, &dummy, size);
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int hott_telemetry_thread_main(int argc, char *argv[])
|
||||
{
|
||||
INFO_MSG("starting");
|
||||
|
||||
thread_running = true;
|
||||
|
||||
char *device = "/dev/ttyS1"; /**< Default telemetry port: USART2 */
|
||||
|
||||
/* read commandline arguments */
|
||||
for (int i = 0; i < argc && argv[i]; i++) {
|
||||
if (strcmp(argv[i], "-d") == 0 || strcmp(argv[i], "--device") == 0) { //device set
|
||||
if (argc > i + 1) {
|
||||
device = argv[i + 1];
|
||||
|
||||
} else {
|
||||
thread_running = false;
|
||||
ERROR_MSG("missing parameter to -d");
|
||||
ERROR_MSG(commandline_usage);
|
||||
exit(1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* enable UART, writes potentially an empty buffer, but multiplexing is disabled */
|
||||
struct termios uart_config_original;
|
||||
int uart = open_uart(device, &uart_config_original);
|
||||
|
||||
if (uart < 0) {
|
||||
ERROR_MSG("Failed opening HoTT UART, exiting.");
|
||||
thread_running = false;
|
||||
exit(ERROR);
|
||||
}
|
||||
|
||||
messages_init();
|
||||
|
||||
uint8_t buffer[MESSAGE_BUFFER_SIZE];
|
||||
int size = 0;
|
||||
int id = 0;
|
||||
|
||||
while (!thread_should_exit) {
|
||||
if (read_data(uart, &id) == OK) {
|
||||
switch (id) {
|
||||
case ELECTRIC_AIR_MODULE:
|
||||
build_eam_response(buffer, &size);
|
||||
break;
|
||||
|
||||
default:
|
||||
continue; // Not a module we support.
|
||||
}
|
||||
|
||||
send_data(uart, buffer, size);
|
||||
}
|
||||
}
|
||||
|
||||
INFO_MSG("exiting");
|
||||
|
||||
close(uart);
|
||||
|
||||
thread_running = false;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Process command line arguments and tart the daemon.
|
||||
*/
|
||||
int hott_telemetry_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 1) {
|
||||
ERROR_MSG("missing command");
|
||||
ERROR_MSG(commandline_usage);
|
||||
exit(1);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
if (thread_running) {
|
||||
INFO_MSG("deamon already running");
|
||||
exit(0);
|
||||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("hott_telemetry",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 40,
|
||||
2048,
|
||||
hott_telemetry_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "stop")) {
|
||||
thread_should_exit = true;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
if (thread_running) {
|
||||
INFO_MSG("daemon is running");
|
||||
|
||||
} else {
|
||||
INFO_MSG("daemon not started");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
ERROR_MSG("unrecognized command");
|
||||
ERROR_MSG(commandline_usage);
|
||||
exit(1);
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -0,0 +1,87 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Simon Wilks <sjwilks@gmail.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file messages.c
|
||||
* @author Simon Wilks <sjwilks@gmail.com>
|
||||
*/
|
||||
|
||||
#include "messages.h"
|
||||
|
||||
#include <string.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <unistd.h>
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
|
||||
static int battery_sub = -1;
|
||||
static int sensor_sub = -1;
|
||||
|
||||
void messages_init(void)
|
||||
{
|
||||
battery_sub = orb_subscribe(ORB_ID(battery_status));
|
||||
sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
|
||||
}
|
||||
|
||||
void build_eam_response(uint8_t *buffer, int *size)
|
||||
{
|
||||
/* get a local copy of the current sensor values */
|
||||
struct sensor_combined_s raw;
|
||||
memset(&raw, 0, sizeof(raw));
|
||||
orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw);
|
||||
|
||||
/* get a local copy of the battery data */
|
||||
struct battery_status_s battery;
|
||||
memset(&battery, 0, sizeof(battery));
|
||||
orb_copy(ORB_ID(battery_status), battery_sub, &battery);
|
||||
|
||||
struct eam_module_msg msg;
|
||||
*size = sizeof(msg);
|
||||
memset(&msg, 0, *size);
|
||||
|
||||
msg.start = START_BYTE;
|
||||
msg.eam_sensor_id = ELECTRIC_AIR_MODULE;
|
||||
msg.sensor_id = EAM_SENSOR_ID;
|
||||
msg.temperature1 = (uint8_t)(raw.baro_temp_celcius + 20);
|
||||
msg.temperature2 = TEMP_ZERO_CELSIUS;
|
||||
msg.main_voltage_L = (uint8_t)(battery.voltage_v * 10);
|
||||
|
||||
uint16_t alt = (uint16_t)(raw.baro_alt_meter + 500);
|
||||
msg.altitude_L = (uint8_t)alt & 0xff;
|
||||
msg.altitude_H = (uint8_t)(alt >> 8) & 0xff;
|
||||
|
||||
msg.stop = STOP_BYTE;
|
||||
|
||||
memcpy(buffer, &msg, *size);
|
||||
}
|
||||
@@ -0,0 +1,124 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Simon Wilks <sjwilks@gmail.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file messages.h
|
||||
* @author Simon Wilks <sjwilks@gmail.com>
|
||||
*
|
||||
* Graupner HoTT Telemetry message generation.
|
||||
*
|
||||
*/
|
||||
#ifndef MESSAGES_H_
|
||||
#define MESSAGES_H
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
/* The buffer size used to store messages. This must be at least as big as the number of
|
||||
* fields in the largest message struct.
|
||||
*/
|
||||
#define MESSAGE_BUFFER_SIZE 50
|
||||
|
||||
/* The HoTT receiver demands a minimum 5ms period of silence after delivering its request.
|
||||
* Note that the value specified here is lower than 5000 (5ms) as time is lost constucting
|
||||
* the message after the read which takes some milliseconds.
|
||||
*/
|
||||
#define POST_READ_DELAY_IN_USECS 4000
|
||||
/* A pause of 3ms is required between each uint8_t sent back to the HoTT receiver. Much lower
|
||||
* values can be used in practise though.
|
||||
*/
|
||||
#define POST_WRITE_DELAY_IN_USECS 2000
|
||||
|
||||
// Protocol constants.
|
||||
#define BINARY_MODE_REQUEST_ID 0x80 // Binary mode request.
|
||||
#define START_BYTE 0x7c
|
||||
#define STOP_BYTE 0x7d
|
||||
#define TEMP_ZERO_CELSIUS 0x14
|
||||
|
||||
/* Electric Air Module (EAM) constants. */
|
||||
#define ELECTRIC_AIR_MODULE 0x8e
|
||||
#define EAM_SENSOR_ID 0xe0
|
||||
|
||||
/* The Electric Air Module message. */
|
||||
struct eam_module_msg {
|
||||
uint8_t start; /**< Start byte */
|
||||
uint8_t eam_sensor_id; /**< EAM sensor ID */
|
||||
uint8_t warning;
|
||||
uint8_t sensor_id; /**< Sensor ID, why different? */
|
||||
uint8_t alarm_inverse1;
|
||||
uint8_t alarm_inverse2;
|
||||
uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */
|
||||
uint8_t cell2_L;
|
||||
uint8_t cell3_L;
|
||||
uint8_t cell4_L;
|
||||
uint8_t cell5_L;
|
||||
uint8_t cell6_L;
|
||||
uint8_t cell7_L;
|
||||
uint8_t cell1_H;
|
||||
uint8_t cell2_H;
|
||||
uint8_t cell3_H;
|
||||
uint8_t cell4_H;
|
||||
uint8_t cell5_H;
|
||||
uint8_t cell6_H;
|
||||
uint8_t cell7_H;
|
||||
uint8_t batt1_voltage_L; /**< Battery 1 voltage, lower 8-bits in steps of 0.02V */
|
||||
uint8_t batt1_voltage_H;
|
||||
uint8_t batt2_voltage_L; /**< Battery 2 voltage, lower 8-bits in steps of 0.02V */
|
||||
uint8_t batt2_voltage_H;
|
||||
uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */
|
||||
uint8_t temperature2;
|
||||
uint8_t altitude_L; /**< Attitude (meters) lower 8-bits. 500 = 0 meters */
|
||||
uint8_t altitude_H;
|
||||
uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */
|
||||
uint8_t current_H;
|
||||
uint8_t main_voltage_L; /**< Main power voltage lower 8-bits in steps of 0.1V */
|
||||
uint8_t main_voltage_H;
|
||||
uint8_t battery_capacity_L; /**< Used battery capacity in steps of 10mAh */
|
||||
uint8_t battery_capacity_H;
|
||||
uint8_t climbrate_L; /**< Climb rate in 0.01m/s. 0m/s = 30000 */
|
||||
uint8_t climbrate_H;
|
||||
uint8_t climbrate_3s; /**< Climb rate in m/3sec. 0m/3sec = 120 */
|
||||
uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */
|
||||
uint8_t rpm_H;
|
||||
uint8_t electric_min; /**< Flight time in minutes. */
|
||||
uint8_t electric_sec; /**< Flight time in seconds. */
|
||||
uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */
|
||||
uint8_t speed_H;
|
||||
uint8_t stop; /**< Stop byte */
|
||||
uint8_t checksum; /**< Lower 8-bits of all bytes summed. */
|
||||
};
|
||||
|
||||
void messages_init(void);
|
||||
void build_eam_response(uint8_t *buffer, int *size);
|
||||
|
||||
#endif /* MESSAGES_H_ */
|
||||
@@ -0,0 +1,41 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Graupner HoTT Telemetry application.
|
||||
#
|
||||
|
||||
MODULE_COMMAND = hott_telemetry
|
||||
|
||||
SRCS = hott_telemetry_main.c \
|
||||
messages.c
|
||||
@@ -0,0 +1,840 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file mb12xx.cpp
|
||||
* @author Greg Hulands
|
||||
*
|
||||
* Driver for the Maxbotix sonar range finders connected via I2C.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdbool.h>
|
||||
#include <semaphore.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/wqueue.h>
|
||||
#include <nuttx/clock.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_range_finder.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/subsystem_info.h>
|
||||
|
||||
/* Configuration Constants */
|
||||
#define MB12XX_BUS PX4_I2C_BUS_EXPANSION
|
||||
#define MB12XX_BASEADDR 0x70 /* 7-bit address. 8-bit address is 0xE0 */
|
||||
|
||||
/* MB12xx Registers addresses */
|
||||
|
||||
#define MB12XX_TAKE_RANGE_REG 0x51 /* Measure range Register */
|
||||
#define MB12XX_SET_ADDRESS_1 0xAA /* Change address 1 Register */
|
||||
#define MB12XX_SET_ADDRESS_2 0xA5 /* Change address 2 Register */
|
||||
|
||||
/* Device limits */
|
||||
#define MB12XX_MIN_DISTANCE (0.20f)
|
||||
#define MB12XX_MAX_DISTANCE (7.65f)
|
||||
|
||||
#define MB12XX_CONVERSION_INTERVAL 60000 /* 60ms */
|
||||
|
||||
/* oddly, ERROR is not defined for c++ */
|
||||
#ifdef ERROR
|
||||
# undef ERROR
|
||||
#endif
|
||||
static const int ERROR = -1;
|
||||
|
||||
#ifndef CONFIG_SCHED_WORKQUEUE
|
||||
# error This requires CONFIG_SCHED_WORKQUEUE.
|
||||
#endif
|
||||
|
||||
class MB12XX : public device::I2C
|
||||
{
|
||||
public:
|
||||
MB12XX(int bus = MB12XX_BUS, int address = MB12XX_BASEADDR);
|
||||
virtual ~MB12XX();
|
||||
|
||||
virtual int init();
|
||||
|
||||
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
|
||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Diagnostics - print some basic information about the driver.
|
||||
*/
|
||||
void print_info();
|
||||
|
||||
protected:
|
||||
virtual int probe();
|
||||
|
||||
private:
|
||||
float _min_distance;
|
||||
float _max_distance;
|
||||
work_s _work;
|
||||
unsigned _num_reports;
|
||||
volatile unsigned _next_report;
|
||||
volatile unsigned _oldest_report;
|
||||
range_finder_report *_reports;
|
||||
bool _sensor_ok;
|
||||
int _measure_ticks;
|
||||
bool _collect_phase;
|
||||
|
||||
orb_advert_t _range_finder_topic;
|
||||
|
||||
perf_counter_t _sample_perf;
|
||||
perf_counter_t _comms_errors;
|
||||
perf_counter_t _buffer_overflows;
|
||||
|
||||
/**
|
||||
* Test whether the device supported by the driver is present at a
|
||||
* specific address.
|
||||
*
|
||||
* @param address The I2C bus address to probe.
|
||||
* @return True if the device is present.
|
||||
*/
|
||||
int probe_address(uint8_t address);
|
||||
|
||||
/**
|
||||
* Initialise the automatic measurement state machine and start it.
|
||||
*
|
||||
* @note This function is called at open and error time. It might make sense
|
||||
* to make it more aggressive about resetting the bus in case of errors.
|
||||
*/
|
||||
void start();
|
||||
|
||||
/**
|
||||
* Stop the automatic measurement state machine.
|
||||
*/
|
||||
void stop();
|
||||
|
||||
/**
|
||||
* Set the min and max distance thresholds if you want the end points of the sensors
|
||||
* range to be brought in at all, otherwise it will use the defaults MB12XX_MIN_DISTANCE
|
||||
* and MB12XX_MAX_DISTANCE
|
||||
*/
|
||||
void set_minimum_distance(float min);
|
||||
void set_maximum_distance(float max);
|
||||
float get_minimum_distance();
|
||||
float get_maximum_distance();
|
||||
|
||||
/**
|
||||
* Perform a poll cycle; collect from the previous measurement
|
||||
* and start a new one.
|
||||
*/
|
||||
void cycle();
|
||||
int measure();
|
||||
int collect();
|
||||
/**
|
||||
* Static trampoline from the workq context; because we don't have a
|
||||
* generic workq wrapper yet.
|
||||
*
|
||||
* @param arg Instance pointer for the driver that is polling.
|
||||
*/
|
||||
static void cycle_trampoline(void *arg);
|
||||
|
||||
|
||||
};
|
||||
|
||||
/* helper macro for handling report buffer indices */
|
||||
#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
|
||||
|
||||
/*
|
||||
* Driver 'main' command.
|
||||
*/
|
||||
extern "C" __EXPORT int mb12xx_main(int argc, char *argv[]);
|
||||
|
||||
MB12XX::MB12XX(int bus, int address) :
|
||||
I2C("MB12xx", RANGE_FINDER_DEVICE_PATH, bus, address, 100000),
|
||||
_min_distance(MB12XX_MIN_DISTANCE),
|
||||
_max_distance(MB12XX_MAX_DISTANCE),
|
||||
_num_reports(0),
|
||||
_next_report(0),
|
||||
_oldest_report(0),
|
||||
_reports(nullptr),
|
||||
_sensor_ok(false),
|
||||
_measure_ticks(0),
|
||||
_collect_phase(false),
|
||||
_range_finder_topic(-1),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "mb12xx_read")),
|
||||
_comms_errors(perf_alloc(PC_COUNT, "mb12xx_comms_errors")),
|
||||
_buffer_overflows(perf_alloc(PC_COUNT, "mb12xx_buffer_overflows"))
|
||||
{
|
||||
// enable debug() calls
|
||||
_debug_enabled = true;
|
||||
|
||||
// work_cancel in the dtor will explode if we don't do this...
|
||||
memset(&_work, 0, sizeof(_work));
|
||||
}
|
||||
|
||||
MB12XX::~MB12XX()
|
||||
{
|
||||
/* make sure we are truly inactive */
|
||||
stop();
|
||||
|
||||
/* free any existing reports */
|
||||
if (_reports != nullptr)
|
||||
delete[] _reports;
|
||||
}
|
||||
|
||||
int
|
||||
MB12XX::init()
|
||||
{
|
||||
int ret = ERROR;
|
||||
|
||||
/* do I2C init (and probe) first */
|
||||
if (I2C::init() != OK)
|
||||
goto out;
|
||||
|
||||
/* allocate basic report buffers */
|
||||
_num_reports = 2;
|
||||
_reports = new struct range_finder_report[_num_reports];
|
||||
|
||||
if (_reports == nullptr)
|
||||
goto out;
|
||||
|
||||
_oldest_report = _next_report = 0;
|
||||
|
||||
/* get a publish handle on the range finder topic */
|
||||
memset(&_reports[0], 0, sizeof(_reports[0]));
|
||||
_range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &_reports[0]);
|
||||
|
||||
if (_range_finder_topic < 0)
|
||||
debug("failed to create sensor_range_finder object. Did you start uOrb?");
|
||||
|
||||
ret = OK;
|
||||
/* sensor is ok, but we don't really know if it is within range */
|
||||
_sensor_ok = true;
|
||||
out:
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
MB12XX::probe()
|
||||
{
|
||||
return measure();
|
||||
}
|
||||
|
||||
void
|
||||
MB12XX::set_minimum_distance(float min)
|
||||
{
|
||||
_min_distance = min;
|
||||
}
|
||||
|
||||
void
|
||||
MB12XX::set_maximum_distance(float max)
|
||||
{
|
||||
_max_distance = max;
|
||||
}
|
||||
|
||||
float
|
||||
MB12XX::get_minimum_distance()
|
||||
{
|
||||
return _min_distance;
|
||||
}
|
||||
|
||||
float
|
||||
MB12XX::get_maximum_distance()
|
||||
{
|
||||
return _max_distance;
|
||||
}
|
||||
|
||||
int
|
||||
MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
switch (cmd) {
|
||||
|
||||
case SENSORIOCSPOLLRATE: {
|
||||
switch (arg) {
|
||||
|
||||
/* switching to manual polling */
|
||||
case SENSOR_POLLRATE_MANUAL:
|
||||
stop();
|
||||
_measure_ticks = 0;
|
||||
return OK;
|
||||
|
||||
/* external signalling (DRDY) not supported */
|
||||
case SENSOR_POLLRATE_EXTERNAL:
|
||||
|
||||
/* zero would be bad */
|
||||
case 0:
|
||||
return -EINVAL;
|
||||
|
||||
/* set default/max polling rate */
|
||||
case SENSOR_POLLRATE_MAX:
|
||||
case SENSOR_POLLRATE_DEFAULT: {
|
||||
/* do we need to start internal polling? */
|
||||
bool want_start = (_measure_ticks == 0);
|
||||
|
||||
/* set interval for next measurement to minimum legal value */
|
||||
_measure_ticks = USEC2TICK(MB12XX_CONVERSION_INTERVAL);
|
||||
|
||||
/* if we need to start the poll state machine, do it */
|
||||
if (want_start)
|
||||
start();
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/* adjust to a legal polling interval in Hz */
|
||||
default: {
|
||||
/* do we need to start internal polling? */
|
||||
bool want_start = (_measure_ticks == 0);
|
||||
|
||||
/* convert hz to tick interval via microseconds */
|
||||
unsigned ticks = USEC2TICK(1000000 / arg);
|
||||
|
||||
/* check against maximum rate */
|
||||
if (ticks < USEC2TICK(MB12XX_CONVERSION_INTERVAL))
|
||||
return -EINVAL;
|
||||
|
||||
/* update interval for next measurement */
|
||||
_measure_ticks = ticks;
|
||||
|
||||
/* if we need to start the poll state machine, do it */
|
||||
if (want_start)
|
||||
start();
|
||||
|
||||
return OK;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
case SENSORIOCGPOLLRATE:
|
||||
if (_measure_ticks == 0)
|
||||
return SENSOR_POLLRATE_MANUAL;
|
||||
|
||||
return (1000 / _measure_ticks);
|
||||
|
||||
case SENSORIOCSQUEUEDEPTH: {
|
||||
/* add one to account for the sentinel in the ring */
|
||||
arg++;
|
||||
|
||||
/* lower bound is mandatory, upper bound is a sanity check */
|
||||
if ((arg < 2) || (arg > 100))
|
||||
return -EINVAL;
|
||||
|
||||
/* allocate new buffer */
|
||||
struct range_finder_report *buf = new struct range_finder_report[arg];
|
||||
|
||||
if (nullptr == buf)
|
||||
return -ENOMEM;
|
||||
|
||||
/* reset the measurement state machine with the new buffer, free the old */
|
||||
stop();
|
||||
delete[] _reports;
|
||||
_num_reports = arg;
|
||||
_reports = buf;
|
||||
start();
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
case SENSORIOCGQUEUEDEPTH:
|
||||
return _num_reports - 1;
|
||||
|
||||
case SENSORIOCRESET:
|
||||
/* XXX implement this */
|
||||
return -EINVAL;
|
||||
|
||||
case RANGEFINDERIOCSETMINIUMDISTANCE:
|
||||
{
|
||||
set_minimum_distance(*(float *)arg);
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
case RANGEFINDERIOCSETMAXIUMDISTANCE:
|
||||
{
|
||||
set_maximum_distance(*(float *)arg);
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return I2C::ioctl(filp, cmd, arg);
|
||||
}
|
||||
}
|
||||
|
||||
ssize_t
|
||||
MB12XX::read(struct file *filp, char *buffer, size_t buflen)
|
||||
{
|
||||
unsigned count = buflen / sizeof(struct range_finder_report);
|
||||
int ret = 0;
|
||||
|
||||
/* buffer must be large enough */
|
||||
if (count < 1)
|
||||
return -ENOSPC;
|
||||
|
||||
/* if automatic measurement is enabled */
|
||||
if (_measure_ticks > 0) {
|
||||
|
||||
/*
|
||||
* While there is space in the caller's buffer, and reports, copy them.
|
||||
* Note that we may be pre-empted by the workq thread while we are doing this;
|
||||
* we are careful to avoid racing with them.
|
||||
*/
|
||||
while (count--) {
|
||||
if (_oldest_report != _next_report) {
|
||||
memcpy(buffer, _reports + _oldest_report, sizeof(*_reports));
|
||||
ret += sizeof(_reports[0]);
|
||||
INCREMENT(_oldest_report, _num_reports);
|
||||
}
|
||||
}
|
||||
|
||||
/* if there was no data, warn the caller */
|
||||
return ret ? ret : -EAGAIN;
|
||||
}
|
||||
|
||||
/* manual measurement - run one conversion */
|
||||
/* XXX really it'd be nice to lock against other readers here */
|
||||
do {
|
||||
_oldest_report = _next_report = 0;
|
||||
|
||||
/* trigger a measurement */
|
||||
if (OK != measure()) {
|
||||
ret = -EIO;
|
||||
break;
|
||||
}
|
||||
|
||||
/* wait for it to complete */
|
||||
usleep(MB12XX_CONVERSION_INTERVAL);
|
||||
|
||||
/* run the collection phase */
|
||||
if (OK != collect()) {
|
||||
ret = -EIO;
|
||||
break;
|
||||
}
|
||||
|
||||
/* state machine will have generated a report, copy it out */
|
||||
memcpy(buffer, _reports, sizeof(*_reports));
|
||||
ret = sizeof(*_reports);
|
||||
|
||||
} while (0);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
MB12XX::measure()
|
||||
{
|
||||
int ret;
|
||||
|
||||
/*
|
||||
* Send the command to begin a measurement.
|
||||
*/
|
||||
uint8_t cmd = MB12XX_TAKE_RANGE_REG;
|
||||
ret = transfer(&cmd, 1, nullptr, 0);
|
||||
|
||||
if (OK != ret)
|
||||
{
|
||||
perf_count(_comms_errors);
|
||||
log("i2c::transfer returned %d", ret);
|
||||
return ret;
|
||||
}
|
||||
ret = OK;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
MB12XX::collect()
|
||||
{
|
||||
int ret = -EIO;
|
||||
|
||||
/* read from the sensor */
|
||||
uint8_t val[2] = {0, 0};
|
||||
|
||||
perf_begin(_sample_perf);
|
||||
|
||||
ret = transfer(nullptr, 0, &val[0], 2);
|
||||
|
||||
if (ret < 0)
|
||||
{
|
||||
log("error reading from sensor: %d", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint16_t distance = val[0] << 8 | val[1];
|
||||
float si_units = (distance * 1.0f)/ 100.0f; /* cm to m */
|
||||
/* this should be fairly close to the end of the measurement, so the best approximation of the time */
|
||||
_reports[_next_report].timestamp = hrt_absolute_time();
|
||||
_reports[_next_report].distance = si_units;
|
||||
_reports[_next_report].valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0;
|
||||
|
||||
/* publish it */
|
||||
orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &_reports[_next_report]);
|
||||
|
||||
/* post a report to the ring - note, not locked */
|
||||
INCREMENT(_next_report, _num_reports);
|
||||
|
||||
/* if we are running up against the oldest report, toss it */
|
||||
if (_next_report == _oldest_report) {
|
||||
perf_count(_buffer_overflows);
|
||||
INCREMENT(_oldest_report, _num_reports);
|
||||
}
|
||||
|
||||
/* notify anyone waiting for data */
|
||||
poll_notify(POLLIN);
|
||||
|
||||
ret = OK;
|
||||
|
||||
out:
|
||||
perf_end(_sample_perf);
|
||||
return ret;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void
|
||||
MB12XX::start()
|
||||
{
|
||||
/* reset the report ring and state machine */
|
||||
_collect_phase = false;
|
||||
_oldest_report = _next_report = 0;
|
||||
|
||||
/* schedule a cycle to start things */
|
||||
work_queue(HPWORK, &_work, (worker_t)&MB12XX::cycle_trampoline, this, 1);
|
||||
|
||||
/* notify about state change */
|
||||
struct subsystem_info_s info = {
|
||||
true,
|
||||
true,
|
||||
true,
|
||||
SUBSYSTEM_TYPE_RANGEFINDER};
|
||||
static orb_advert_t pub = -1;
|
||||
|
||||
if (pub > 0) {
|
||||
orb_publish(ORB_ID(subsystem_info), pub, &info);
|
||||
} else {
|
||||
pub = orb_advertise(ORB_ID(subsystem_info), &info);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
MB12XX::stop()
|
||||
{
|
||||
work_cancel(HPWORK, &_work);
|
||||
}
|
||||
|
||||
void
|
||||
MB12XX::cycle_trampoline(void *arg)
|
||||
{
|
||||
MB12XX *dev = (MB12XX *)arg;
|
||||
|
||||
dev->cycle();
|
||||
}
|
||||
|
||||
void
|
||||
MB12XX::cycle()
|
||||
{
|
||||
/* collection phase? */
|
||||
if (_collect_phase) {
|
||||
|
||||
/* perform collection */
|
||||
if (OK != collect()) {
|
||||
log("collection error");
|
||||
/* restart the measurement state machine */
|
||||
start();
|
||||
return;
|
||||
}
|
||||
|
||||
/* next phase is measurement */
|
||||
_collect_phase = false;
|
||||
|
||||
/*
|
||||
* Is there a collect->measure gap?
|
||||
*/
|
||||
if (_measure_ticks > USEC2TICK(MB12XX_CONVERSION_INTERVAL)) {
|
||||
|
||||
/* schedule a fresh cycle call when we are ready to measure again */
|
||||
work_queue(HPWORK,
|
||||
&_work,
|
||||
(worker_t)&MB12XX::cycle_trampoline,
|
||||
this,
|
||||
_measure_ticks - USEC2TICK(MB12XX_CONVERSION_INTERVAL));
|
||||
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
/* measurement phase */
|
||||
if (OK != measure())
|
||||
log("measure error");
|
||||
|
||||
/* next phase is collection */
|
||||
_collect_phase = true;
|
||||
|
||||
/* schedule a fresh cycle call when the measurement is done */
|
||||
work_queue(HPWORK,
|
||||
&_work,
|
||||
(worker_t)&MB12XX::cycle_trampoline,
|
||||
this,
|
||||
USEC2TICK(MB12XX_CONVERSION_INTERVAL));
|
||||
}
|
||||
|
||||
void
|
||||
MB12XX::print_info()
|
||||
{
|
||||
perf_print_counter(_sample_perf);
|
||||
perf_print_counter(_comms_errors);
|
||||
perf_print_counter(_buffer_overflows);
|
||||
printf("poll interval: %u ticks\n", _measure_ticks);
|
||||
printf("report queue: %u (%u/%u @ %p)\n",
|
||||
_num_reports, _oldest_report, _next_report, _reports);
|
||||
}
|
||||
|
||||
/**
|
||||
* Local functions in support of the shell command.
|
||||
*/
|
||||
namespace mb12xx
|
||||
{
|
||||
|
||||
/* oddly, ERROR is not defined for c++ */
|
||||
#ifdef ERROR
|
||||
# undef ERROR
|
||||
#endif
|
||||
const int ERROR = -1;
|
||||
|
||||
MB12XX *g_dev;
|
||||
|
||||
void start();
|
||||
void stop();
|
||||
void test();
|
||||
void reset();
|
||||
void info();
|
||||
|
||||
/**
|
||||
* Start the driver.
|
||||
*/
|
||||
void
|
||||
start()
|
||||
{
|
||||
int fd;
|
||||
|
||||
if (g_dev != nullptr)
|
||||
errx(1, "already started");
|
||||
|
||||
/* create the driver */
|
||||
g_dev = new MB12XX(MB12XX_BUS);
|
||||
|
||||
if (g_dev == nullptr)
|
||||
goto fail;
|
||||
|
||||
if (OK != g_dev->init())
|
||||
goto fail;
|
||||
|
||||
/* set the poll rate to default, starts automatic data collection */
|
||||
fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0)
|
||||
goto fail;
|
||||
|
||||
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
|
||||
goto fail;
|
||||
|
||||
exit(0);
|
||||
|
||||
fail:
|
||||
|
||||
if (g_dev != nullptr)
|
||||
{
|
||||
delete g_dev;
|
||||
g_dev = nullptr;
|
||||
}
|
||||
|
||||
errx(1, "driver start failed");
|
||||
}
|
||||
|
||||
/**
|
||||
* Stop the driver
|
||||
*/
|
||||
void stop()
|
||||
{
|
||||
if (g_dev != nullptr)
|
||||
{
|
||||
delete g_dev;
|
||||
g_dev = nullptr;
|
||||
}
|
||||
else
|
||||
{
|
||||
errx(1, "driver not running");
|
||||
}
|
||||
exit(0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Perform some basic functional tests on the driver;
|
||||
* make sure we can collect data from the sensor in polled
|
||||
* and automatic modes.
|
||||
*/
|
||||
void
|
||||
test()
|
||||
{
|
||||
struct range_finder_report report;
|
||||
ssize_t sz;
|
||||
int ret;
|
||||
|
||||
int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0)
|
||||
err(1, "%s open failed (try 'mb12xx start' if the driver is not running", RANGE_FINDER_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: %0.2f m", (double)report.distance);
|
||||
warnx("time: %lld", report.timestamp);
|
||||
|
||||
/* start the sensor polling at 2Hz */
|
||||
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2))
|
||||
errx(1, "failed to set 2Hz poll rate");
|
||||
|
||||
/* read the sensor 5x and report each value */
|
||||
for (unsigned i = 0; i < 5; 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");
|
||||
|
||||
warnx("periodic read %u", i);
|
||||
warnx("measurement: %0.3f", (double)report.distance);
|
||||
warnx("time: %lld", report.timestamp);
|
||||
}
|
||||
|
||||
errx(0, "PASS");
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the driver.
|
||||
*/
|
||||
void
|
||||
reset()
|
||||
{
|
||||
int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0)
|
||||
err(1, "failed ");
|
||||
|
||||
if (ioctl(fd, SENSORIOCRESET, 0) < 0)
|
||||
err(1, "driver reset failed");
|
||||
|
||||
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
|
||||
err(1, "driver poll restart failed");
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Print a little info about the driver.
|
||||
*/
|
||||
void
|
||||
info()
|
||||
{
|
||||
if (g_dev == nullptr)
|
||||
errx(1, "driver not running");
|
||||
|
||||
printf("state @ %p\n", g_dev);
|
||||
g_dev->print_info();
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
int
|
||||
mb12xx_main(int argc, char *argv[])
|
||||
{
|
||||
/*
|
||||
* Start/load the driver.
|
||||
*/
|
||||
if (!strcmp(argv[1], "start"))
|
||||
mb12xx::start();
|
||||
|
||||
/*
|
||||
* Stop the driver
|
||||
*/
|
||||
if (!strcmp(argv[1], "stop"))
|
||||
mb12xx::stop();
|
||||
|
||||
/*
|
||||
* Test the driver/device.
|
||||
*/
|
||||
if (!strcmp(argv[1], "test"))
|
||||
mb12xx::test();
|
||||
|
||||
/*
|
||||
* Reset the driver.
|
||||
*/
|
||||
if (!strcmp(argv[1], "reset"))
|
||||
mb12xx::reset();
|
||||
|
||||
/*
|
||||
* Print driver information.
|
||||
*/
|
||||
if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status"))
|
||||
mb12xx::info();
|
||||
|
||||
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
|
||||
}
|
||||
@@ -0,0 +1,40 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2013 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Makefile to build the Maxbotix Sonar driver.
|
||||
#
|
||||
|
||||
MODULE_COMMAND = mb12xx
|
||||
|
||||
SRCS = mb12xx.cpp
|
||||
@@ -0,0 +1,43 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Makefile to build the MPU6000 driver.
|
||||
#
|
||||
|
||||
MODULE_COMMAND = mpu6000
|
||||
|
||||
# XXX seems excessive, check if 2048 is not sufficient
|
||||
MODULE_STACKSIZE = 4096
|
||||
|
||||
SRCS = mpu6000.cpp
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,40 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# MS5611 driver
|
||||
#
|
||||
|
||||
MODULE_COMMAND = ms5611
|
||||
|
||||
SRCS = ms5611.cpp
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,771 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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 KalmanNav.cpp
|
||||
*
|
||||
* kalman filter navigation code
|
||||
*/
|
||||
|
||||
#include <poll.h>
|
||||
|
||||
#include "KalmanNav.hpp"
|
||||
|
||||
// constants
|
||||
// Titterton pg. 52
|
||||
static const float omega = 7.2921150e-5f; // earth rotation rate, rad/s
|
||||
static const float R0 = 6378137.0f; // earth radius, m
|
||||
static const float g0 = 9.806f; // standard gravitational accel. m/s^2
|
||||
static const int8_t ret_ok = 0; // no error in function
|
||||
static const int8_t ret_error = -1; // error occurred
|
||||
|
||||
KalmanNav::KalmanNav(SuperBlock *parent, const char *name) :
|
||||
SuperBlock(parent, name),
|
||||
// ekf matrices
|
||||
F(9, 9),
|
||||
G(9, 6),
|
||||
P(9, 9),
|
||||
P0(9, 9),
|
||||
V(6, 6),
|
||||
// attitude measurement ekf matrices
|
||||
HAtt(6, 9),
|
||||
RAtt(6, 6),
|
||||
// position measurement ekf matrices
|
||||
HPos(6, 9),
|
||||
RPos(6, 6),
|
||||
// attitude representations
|
||||
C_nb(),
|
||||
q(),
|
||||
// subscriptions
|
||||
_sensors(&getSubscriptions(), ORB_ID(sensor_combined), 5), // limit to 200 Hz
|
||||
_gps(&getSubscriptions(), ORB_ID(vehicle_gps_position), 100), // limit to 10 Hz
|
||||
_param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz
|
||||
// publications
|
||||
_pos(&getPublications(), ORB_ID(vehicle_global_position)),
|
||||
_att(&getPublications(), ORB_ID(vehicle_attitude)),
|
||||
// timestamps
|
||||
_pubTimeStamp(hrt_absolute_time()),
|
||||
_predictTimeStamp(hrt_absolute_time()),
|
||||
_attTimeStamp(hrt_absolute_time()),
|
||||
_outTimeStamp(hrt_absolute_time()),
|
||||
// frame count
|
||||
_navFrames(0),
|
||||
// miss counts
|
||||
_miss(0),
|
||||
// accelerations
|
||||
fN(0), fE(0), fD(0),
|
||||
// state
|
||||
phi(0), theta(0), psi(0),
|
||||
vN(0), vE(0), vD(0),
|
||||
lat(0), lon(0), alt(0),
|
||||
// parameters for ground station
|
||||
_vGyro(this, "V_GYRO"),
|
||||
_vAccel(this, "V_ACCEL"),
|
||||
_rMag(this, "R_MAG"),
|
||||
_rGpsVel(this, "R_GPS_VEL"),
|
||||
_rGpsPos(this, "R_GPS_POS"),
|
||||
_rGpsAlt(this, "R_GPS_ALT"),
|
||||
_rPressAlt(this, "R_PRESS_ALT"),
|
||||
_rAccel(this, "R_ACCEL"),
|
||||
_magDip(this, "ENV_MAG_DIP"),
|
||||
_magDec(this, "ENV_MAG_DEC"),
|
||||
_g(this, "ENV_G"),
|
||||
_faultPos(this, "FAULT_POS"),
|
||||
_faultAtt(this, "FAULT_ATT"),
|
||||
_attitudeInitialized(false),
|
||||
_positionInitialized(false),
|
||||
_attitudeInitCounter(0)
|
||||
{
|
||||
using namespace math;
|
||||
|
||||
// initial state covariance matrix
|
||||
P0 = Matrix::identity(9) * 0.01f;
|
||||
P = P0;
|
||||
|
||||
// initial state
|
||||
phi = 0.0f;
|
||||
theta = 0.0f;
|
||||
psi = 0.0f;
|
||||
vN = 0.0f;
|
||||
vE = 0.0f;
|
||||
vD = 0.0f;
|
||||
lat = 0.0f;
|
||||
lon = 0.0f;
|
||||
alt = 0.0f;
|
||||
|
||||
// initialize quaternions
|
||||
q = Quaternion(EulerAngles(phi, theta, psi));
|
||||
|
||||
// initialize dcm
|
||||
C_nb = Dcm(q);
|
||||
|
||||
// HPos is constant
|
||||
HPos(0, 3) = 1.0f;
|
||||
HPos(1, 4) = 1.0f;
|
||||
HPos(2, 6) = 1.0e7f * M_RAD_TO_DEG_F;
|
||||
HPos(3, 7) = 1.0e7f * M_RAD_TO_DEG_F;
|
||||
HPos(4, 8) = 1.0f;
|
||||
HPos(5, 8) = 1.0f;
|
||||
|
||||
// initialize all parameters
|
||||
updateParams();
|
||||
}
|
||||
|
||||
void KalmanNav::update()
|
||||
{
|
||||
using namespace math;
|
||||
|
||||
struct pollfd fds[1];
|
||||
fds[0].fd = _sensors.getHandle();
|
||||
fds[0].events = POLLIN;
|
||||
|
||||
// poll for new data
|
||||
int ret = poll(fds, 1, 1000);
|
||||
|
||||
if (ret < 0) {
|
||||
// XXX this is seriously bad - should be an emergency
|
||||
return;
|
||||
|
||||
} else if (ret == 0) { // timeout
|
||||
return;
|
||||
}
|
||||
|
||||
// get new timestamp
|
||||
uint64_t newTimeStamp = hrt_absolute_time();
|
||||
|
||||
// check updated subscriptions
|
||||
if (_param_update.updated()) updateParams();
|
||||
|
||||
bool gpsUpdate = _gps.updated();
|
||||
bool sensorsUpdate = _sensors.updated();
|
||||
|
||||
// get new information from subscriptions
|
||||
// this clears update flag
|
||||
updateSubscriptions();
|
||||
|
||||
// initialize attitude when sensors online
|
||||
if (!_attitudeInitialized && sensorsUpdate &&
|
||||
_sensors.accelerometer_counter > 10 &&
|
||||
_sensors.gyro_counter > 10 &&
|
||||
_sensors.magnetometer_counter > 10) {
|
||||
if (correctAtt() == ret_ok) _attitudeInitCounter++;
|
||||
|
||||
if (_attitudeInitCounter > 100) {
|
||||
printf("[kalman_demo] initialized EKF attitude\n");
|
||||
printf("phi: %8.4f, theta: %8.4f, psi: %8.4f\n",
|
||||
double(phi), double(theta), double(psi));
|
||||
_attitudeInitialized = true;
|
||||
}
|
||||
}
|
||||
|
||||
// initialize position when gps received
|
||||
if (!_positionInitialized &&
|
||||
_attitudeInitialized && // wait for attitude first
|
||||
gpsUpdate &&
|
||||
_gps.fix_type > 2
|
||||
//&& _gps.counter_pos_valid > 10
|
||||
) {
|
||||
vN = _gps.vel_n_m_s;
|
||||
vE = _gps.vel_e_m_s;
|
||||
vD = _gps.vel_d_m_s;
|
||||
setLatDegE7(_gps.lat);
|
||||
setLonDegE7(_gps.lon);
|
||||
setAltE3(_gps.alt);
|
||||
_positionInitialized = true;
|
||||
printf("[kalman_demo] initialized EKF state with GPS\n");
|
||||
printf("vN: %8.4f, vE: %8.4f, vD: %8.4f, lat: %8.4f, lon: %8.4f, alt: %8.4f\n",
|
||||
double(vN), double(vE), double(vD),
|
||||
lat, lon, alt);
|
||||
}
|
||||
|
||||
// prediciton step
|
||||
// using sensors timestamp so we can account for packet lag
|
||||
float dt = (_sensors.timestamp - _predictTimeStamp) / 1.0e6f;
|
||||
//printf("dt: %15.10f\n", double(dt));
|
||||
_predictTimeStamp = _sensors.timestamp;
|
||||
|
||||
// don't predict if time greater than a second
|
||||
if (dt < 1.0f) {
|
||||
predictState(dt);
|
||||
predictStateCovariance(dt);
|
||||
// count fast frames
|
||||
_navFrames += 1;
|
||||
}
|
||||
|
||||
// count times 100 Hz rate isn't met
|
||||
if (dt > 0.01f) _miss++;
|
||||
|
||||
// gps correction step
|
||||
if (_positionInitialized && gpsUpdate) {
|
||||
correctPos();
|
||||
}
|
||||
|
||||
// attitude correction step
|
||||
if (_attitudeInitialized // initialized
|
||||
&& sensorsUpdate // new data
|
||||
&& _sensors.timestamp - _attTimeStamp > 1e6 / 20 // 20 Hz
|
||||
) {
|
||||
_attTimeStamp = _sensors.timestamp;
|
||||
correctAtt();
|
||||
}
|
||||
|
||||
// publication
|
||||
if (newTimeStamp - _pubTimeStamp > 1e6 / 50) { // 50 Hz
|
||||
_pubTimeStamp = newTimeStamp;
|
||||
|
||||
updatePublications();
|
||||
}
|
||||
|
||||
// output
|
||||
if (newTimeStamp - _outTimeStamp > 10e6) { // 0.1 Hz
|
||||
_outTimeStamp = newTimeStamp;
|
||||
//printf("nav: %4d Hz, miss #: %4d\n",
|
||||
// _navFrames / 10, _miss / 10);
|
||||
_navFrames = 0;
|
||||
_miss = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void KalmanNav::updatePublications()
|
||||
{
|
||||
using namespace math;
|
||||
|
||||
// position publication
|
||||
_pos.timestamp = _pubTimeStamp;
|
||||
_pos.time_gps_usec = _gps.timestamp_position;
|
||||
_pos.valid = true;
|
||||
_pos.lat = getLatDegE7();
|
||||
_pos.lon = getLonDegE7();
|
||||
_pos.alt = float(alt);
|
||||
_pos.relative_alt = float(alt); // TODO, make relative
|
||||
_pos.vx = vN;
|
||||
_pos.vy = vE;
|
||||
_pos.vz = vD;
|
||||
_pos.hdg = psi;
|
||||
|
||||
// attitude publication
|
||||
_att.timestamp = _pubTimeStamp;
|
||||
_att.roll = phi;
|
||||
_att.pitch = theta;
|
||||
_att.yaw = psi;
|
||||
_att.rollspeed = _sensors.gyro_rad_s[0];
|
||||
_att.pitchspeed = _sensors.gyro_rad_s[1];
|
||||
_att.yawspeed = _sensors.gyro_rad_s[2];
|
||||
// TODO, add gyro offsets to filter
|
||||
_att.rate_offsets[0] = 0.0f;
|
||||
_att.rate_offsets[1] = 0.0f;
|
||||
_att.rate_offsets[2] = 0.0f;
|
||||
|
||||
for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
|
||||
_att.R[i][j] = C_nb(i, j);
|
||||
|
||||
for (int i = 0; i < 4; i++) _att.q[i] = q(i);
|
||||
|
||||
_att.R_valid = true;
|
||||
_att.q_valid = true;
|
||||
|
||||
// selectively update publications,
|
||||
// do NOT call superblock do-all method
|
||||
if (_positionInitialized)
|
||||
_pos.update();
|
||||
|
||||
if (_attitudeInitialized)
|
||||
_att.update();
|
||||
}
|
||||
|
||||
int KalmanNav::predictState(float dt)
|
||||
{
|
||||
using namespace math;
|
||||
|
||||
// trig
|
||||
float sinL = sinf(lat);
|
||||
float cosL = cosf(lat);
|
||||
float cosLSing = cosf(lat);
|
||||
|
||||
// prevent singularity
|
||||
if (fabsf(cosLSing) < 0.01f) {
|
||||
if (cosLSing > 0) cosLSing = 0.01;
|
||||
else cosLSing = -0.01;
|
||||
}
|
||||
|
||||
// attitude prediction
|
||||
if (_attitudeInitialized) {
|
||||
Vector3 w(_sensors.gyro_rad_s);
|
||||
|
||||
// attitude
|
||||
q = q + q.derivative(w) * dt;
|
||||
|
||||
// renormalize quaternion if needed
|
||||
if (fabsf(q.norm() - 1.0f) > 1e-4f) {
|
||||
q = q.unit();
|
||||
}
|
||||
|
||||
// C_nb update
|
||||
C_nb = Dcm(q);
|
||||
|
||||
// euler update
|
||||
EulerAngles euler(C_nb);
|
||||
phi = euler.getPhi();
|
||||
theta = euler.getTheta();
|
||||
psi = euler.getPsi();
|
||||
|
||||
// specific acceleration in nav frame
|
||||
Vector3 accelB(_sensors.accelerometer_m_s2);
|
||||
Vector3 accelN = C_nb * accelB;
|
||||
fN = accelN(0);
|
||||
fE = accelN(1);
|
||||
fD = accelN(2);
|
||||
}
|
||||
|
||||
// position prediction
|
||||
if (_positionInitialized) {
|
||||
// neglects angular deflections in local gravity
|
||||
// see Titerton pg. 70
|
||||
float R = R0 + float(alt);
|
||||
float LDot = vN / R;
|
||||
float lDot = vE / (cosLSing * R);
|
||||
float rotRate = 2 * omega + lDot;
|
||||
|
||||
// XXX position prediction using speed
|
||||
float vNDot = fN - vE * rotRate * sinL +
|
||||
vD * LDot;
|
||||
float vDDot = fD - vE * rotRate * cosL -
|
||||
vN * LDot + _g.get();
|
||||
float vEDot = fE + vN * rotRate * sinL +
|
||||
vDDot * rotRate * cosL;
|
||||
|
||||
// rectangular integration
|
||||
vN += vNDot * dt;
|
||||
vE += vEDot * dt;
|
||||
vD += vDDot * dt;
|
||||
lat += double(LDot * dt);
|
||||
lon += double(lDot * dt);
|
||||
alt += double(-vD * dt);
|
||||
}
|
||||
|
||||
return ret_ok;
|
||||
}
|
||||
|
||||
int KalmanNav::predictStateCovariance(float dt)
|
||||
{
|
||||
using namespace math;
|
||||
|
||||
// trig
|
||||
float sinL = sinf(lat);
|
||||
float cosL = cosf(lat);
|
||||
float cosLSq = cosL * cosL;
|
||||
float tanL = tanf(lat);
|
||||
|
||||
// prepare for matrix
|
||||
float R = R0 + float(alt);
|
||||
float RSq = R * R;
|
||||
|
||||
// F Matrix
|
||||
// Titterton pg. 291
|
||||
|
||||
F(0, 1) = -(omega * sinL + vE * tanL / R);
|
||||
F(0, 2) = vN / R;
|
||||
F(0, 4) = 1.0f / R;
|
||||
F(0, 6) = -omega * sinL;
|
||||
F(0, 8) = -vE / RSq;
|
||||
|
||||
F(1, 0) = omega * sinL + vE * tanL / R;
|
||||
F(1, 2) = omega * cosL + vE / R;
|
||||
F(1, 3) = -1.0f / R;
|
||||
F(1, 8) = vN / RSq;
|
||||
|
||||
F(2, 0) = -vN / R;
|
||||
F(2, 1) = -omega * cosL - vE / R;
|
||||
F(2, 4) = -tanL / R;
|
||||
F(2, 6) = -omega * cosL - vE / (R * cosLSq);
|
||||
F(2, 8) = vE * tanL / RSq;
|
||||
|
||||
F(3, 1) = -fD;
|
||||
F(3, 2) = fE;
|
||||
F(3, 3) = vD / R;
|
||||
F(3, 4) = -2 * (omega * sinL + vE * tanL / R);
|
||||
F(3, 5) = vN / R;
|
||||
F(3, 6) = -vE * (2 * omega * cosL + vE / (R * cosLSq));
|
||||
F(3, 8) = (vE * vE * tanL - vN * vD) / RSq;
|
||||
|
||||
F(4, 0) = fD;
|
||||
F(4, 2) = -fN;
|
||||
F(4, 3) = 2 * omega * sinL + vE * tanL / R;
|
||||
F(4, 4) = (vN * tanL + vD) / R;
|
||||
F(4, 5) = 2 * omega * cosL + vE / R;
|
||||
F(4, 6) = 2 * omega * (vN * cosL - vD * sinL) +
|
||||
vN * vE / (R * cosLSq);
|
||||
F(4, 8) = -vE * (vN * tanL + vD) / RSq;
|
||||
|
||||
F(5, 0) = -fE;
|
||||
F(5, 1) = fN;
|
||||
F(5, 3) = -2 * vN / R;
|
||||
F(5, 4) = -2 * (omega * cosL + vE / R);
|
||||
F(5, 6) = 2 * omega * vE * sinL;
|
||||
F(5, 8) = (vN * vN + vE * vE) / RSq;
|
||||
|
||||
F(6, 3) = 1 / R;
|
||||
F(6, 8) = -vN / RSq;
|
||||
|
||||
F(7, 4) = 1 / (R * cosL);
|
||||
F(7, 6) = vE * tanL / (R * cosL);
|
||||
F(7, 8) = -vE / (cosL * RSq);
|
||||
|
||||
F(8, 5) = -1;
|
||||
|
||||
// G Matrix
|
||||
// Titterton pg. 291
|
||||
G(0, 0) = -C_nb(0, 0);
|
||||
G(0, 1) = -C_nb(0, 1);
|
||||
G(0, 2) = -C_nb(0, 2);
|
||||
G(1, 0) = -C_nb(1, 0);
|
||||
G(1, 1) = -C_nb(1, 1);
|
||||
G(1, 2) = -C_nb(1, 2);
|
||||
G(2, 0) = -C_nb(2, 0);
|
||||
G(2, 1) = -C_nb(2, 1);
|
||||
G(2, 2) = -C_nb(2, 2);
|
||||
|
||||
G(3, 3) = C_nb(0, 0);
|
||||
G(3, 4) = C_nb(0, 1);
|
||||
G(3, 5) = C_nb(0, 2);
|
||||
G(4, 3) = C_nb(1, 0);
|
||||
G(4, 4) = C_nb(1, 1);
|
||||
G(4, 5) = C_nb(1, 2);
|
||||
G(5, 3) = C_nb(2, 0);
|
||||
G(5, 4) = C_nb(2, 1);
|
||||
G(5, 5) = C_nb(2, 2);
|
||||
|
||||
// continuous predictioon equations
|
||||
// for discrte time EKF
|
||||
// http://en.wikipedia.org/wiki/Extended_Kalman_filter
|
||||
P = P + (F * P + P * F.transpose() + G * V * G.transpose()) * dt;
|
||||
|
||||
return ret_ok;
|
||||
}
|
||||
|
||||
int KalmanNav::correctAtt()
|
||||
{
|
||||
using namespace math;
|
||||
|
||||
// trig
|
||||
float cosPhi = cosf(phi);
|
||||
float cosTheta = cosf(theta);
|
||||
float cosPsi = cosf(psi);
|
||||
float sinPhi = sinf(phi);
|
||||
float sinTheta = sinf(theta);
|
||||
float sinPsi = sinf(psi);
|
||||
|
||||
// mag measurement
|
||||
Vector3 zMag(_sensors.magnetometer_ga);
|
||||
//float magNorm = zMag.norm();
|
||||
zMag = zMag.unit();
|
||||
|
||||
// mag predicted measurement
|
||||
// choosing some typical magnetic field properties,
|
||||
// TODO dip/dec depend on lat/ lon/ time
|
||||
float dip = _magDip.get() / M_RAD_TO_DEG_F; // dip, inclination with level
|
||||
float dec = _magDec.get() / M_RAD_TO_DEG_F; // declination, clockwise rotation from north
|
||||
float bN = cosf(dip) * cosf(dec);
|
||||
float bE = cosf(dip) * sinf(dec);
|
||||
float bD = sinf(dip);
|
||||
Vector3 bNav(bN, bE, bD);
|
||||
Vector3 zMagHat = (C_nb.transpose() * bNav).unit();
|
||||
|
||||
// accel measurement
|
||||
Vector3 zAccel(_sensors.accelerometer_m_s2);
|
||||
float accelMag = zAccel.norm();
|
||||
zAccel = zAccel.unit();
|
||||
|
||||
// ignore accel correction when accel mag not close to g
|
||||
Matrix RAttAdjust = RAtt;
|
||||
|
||||
bool ignoreAccel = fabsf(accelMag - _g.get()) > 1.1f;
|
||||
|
||||
if (ignoreAccel) {
|
||||
RAttAdjust(3, 3) = 1.0e10;
|
||||
RAttAdjust(4, 4) = 1.0e10;
|
||||
RAttAdjust(5, 5) = 1.0e10;
|
||||
|
||||
} else {
|
||||
//printf("correcting attitude with accel\n");
|
||||
}
|
||||
|
||||
// accel predicted measurement
|
||||
Vector3 zAccelHat = (C_nb.transpose() * Vector3(0, 0, -_g.get())).unit();
|
||||
|
||||
// combined measurement
|
||||
Vector zAtt(6);
|
||||
Vector zAttHat(6);
|
||||
|
||||
for (int i = 0; i < 3; i++) {
|
||||
zAtt(i) = zMag(i);
|
||||
zAtt(i + 3) = zAccel(i);
|
||||
zAttHat(i) = zMagHat(i);
|
||||
zAttHat(i + 3) = zAccelHat(i);
|
||||
}
|
||||
|
||||
// HMag , HAtt (0-2,:)
|
||||
float tmp1 =
|
||||
cosPsi * cosTheta * bN +
|
||||
sinPsi * cosTheta * bE -
|
||||
sinTheta * bD;
|
||||
HAtt(0, 1) = -(
|
||||
cosPsi * sinTheta * bN +
|
||||
sinPsi * sinTheta * bE +
|
||||
cosTheta * bD
|
||||
);
|
||||
HAtt(0, 2) = -cosTheta * (sinPsi * bN - cosPsi * bE);
|
||||
HAtt(1, 0) =
|
||||
(cosPhi * cosPsi * sinTheta + sinPhi * sinPsi) * bN +
|
||||
(cosPhi * sinPsi * sinTheta - sinPhi * cosPsi) * bE +
|
||||
cosPhi * cosTheta * bD;
|
||||
HAtt(1, 1) = sinPhi * tmp1;
|
||||
HAtt(1, 2) = -(
|
||||
(sinPhi * sinPsi * sinTheta + cosPhi * cosPsi) * bN -
|
||||
(sinPhi * cosPsi * sinTheta - cosPhi * sinPsi) * bE
|
||||
);
|
||||
HAtt(2, 0) = -(
|
||||
(sinPhi * cosPsi * sinTheta - cosPhi * sinPsi) * bN +
|
||||
(sinPhi * sinPsi * sinTheta + cosPhi * cosPsi) * bE +
|
||||
(sinPhi * cosTheta) * bD
|
||||
);
|
||||
HAtt(2, 1) = cosPhi * tmp1;
|
||||
HAtt(2, 2) = -(
|
||||
(cosPhi * sinPsi * sinTheta - sinPhi * cosTheta) * bN -
|
||||
(cosPhi * cosPsi * sinTheta + sinPhi * sinPsi) * bE
|
||||
);
|
||||
|
||||
// HAccel , HAtt (3-5,:)
|
||||
HAtt(3, 1) = cosTheta;
|
||||
HAtt(4, 0) = -cosPhi * cosTheta;
|
||||
HAtt(4, 1) = sinPhi * sinTheta;
|
||||
HAtt(5, 0) = sinPhi * cosTheta;
|
||||
HAtt(5, 1) = cosPhi * sinTheta;
|
||||
|
||||
// compute correction
|
||||
// http://en.wikipedia.org/wiki/Extended_Kalman_filter
|
||||
Vector y = zAtt - zAttHat; // residual
|
||||
Matrix S = HAtt * P * HAtt.transpose() + RAttAdjust; // residual covariance
|
||||
Matrix K = P * HAtt.transpose() * S.inverse();
|
||||
Vector xCorrect = K * y;
|
||||
|
||||
// check correciton is sane
|
||||
for (size_t i = 0; i < xCorrect.getRows(); i++) {
|
||||
float val = xCorrect(i);
|
||||
|
||||
if (isnan(val) || isinf(val)) {
|
||||
// abort correction and return
|
||||
printf("[kalman_demo] numerical failure in att correction\n");
|
||||
// reset P matrix to P0
|
||||
P = P0;
|
||||
return ret_error;
|
||||
}
|
||||
}
|
||||
|
||||
// correct state
|
||||
if (!ignoreAccel) {
|
||||
phi += xCorrect(PHI);
|
||||
theta += xCorrect(THETA);
|
||||
}
|
||||
|
||||
psi += xCorrect(PSI);
|
||||
|
||||
// attitude also affects nav velocities
|
||||
if (_positionInitialized) {
|
||||
vN += xCorrect(VN);
|
||||
vE += xCorrect(VE);
|
||||
vD += xCorrect(VD);
|
||||
}
|
||||
|
||||
// update state covariance
|
||||
// http://en.wikipedia.org/wiki/Extended_Kalman_filter
|
||||
P = P - K * HAtt * P;
|
||||
|
||||
// fault detection
|
||||
float beta = y.dot(S.inverse() * y);
|
||||
|
||||
if (beta > _faultAtt.get()) {
|
||||
printf("fault in attitude: beta = %8.4f\n", (double)beta);
|
||||
printf("y:\n"); y.print();
|
||||
printf("zMagHat:\n"); zMagHat.print();
|
||||
printf("zMag:\n"); zMag.print();
|
||||
printf("bNav:\n"); bNav.print();
|
||||
}
|
||||
|
||||
// update quaternions from euler
|
||||
// angle correction
|
||||
q = Quaternion(EulerAngles(phi, theta, psi));
|
||||
|
||||
return ret_ok;
|
||||
}
|
||||
|
||||
int KalmanNav::correctPos()
|
||||
{
|
||||
using namespace math;
|
||||
|
||||
// residual
|
||||
Vector y(6);
|
||||
y(0) = _gps.vel_n_m_s - vN;
|
||||
y(1) = _gps.vel_e_m_s - vE;
|
||||
y(2) = double(_gps.lat) - lat * 1.0e7 * M_RAD_TO_DEG;
|
||||
y(3) = double(_gps.lon) - lon * 1.0e7 * M_RAD_TO_DEG;
|
||||
y(4) = double(_gps.alt) / 1.0e3 - alt;
|
||||
y(5) = double(_sensors.baro_alt_meter) - alt;
|
||||
|
||||
// compute correction
|
||||
// http://en.wikipedia.org/wiki/Extended_Kalman_filter
|
||||
Matrix S = HPos * P * HPos.transpose() + RPos; // residual covariance
|
||||
Matrix K = P * HPos.transpose() * S.inverse();
|
||||
Vector xCorrect = K * y;
|
||||
|
||||
// check correction is sane
|
||||
for (size_t i = 0; i < xCorrect.getRows(); i++) {
|
||||
float val = xCorrect(i);
|
||||
|
||||
if (isnan(val) || isinf(val)) {
|
||||
// abort correction and return
|
||||
printf("[kalman_demo] numerical failure in gps correction\n");
|
||||
// fallback to GPS
|
||||
vN = _gps.vel_n_m_s;
|
||||
vE = _gps.vel_e_m_s;
|
||||
vD = _gps.vel_d_m_s;
|
||||
setLatDegE7(_gps.lat);
|
||||
setLonDegE7(_gps.lon);
|
||||
setAltE3(_gps.alt);
|
||||
// reset P matrix to P0
|
||||
P = P0;
|
||||
return ret_error;
|
||||
}
|
||||
}
|
||||
|
||||
// correct state
|
||||
vN += xCorrect(VN);
|
||||
vE += xCorrect(VE);
|
||||
vD += xCorrect(VD);
|
||||
lat += double(xCorrect(LAT));
|
||||
lon += double(xCorrect(LON));
|
||||
alt += double(xCorrect(ALT));
|
||||
|
||||
// update state covariance
|
||||
// http://en.wikipedia.org/wiki/Extended_Kalman_filter
|
||||
P = P - K * HPos * P;
|
||||
|
||||
// fault detetcion
|
||||
float beta = y.dot(S.inverse() * y);
|
||||
|
||||
if (beta > _faultPos.get()) {
|
||||
printf("fault in gps: beta = %8.4f\n", (double)beta);
|
||||
printf("Y/N: vN: %8.4f, vE: %8.4f, lat: %8.4f, lon: %8.4f, alt: %8.4f\n",
|
||||
double(y(0) / sqrtf(RPos(0, 0))),
|
||||
double(y(1) / sqrtf(RPos(1, 1))),
|
||||
double(y(2) / sqrtf(RPos(2, 2))),
|
||||
double(y(3) / sqrtf(RPos(3, 3))),
|
||||
double(y(4) / sqrtf(RPos(4, 4))),
|
||||
double(y(5) / sqrtf(RPos(5, 5))));
|
||||
}
|
||||
|
||||
return ret_ok;
|
||||
}
|
||||
|
||||
void KalmanNav::updateParams()
|
||||
{
|
||||
using namespace math;
|
||||
using namespace control;
|
||||
SuperBlock::updateParams();
|
||||
|
||||
// gyro noise
|
||||
V(0, 0) = _vGyro.get(); // gyro x, rad/s
|
||||
V(1, 1) = _vGyro.get(); // gyro y
|
||||
V(2, 2) = _vGyro.get(); // gyro z
|
||||
|
||||
// accel noise
|
||||
V(3, 3) = _vAccel.get(); // accel x, m/s^2
|
||||
V(4, 4) = _vAccel.get(); // accel y
|
||||
V(5, 5) = _vAccel.get(); // accel z
|
||||
|
||||
// magnetometer noise
|
||||
float noiseMin = 1e-6f;
|
||||
float noiseMagSq = _rMag.get() * _rMag.get();
|
||||
|
||||
if (noiseMagSq < noiseMin) noiseMagSq = noiseMin;
|
||||
|
||||
RAtt(0, 0) = noiseMagSq; // normalized direction
|
||||
RAtt(1, 1) = noiseMagSq;
|
||||
RAtt(2, 2) = noiseMagSq;
|
||||
|
||||
// accelerometer noise
|
||||
float noiseAccelSq = _rAccel.get() * _rAccel.get();
|
||||
|
||||
// bound noise to prevent singularities
|
||||
if (noiseAccelSq < noiseMin) noiseAccelSq = noiseMin;
|
||||
|
||||
RAtt(3, 3) = noiseAccelSq; // normalized direction
|
||||
RAtt(4, 4) = noiseAccelSq;
|
||||
RAtt(5, 5) = noiseAccelSq;
|
||||
|
||||
// gps noise
|
||||
float R = R0 + float(alt);
|
||||
float cosLSing = cosf(lat);
|
||||
|
||||
// prevent singularity
|
||||
if (fabsf(cosLSing) < 0.01f) {
|
||||
if (cosLSing > 0) cosLSing = 0.01;
|
||||
else cosLSing = -0.01;
|
||||
}
|
||||
|
||||
float noiseVel = _rGpsVel.get();
|
||||
float noiseLatDegE7 = 1.0e7f * M_RAD_TO_DEG_F * _rGpsPos.get() / R;
|
||||
float noiseLonDegE7 = noiseLatDegE7 / cosLSing;
|
||||
float noiseGpsAlt = _rGpsAlt.get();
|
||||
float noisePressAlt = _rPressAlt.get();
|
||||
|
||||
// bound noise to prevent singularities
|
||||
if (noiseVel < noiseMin) noiseVel = noiseMin;
|
||||
|
||||
if (noiseLatDegE7 < noiseMin) noiseLatDegE7 = noiseMin;
|
||||
|
||||
if (noiseLonDegE7 < noiseMin) noiseLonDegE7 = noiseMin;
|
||||
|
||||
if (noiseGpsAlt < noiseMin) noiseGpsAlt = noiseMin;
|
||||
|
||||
if (noisePressAlt < noiseMin) noisePressAlt = noiseMin;
|
||||
|
||||
RPos(0, 0) = noiseVel * noiseVel; // vn
|
||||
RPos(1, 1) = noiseVel * noiseVel; // ve
|
||||
RPos(2, 2) = noiseLatDegE7 * noiseLatDegE7; // lat
|
||||
RPos(3, 3) = noiseLonDegE7 * noiseLonDegE7; // lon
|
||||
RPos(4, 4) = noiseGpsAlt * noiseGpsAlt; // h
|
||||
RPos(5, 5) = noisePressAlt * noisePressAlt; // h
|
||||
// XXX, note that RPos depends on lat, so updateParams should
|
||||
// be called if lat changes significantly
|
||||
}
|
||||
@@ -0,0 +1,180 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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 KalmanNav.hpp
|
||||
*
|
||||
* kalman filter navigation code
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
//#define MATRIX_ASSERT
|
||||
//#define VECTOR_ASSERT
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <controllib/blocks.hpp>
|
||||
#include <controllib/block/BlockParam.hpp>
|
||||
#include <controllib/block/UOrbSubscription.hpp>
|
||||
#include <controllib/block/UOrbPublication.hpp>
|
||||
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <poll.h>
|
||||
#include <unistd.h>
|
||||
|
||||
/**
|
||||
* Kalman filter navigation class
|
||||
* http://en.wikipedia.org/wiki/Extended_Kalman_filter
|
||||
* Discrete-time extended Kalman filter
|
||||
*/
|
||||
class KalmanNav : public control::SuperBlock
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Constructor
|
||||
*/
|
||||
KalmanNav(SuperBlock *parent, const char *name);
|
||||
|
||||
/**
|
||||
* Deconstuctor
|
||||
*/
|
||||
|
||||
virtual ~KalmanNav() {};
|
||||
/**
|
||||
* The main callback function for the class
|
||||
*/
|
||||
void update();
|
||||
|
||||
|
||||
/**
|
||||
* Publication update
|
||||
*/
|
||||
virtual void updatePublications();
|
||||
|
||||
/**
|
||||
* State prediction
|
||||
* Continuous, non-linear
|
||||
*/
|
||||
int predictState(float dt);
|
||||
|
||||
/**
|
||||
* State covariance prediction
|
||||
* Continuous, linear
|
||||
*/
|
||||
int predictStateCovariance(float dt);
|
||||
|
||||
/**
|
||||
* Attitude correction
|
||||
*/
|
||||
int correctAtt();
|
||||
|
||||
/**
|
||||
* Position correction
|
||||
*/
|
||||
int correctPos();
|
||||
|
||||
/**
|
||||
* Overloaded update parameters
|
||||
*/
|
||||
virtual void updateParams();
|
||||
protected:
|
||||
// kalman filter
|
||||
math::Matrix F; /**< Jacobian(f,x), where dx/dt = f(x,u) */
|
||||
math::Matrix G; /**< noise shaping matrix for gyro/accel */
|
||||
math::Matrix P; /**< state covariance matrix */
|
||||
math::Matrix P0; /**< initial state covariance matrix */
|
||||
math::Matrix V; /**< gyro/ accel noise matrix */
|
||||
math::Matrix HAtt; /**< attitude measurement matrix */
|
||||
math::Matrix RAtt; /**< attitude measurement noise matrix */
|
||||
math::Matrix HPos; /**< position measurement jacobian matrix */
|
||||
math::Matrix RPos; /**< position measurement noise matrix */
|
||||
// attitude
|
||||
math::Dcm C_nb; /**< direction cosine matrix from body to nav frame */
|
||||
math::Quaternion q; /**< quaternion from body to nav frame */
|
||||
// subscriptions
|
||||
control::UOrbSubscription<sensor_combined_s> _sensors; /**< sensors sub. */
|
||||
control::UOrbSubscription<vehicle_gps_position_s> _gps; /**< gps sub. */
|
||||
control::UOrbSubscription<parameter_update_s> _param_update; /**< parameter update sub. */
|
||||
// publications
|
||||
control::UOrbPublication<vehicle_global_position_s> _pos; /**< position pub. */
|
||||
control::UOrbPublication<vehicle_attitude_s> _att; /**< attitude pub. */
|
||||
// time stamps
|
||||
uint64_t _pubTimeStamp; /**< output data publication time stamp */
|
||||
uint64_t _predictTimeStamp; /**< prediction time stamp */
|
||||
uint64_t _attTimeStamp; /**< attitude correction time stamp */
|
||||
uint64_t _outTimeStamp; /**< output time stamp */
|
||||
// frame count
|
||||
uint16_t _navFrames; /**< navigation frames completed in output cycle */
|
||||
// miss counts
|
||||
uint16_t _miss; /**< number of times fast prediction loop missed */
|
||||
// accelerations
|
||||
float fN, fE, fD; /**< navigation frame acceleration */
|
||||
// states
|
||||
enum {PHI = 0, THETA, PSI, VN, VE, VD, LAT, LON, ALT}; /**< state enumeration */
|
||||
float phi, theta, psi; /**< 3-2-1 euler angles */
|
||||
float vN, vE, vD; /**< navigation velocity, m/s */
|
||||
double lat, lon, alt; /**< lat, lon, alt, radians */
|
||||
// parameters
|
||||
control::BlockParam<float> _vGyro; /**< gyro process noise */
|
||||
control::BlockParam<float> _vAccel; /**< accelerometer process noise */
|
||||
control::BlockParam<float> _rMag; /**< magnetometer measurement noise */
|
||||
control::BlockParam<float> _rGpsVel; /**< gps velocity measurement noise */
|
||||
control::BlockParam<float> _rGpsPos; /**< gps position measurement noise */
|
||||
control::BlockParam<float> _rGpsAlt; /**< gps altitude measurement noise */
|
||||
control::BlockParam<float> _rPressAlt; /**< press altitude measurement noise */
|
||||
control::BlockParam<float> _rAccel; /**< accelerometer measurement noise */
|
||||
control::BlockParam<float> _magDip; /**< magnetic inclination with level */
|
||||
control::BlockParam<float> _magDec; /**< magnetic declination, clockwise rotation */
|
||||
control::BlockParam<float> _g; /**< gravitational constant */
|
||||
control::BlockParam<float> _faultPos; /**< fault detection threshold for position */
|
||||
control::BlockParam<float> _faultAtt; /**< fault detection threshold for attitude */
|
||||
// status
|
||||
bool _attitudeInitialized;
|
||||
bool _positionInitialized;
|
||||
uint16_t _attitudeInitCounter;
|
||||
// accessors
|
||||
int32_t getLatDegE7() { return int32_t(lat * 1.0e7 * M_RAD_TO_DEG); }
|
||||
void setLatDegE7(int32_t val) { lat = val / 1.0e7 / M_RAD_TO_DEG; }
|
||||
int32_t getLonDegE7() { return int32_t(lon * 1.0e7 * M_RAD_TO_DEG); }
|
||||
void setLonDegE7(int32_t val) { lon = val / 1.0e7 / M_RAD_TO_DEG; }
|
||||
int32_t getAltE3() { return int32_t(alt * 1.0e3); }
|
||||
void setAltE3(int32_t val) { alt = double(val) / 1.0e3; }
|
||||
};
|
||||
@@ -0,0 +1,152 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Example User <mail@example.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file kalman_demo.cpp
|
||||
* Demonstration of control library
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <math.h>
|
||||
#include "KalmanNav.hpp"
|
||||
|
||||
static bool thread_should_exit = false; /**< Deamon exit flag */
|
||||
static bool thread_running = false; /**< Deamon status flag */
|
||||
static int deamon_task; /**< Handle of deamon task / thread */
|
||||
|
||||
/**
|
||||
* Deamon management function.
|
||||
*/
|
||||
extern "C" __EXPORT int att_pos_estimator_ekf_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Mainloop of deamon.
|
||||
*/
|
||||
int kalman_demo_thread_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Print the correct usage.
|
||||
*/
|
||||
static void usage(const char *reason);
|
||||
|
||||
static void
|
||||
usage(const char *reason)
|
||||
{
|
||||
if (reason)
|
||||
fprintf(stderr, "%s\n", reason);
|
||||
|
||||
fprintf(stderr, "usage: kalman_demo {start|stop|status} [-p <additional params>]\n\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
/**
|
||||
* The deamon app only briefly exists to start
|
||||
* the background job. The stack size assigned in the
|
||||
* Makefile does only apply to this management task.
|
||||
*
|
||||
* The actual stack size should be set in the call
|
||||
* to task_create().
|
||||
*/
|
||||
int att_pos_estimator_ekf_main(int argc, char *argv[])
|
||||
{
|
||||
|
||||
if (argc < 1)
|
||||
usage("missing command");
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
if (thread_running) {
|
||||
printf("kalman_demo already running\n");
|
||||
/* this is not an error */
|
||||
exit(0);
|
||||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("kalman_demo",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
4096,
|
||||
kalman_demo_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "stop")) {
|
||||
thread_should_exit = true;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
if (thread_running) {
|
||||
printf("\tkalman_demo app is running\n");
|
||||
|
||||
} else {
|
||||
printf("\tkalman_demo app not started\n");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
usage("unrecognized command");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
int kalman_demo_thread_main(int argc, char *argv[])
|
||||
{
|
||||
|
||||
printf("[kalman_demo] starting\n");
|
||||
|
||||
using namespace math;
|
||||
|
||||
thread_running = true;
|
||||
|
||||
KalmanNav nav(NULL, "KF");
|
||||
|
||||
while (!thread_should_exit) {
|
||||
nav.update();
|
||||
}
|
||||
|
||||
printf("[kalman_demo] exiting.\n");
|
||||
|
||||
thread_running = false;
|
||||
|
||||
return 0;
|
||||
}
|
||||
@@ -0,0 +1,45 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Full attitude / position Extended Kalman Filter
|
||||
#
|
||||
|
||||
MODULE_COMMAND = att_pos_estimator_ekf
|
||||
|
||||
# XXX this might be intended for the spawned deamon, validate
|
||||
MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30"
|
||||
|
||||
SRCS = kalman_main.cpp \
|
||||
KalmanNav.cpp \
|
||||
params.c
|
||||
@@ -0,0 +1,16 @@
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/*PARAM_DEFINE_FLOAT(NAME,0.0f);*/
|
||||
PARAM_DEFINE_FLOAT(KF_V_GYRO, 0.008f);
|
||||
PARAM_DEFINE_FLOAT(KF_V_ACCEL, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_R_MAG, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_R_GPS_VEL, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_R_GPS_POS, 5.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_R_GPS_ALT, 5.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_R_PRESS_ALT, 0.1f);
|
||||
PARAM_DEFINE_FLOAT(KF_R_ACCEL, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_FAULT_POS, 10.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_FAULT_ATT, 10.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_ENV_G, 9.765f);
|
||||
PARAM_DEFINE_FLOAT(KF_ENV_MAG_DIP, 60.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_ENV_MAG_DEC, 0.0f);
|
||||
@@ -0,0 +1,169 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Thomas Gubler <thomasgubler@student.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 fixedwing_att_control_rate.c
|
||||
* Implementation of a fixed wing attitude controller.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <math.h>
|
||||
#include <poll.h>
|
||||
#include <time.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/pid/pid.h>
|
||||
#include <systemlib/geo/geo.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
#include "fixedwing_att_control_att.h"
|
||||
|
||||
|
||||
struct fw_att_control_params {
|
||||
float roll_p;
|
||||
float rollrate_lim;
|
||||
float pitch_p;
|
||||
float pitchrate_lim;
|
||||
float yawrate_lim;
|
||||
float pitch_roll_compensation_p;
|
||||
};
|
||||
|
||||
struct fw_pos_control_param_handles {
|
||||
param_t roll_p;
|
||||
param_t rollrate_lim;
|
||||
param_t pitch_p;
|
||||
param_t pitchrate_lim;
|
||||
param_t yawrate_lim;
|
||||
param_t pitch_roll_compensation_p;
|
||||
};
|
||||
|
||||
|
||||
|
||||
/* Internal Prototypes */
|
||||
static int parameters_init(struct fw_pos_control_param_handles *h);
|
||||
static int parameters_update(const struct fw_pos_control_param_handles *h, struct fw_att_control_params *p);
|
||||
|
||||
static int parameters_init(struct fw_pos_control_param_handles *h)
|
||||
{
|
||||
/* PID parameters */
|
||||
h->roll_p = param_find("FW_ROLL_P");
|
||||
h->rollrate_lim = param_find("FW_ROLLR_LIM");
|
||||
h->pitch_p = param_find("FW_PITCH_P");
|
||||
h->pitchrate_lim = param_find("FW_PITCHR_LIM");
|
||||
h->yawrate_lim = param_find("FW_YAWR_LIM");
|
||||
h->pitch_roll_compensation_p = param_find("FW_PITCH_RCOMP");
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
static int parameters_update(const struct fw_pos_control_param_handles *h, struct fw_att_control_params *p)
|
||||
{
|
||||
param_get(h->roll_p, &(p->roll_p));
|
||||
param_get(h->rollrate_lim, &(p->rollrate_lim));
|
||||
param_get(h->pitch_p, &(p->pitch_p));
|
||||
param_get(h->pitchrate_lim, &(p->pitchrate_lim));
|
||||
param_get(h->yawrate_lim, &(p->yawrate_lim));
|
||||
param_get(h->pitch_roll_compensation_p, &(p->pitch_roll_compensation_p));
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
|
||||
const struct vehicle_attitude_s *att,
|
||||
const float speed_body[],
|
||||
struct vehicle_rates_setpoint_s *rates_sp)
|
||||
{
|
||||
static int counter = 0;
|
||||
static bool initialized = false;
|
||||
|
||||
static struct fw_att_control_params p;
|
||||
static struct fw_pos_control_param_handles h;
|
||||
|
||||
static PID_t roll_controller;
|
||||
static PID_t pitch_controller;
|
||||
|
||||
|
||||
if (!initialized) {
|
||||
parameters_init(&h);
|
||||
parameters_update(&h, &p);
|
||||
pid_init(&roll_controller, p.roll_p, 0, 0, 0, p.rollrate_lim, PID_MODE_DERIVATIV_NONE); //P Controller
|
||||
pid_init(&pitch_controller, p.pitch_p, 0, 0, 0, p.pitchrate_lim, PID_MODE_DERIVATIV_NONE); //P Controller
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
/* load new parameters with lower rate */
|
||||
if (counter % 100 == 0) {
|
||||
/* update parameters from storage */
|
||||
parameters_update(&h, &p);
|
||||
pid_set_parameters(&roll_controller, p.roll_p, 0, 0, 0, p.rollrate_lim);
|
||||
pid_set_parameters(&pitch_controller, p.pitch_p, 0, 0, 0, p.pitchrate_lim);
|
||||
}
|
||||
|
||||
/* Roll (P) */
|
||||
rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body, att->roll, 0, 0);
|
||||
|
||||
|
||||
/* Pitch (P) */
|
||||
|
||||
/* compensate feedforward for loss of lift due to non-horizontal angle of wing */
|
||||
float pitch_sp_rollcompensation = p.pitch_roll_compensation_p * fabsf(sinf(att_sp->roll_body));
|
||||
/* set pitch plus feedforward roll compensation */
|
||||
rates_sp->pitch = pid_calculate(&pitch_controller,
|
||||
att_sp->pitch_body + pitch_sp_rollcompensation,
|
||||
att->pitch, 0, 0);
|
||||
|
||||
/* Yaw (from coordinated turn constraint or lateral force) */
|
||||
rates_sp->yaw = (att->rollspeed * rates_sp->roll + 9.81f * sinf(att->roll) * cosf(att->pitch) + speed_body[0] * rates_sp->pitch * sinf(att->roll))
|
||||
/ (speed_body[0] * cosf(att->roll) * cosf(att->pitch) + speed_body[2] * sinf(att->pitch));
|
||||
|
||||
// printf("rates_sp->yaw %.4f \n", (double)rates_sp->yaw);
|
||||
|
||||
counter++;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -0,0 +1,51 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Thomas Gubler <thomasgubler@student.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 Fixed Wing Attitude Control */
|
||||
|
||||
#ifndef FIXEDWING_ATT_CONTROL_ATT_H_
|
||||
#define FIXEDWING_ATT_CONTROL_ATT_H_
|
||||
|
||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
|
||||
int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
|
||||
const struct vehicle_attitude_s *att,
|
||||
const float speed_body[],
|
||||
struct vehicle_rates_setpoint_s *rates_sp);
|
||||
|
||||
#endif /* FIXEDWING_ATT_CONTROL_ATT_H_ */
|
||||
@@ -0,0 +1,370 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* @author Doug Weibel <douglas.weibel@colorado.edu>
|
||||
*
|
||||
* 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 fixedwing_att_control.c
|
||||
* Implementation of a fixed wing attitude controller.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <math.h>
|
||||
#include <poll.h>
|
||||
#include <time.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_global_position_setpoint.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/debug_key_value.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/pid/pid.h>
|
||||
#include <systemlib/geo/geo.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
#include "fixedwing_att_control_rate.h"
|
||||
#include "fixedwing_att_control_att.h"
|
||||
|
||||
/* Prototypes */
|
||||
/**
|
||||
* Deamon management function.
|
||||
*/
|
||||
__EXPORT int fixedwing_att_control_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Mainloop of deamon.
|
||||
*/
|
||||
int fixedwing_att_control_thread_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Print the correct usage.
|
||||
*/
|
||||
static void usage(const char *reason);
|
||||
|
||||
/* Variables */
|
||||
static bool thread_should_exit = false; /**< Deamon exit flag */
|
||||
static bool thread_running = false; /**< Deamon status flag */
|
||||
static int deamon_task; /**< Handle of deamon task / thread */
|
||||
|
||||
/* Main Thread */
|
||||
int fixedwing_att_control_thread_main(int argc, char *argv[])
|
||||
{
|
||||
/* read arguments */
|
||||
bool verbose = false;
|
||||
|
||||
for (int i = 1; i < argc; i++) {
|
||||
if (strcmp(argv[i], "-v") == 0 || strcmp(argv[i], "--verbose") == 0) {
|
||||
verbose = true;
|
||||
}
|
||||
}
|
||||
|
||||
/* welcome user */
|
||||
printf("[fixedwing att control] started\n");
|
||||
|
||||
/* declare and safely initialize all structs */
|
||||
struct vehicle_attitude_s att;
|
||||
memset(&att, 0, sizeof(att));
|
||||
struct vehicle_attitude_setpoint_s att_sp;
|
||||
memset(&att_sp, 0, sizeof(att_sp));
|
||||
struct vehicle_rates_setpoint_s rates_sp;
|
||||
memset(&rates_sp, 0, sizeof(rates_sp));
|
||||
struct vehicle_global_position_s global_pos;
|
||||
memset(&global_pos, 0, sizeof(global_pos));
|
||||
struct manual_control_setpoint_s manual_sp;
|
||||
memset(&manual_sp, 0, sizeof(manual_sp));
|
||||
struct vehicle_status_s vstatus;
|
||||
memset(&vstatus, 0, sizeof(vstatus));
|
||||
|
||||
/* output structs */
|
||||
struct actuator_controls_s actuators;
|
||||
memset(&actuators, 0, sizeof(actuators));
|
||||
|
||||
|
||||
/* publish actuator controls */
|
||||
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) {
|
||||
actuators.control[i] = 0.0f;
|
||||
}
|
||||
|
||||
orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators);
|
||||
orb_advert_t rates_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
|
||||
|
||||
/* subscribe */
|
||||
int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
||||
int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
|
||||
int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
|
||||
int manual_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
|
||||
int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
|
||||
|
||||
/* Setup of loop */
|
||||
float gyro[3] = {0.0f, 0.0f, 0.0f};
|
||||
float speed_body[3] = {0.0f, 0.0f, 0.0f};
|
||||
struct pollfd fds = { .fd = att_sub, .events = POLLIN };
|
||||
|
||||
while (!thread_should_exit) {
|
||||
/* wait for a sensor update, check for exit condition every 500 ms */
|
||||
poll(&fds, 1, 500);
|
||||
|
||||
/* Check if there is a new position measurement or attitude setpoint */
|
||||
bool pos_updated;
|
||||
orb_check(global_pos_sub, &pos_updated);
|
||||
bool att_sp_updated;
|
||||
orb_check(att_sp_sub, &att_sp_updated);
|
||||
|
||||
/* get a local copy of attitude */
|
||||
orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
|
||||
|
||||
if (att_sp_updated)
|
||||
orb_copy(ORB_ID(vehicle_attitude_setpoint), att_sp_sub, &att_sp);
|
||||
|
||||
if (pos_updated) {
|
||||
orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos);
|
||||
|
||||
if (att.R_valid) {
|
||||
speed_body[0] = att.R[0][0] * global_pos.vx + att.R[0][1] * global_pos.vy + att.R[0][2] * global_pos.vz;
|
||||
speed_body[1] = att.R[1][0] * global_pos.vx + att.R[1][1] * global_pos.vy + att.R[1][2] * global_pos.vz;
|
||||
speed_body[2] = att.R[2][0] * global_pos.vx + att.R[2][1] * global_pos.vy + att.R[2][2] * global_pos.vz;
|
||||
|
||||
} else {
|
||||
speed_body[0] = 0;
|
||||
speed_body[1] = 0;
|
||||
speed_body[2] = 0;
|
||||
|
||||
printf("FW ATT CONTROL: Did not get a valid R\n");
|
||||
}
|
||||
}
|
||||
|
||||
orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp);
|
||||
orb_copy(ORB_ID(vehicle_status), vstatus_sub, &vstatus);
|
||||
|
||||
gyro[0] = att.rollspeed;
|
||||
gyro[1] = att.pitchspeed;
|
||||
gyro[2] = att.yawspeed;
|
||||
|
||||
/* control */
|
||||
|
||||
if (vstatus.state_machine == SYSTEM_STATE_AUTO ||
|
||||
vstatus.state_machine == SYSTEM_STATE_STABILIZED) {
|
||||
/* attitude control */
|
||||
fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
|
||||
|
||||
/* angular rate control */
|
||||
fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
|
||||
|
||||
/* pass through throttle */
|
||||
actuators.control[3] = att_sp.thrust;
|
||||
|
||||
/* set flaps to zero */
|
||||
actuators.control[4] = 0.0f;
|
||||
|
||||
} else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) {
|
||||
if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) {
|
||||
|
||||
/* if the RC signal is lost, try to stay level and go slowly back down to ground */
|
||||
if (vstatus.rc_signal_lost) {
|
||||
|
||||
/* put plane into loiter */
|
||||
att_sp.roll_body = 0.3f;
|
||||
att_sp.pitch_body = 0.0f;
|
||||
|
||||
/* limit throttle to 60 % of last value if sane */
|
||||
if (isfinite(manual_sp.throttle) &&
|
||||
(manual_sp.throttle >= 0.0f) &&
|
||||
(manual_sp.throttle <= 1.0f)) {
|
||||
att_sp.thrust = 0.6f * manual_sp.throttle;
|
||||
|
||||
} else {
|
||||
att_sp.thrust = 0.0f;
|
||||
}
|
||||
|
||||
att_sp.yaw_body = 0;
|
||||
|
||||
// XXX disable yaw control, loiter
|
||||
|
||||
} else {
|
||||
|
||||
att_sp.roll_body = manual_sp.roll;
|
||||
att_sp.pitch_body = manual_sp.pitch;
|
||||
att_sp.yaw_body = 0;
|
||||
att_sp.thrust = manual_sp.throttle;
|
||||
}
|
||||
|
||||
att_sp.timestamp = hrt_absolute_time();
|
||||
|
||||
/* attitude control */
|
||||
fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
|
||||
|
||||
/* angular rate control */
|
||||
fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
|
||||
|
||||
/* pass through throttle */
|
||||
actuators.control[3] = att_sp.thrust;
|
||||
|
||||
/* pass through flaps */
|
||||
if (isfinite(manual_sp.flaps)) {
|
||||
actuators.control[4] = manual_sp.flaps;
|
||||
|
||||
} else {
|
||||
actuators.control[4] = 0.0f;
|
||||
}
|
||||
|
||||
} else if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
|
||||
/* directly pass through values */
|
||||
actuators.control[0] = manual_sp.roll;
|
||||
/* positive pitch means negative actuator -> pull up */
|
||||
actuators.control[1] = manual_sp.pitch;
|
||||
actuators.control[2] = manual_sp.yaw;
|
||||
actuators.control[3] = manual_sp.throttle;
|
||||
|
||||
if (isfinite(manual_sp.flaps)) {
|
||||
actuators.control[4] = manual_sp.flaps;
|
||||
|
||||
} else {
|
||||
actuators.control[4] = 0.0f;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* publish rates */
|
||||
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp);
|
||||
|
||||
/* sanity check and publish actuator outputs */
|
||||
if (isfinite(actuators.control[0]) &&
|
||||
isfinite(actuators.control[1]) &&
|
||||
isfinite(actuators.control[2]) &&
|
||||
isfinite(actuators.control[3])) {
|
||||
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
|
||||
}
|
||||
}
|
||||
|
||||
printf("[fixedwing_att_control] exiting, stopping all motors.\n");
|
||||
thread_running = false;
|
||||
|
||||
/* kill all outputs */
|
||||
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++)
|
||||
actuators.control[i] = 0.0f;
|
||||
|
||||
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
|
||||
|
||||
|
||||
|
||||
close(att_sub);
|
||||
close(actuator_pub);
|
||||
close(rates_pub);
|
||||
|
||||
fflush(stdout);
|
||||
exit(0);
|
||||
|
||||
return 0;
|
||||
|
||||
}
|
||||
|
||||
/* Startup Functions */
|
||||
|
||||
static void
|
||||
usage(const char *reason)
|
||||
{
|
||||
if (reason)
|
||||
fprintf(stderr, "%s\n", reason);
|
||||
|
||||
fprintf(stderr, "usage: fixedwing_att_control {start|stop|status}\n\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
/**
|
||||
* The deamon app only briefly exists to start
|
||||
* the background job. The stack size assigned in the
|
||||
* Makefile does only apply to this management task.
|
||||
*
|
||||
* The actual stack size should be set in the call
|
||||
* to task_create().
|
||||
*/
|
||||
int fixedwing_att_control_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 1)
|
||||
usage("missing command");
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
if (thread_running) {
|
||||
printf("fixedwing_att_control already running\n");
|
||||
/* this is not an error */
|
||||
exit(0);
|
||||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("fixedwing_att_control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 20,
|
||||
2048,
|
||||
fixedwing_att_control_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
thread_running = true;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "stop")) {
|
||||
thread_should_exit = true;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
if (thread_running) {
|
||||
printf("\tfixedwing_att_control is running\n");
|
||||
|
||||
} else {
|
||||
printf("\tfixedwing_att_control not started\n");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
usage("unrecognized command");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -0,0 +1,211 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Thomas Gubler <thomasgubler@student.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 fixedwing_att_control_rate.c
|
||||
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
*
|
||||
* Implementation of a fixed wing attitude controller.
|
||||
*
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <math.h>
|
||||
#include <poll.h>
|
||||
#include <time.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/pid/pid.h>
|
||||
#include <systemlib/geo/geo.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
#include "fixedwing_att_control_rate.h"
|
||||
|
||||
/*
|
||||
* Controller parameters, accessible via MAVLink
|
||||
*
|
||||
*/
|
||||
// Roll control parameters
|
||||
PARAM_DEFINE_FLOAT(FW_ROLLR_P, 0.9f);
|
||||
PARAM_DEFINE_FLOAT(FW_ROLLR_I, 0.2f);
|
||||
PARAM_DEFINE_FLOAT(FW_ROLLR_AWU, 0.9f);
|
||||
PARAM_DEFINE_FLOAT(FW_ROLLR_LIM, 0.7f); // Roll rate limit in radians/sec, applies to the roll controller
|
||||
PARAM_DEFINE_FLOAT(FW_ROLL_P, 4.0f);
|
||||
PARAM_DEFINE_FLOAT(FW_PITCH_RCOMP, 0.1f);
|
||||
|
||||
//Pitch control parameters
|
||||
PARAM_DEFINE_FLOAT(FW_PITCHR_P, 0.8f);
|
||||
PARAM_DEFINE_FLOAT(FW_PITCHR_I, 0.2f);
|
||||
PARAM_DEFINE_FLOAT(FW_PITCHR_AWU, 0.8f);
|
||||
PARAM_DEFINE_FLOAT(FW_PITCHR_LIM, 0.35f); // Pitch rate limit in radians/sec, applies to the pitch controller
|
||||
PARAM_DEFINE_FLOAT(FW_PITCH_P, 8.0f);
|
||||
|
||||
//Yaw control parameters //XXX TODO this is copy paste, asign correct values
|
||||
PARAM_DEFINE_FLOAT(FW_YAWR_P, 0.3f);
|
||||
PARAM_DEFINE_FLOAT(FW_YAWR_I, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FW_YAWR_AWU, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FW_YAWR_LIM, 0.35f); // Yaw rate limit in radians/sec
|
||||
|
||||
/* feedforward compensation */
|
||||
PARAM_DEFINE_FLOAT(FW_PITCH_THR_P, 0.1f); /**< throttle to pitch coupling feedforward */
|
||||
|
||||
struct fw_rate_control_params {
|
||||
float rollrate_p;
|
||||
float rollrate_i;
|
||||
float rollrate_awu;
|
||||
float pitchrate_p;
|
||||
float pitchrate_i;
|
||||
float pitchrate_awu;
|
||||
float yawrate_p;
|
||||
float yawrate_i;
|
||||
float yawrate_awu;
|
||||
float pitch_thr_ff;
|
||||
};
|
||||
|
||||
struct fw_rate_control_param_handles {
|
||||
param_t rollrate_p;
|
||||
param_t rollrate_i;
|
||||
param_t rollrate_awu;
|
||||
param_t pitchrate_p;
|
||||
param_t pitchrate_i;
|
||||
param_t pitchrate_awu;
|
||||
param_t yawrate_p;
|
||||
param_t yawrate_i;
|
||||
param_t yawrate_awu;
|
||||
param_t pitch_thr_ff;
|
||||
};
|
||||
|
||||
|
||||
|
||||
/* Internal Prototypes */
|
||||
static int parameters_init(struct fw_rate_control_param_handles *h);
|
||||
static int parameters_update(const struct fw_rate_control_param_handles *h, struct fw_rate_control_params *p);
|
||||
|
||||
static int parameters_init(struct fw_rate_control_param_handles *h)
|
||||
{
|
||||
/* PID parameters */
|
||||
h->rollrate_p = param_find("FW_ROLLR_P"); //TODO define rate params for fixed wing
|
||||
h->rollrate_i = param_find("FW_ROLLR_I");
|
||||
h->rollrate_awu = param_find("FW_ROLLR_AWU");
|
||||
|
||||
h->pitchrate_p = param_find("FW_PITCHR_P");
|
||||
h->pitchrate_i = param_find("FW_PITCHR_I");
|
||||
h->pitchrate_awu = param_find("FW_PITCHR_AWU");
|
||||
|
||||
h->yawrate_p = param_find("FW_YAWR_P");
|
||||
h->yawrate_i = param_find("FW_YAWR_I");
|
||||
h->yawrate_awu = param_find("FW_YAWR_AWU");
|
||||
h->pitch_thr_ff = param_find("FW_PITCH_THR_P");
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
static int parameters_update(const struct fw_rate_control_param_handles *h, struct fw_rate_control_params *p)
|
||||
{
|
||||
param_get(h->rollrate_p, &(p->rollrate_p));
|
||||
param_get(h->rollrate_i, &(p->rollrate_i));
|
||||
param_get(h->rollrate_awu, &(p->rollrate_awu));
|
||||
param_get(h->pitchrate_p, &(p->pitchrate_p));
|
||||
param_get(h->pitchrate_i, &(p->pitchrate_i));
|
||||
param_get(h->pitchrate_awu, &(p->pitchrate_awu));
|
||||
param_get(h->yawrate_p, &(p->yawrate_p));
|
||||
param_get(h->yawrate_i, &(p->yawrate_i));
|
||||
param_get(h->yawrate_awu, &(p->yawrate_awu));
|
||||
param_get(h->pitch_thr_ff, &(p->pitch_thr_ff));
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
|
||||
const float rates[],
|
||||
struct actuator_controls_s *actuators)
|
||||
{
|
||||
static int counter = 0;
|
||||
static bool initialized = false;
|
||||
|
||||
static struct fw_rate_control_params p;
|
||||
static struct fw_rate_control_param_handles h;
|
||||
|
||||
static PID_t roll_rate_controller;
|
||||
static PID_t pitch_rate_controller;
|
||||
static PID_t yaw_rate_controller;
|
||||
|
||||
static uint64_t last_run = 0;
|
||||
const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
|
||||
last_run = hrt_absolute_time();
|
||||
|
||||
if (!initialized) {
|
||||
parameters_init(&h);
|
||||
parameters_update(&h, &p);
|
||||
pid_init(&roll_rate_controller, p.rollrate_p, p.rollrate_i, 0, p.rollrate_awu, 1, PID_MODE_DERIVATIV_NONE); // set D part to 0 because the controller layout is with a PI rate controller
|
||||
pid_init(&pitch_rate_controller, p.pitchrate_p, p.pitchrate_i, 0, p.pitchrate_awu, 1, PID_MODE_DERIVATIV_NONE); // set D part to 0 because the contpitcher layout is with a PI rate contpitcher
|
||||
pid_init(&yaw_rate_controller, p.yawrate_p, p.yawrate_i, 0, p.yawrate_awu, 1, PID_MODE_DERIVATIV_NONE); // set D part to 0 because the contpitcher layout is with a PI rate contpitcher
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
/* load new parameters with lower rate */
|
||||
if (counter % 100 == 0) {
|
||||
/* update parameters from storage */
|
||||
parameters_update(&h, &p);
|
||||
pid_set_parameters(&roll_rate_controller, p.rollrate_p, p.rollrate_i, 0, p.rollrate_awu, 1);
|
||||
pid_set_parameters(&pitch_rate_controller, p.pitchrate_p, p.pitchrate_i, 0, p.pitchrate_awu, 1);
|
||||
pid_set_parameters(&yaw_rate_controller, p.yawrate_p, p.yawrate_i, 0, p.yawrate_awu, 1);
|
||||
}
|
||||
|
||||
|
||||
/* roll rate (PI) */
|
||||
actuators->control[0] = pid_calculate(&roll_rate_controller, rate_sp->roll, rates[0], 0.0f, deltaT);
|
||||
/* pitch rate (PI) */
|
||||
actuators->control[1] = -pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0.0f, deltaT);
|
||||
/* yaw rate (PI) */
|
||||
actuators->control[2] = pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0.0f, deltaT);
|
||||
|
||||
counter++;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -0,0 +1,48 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Thomas Gubler <thomasgubler@student.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 Fixed Wing Attitude Rate Control */
|
||||
|
||||
#ifndef FIXEDWING_ATT_CONTROL_RATE_H_
|
||||
#define FIXEDWING_ATT_CONTROL_RATE_H_
|
||||
|
||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
|
||||
int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
|
||||
const float rates[],
|
||||
struct actuator_controls_s *actuators);
|
||||
|
||||
#endif /* FIXEDWING_ATT_CONTROL_RATE_H_ */
|
||||
@@ -0,0 +1,42 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Fixedwing Attitude Control application
|
||||
#
|
||||
|
||||
MODULE_COMMAND = fixedwing_att_control
|
||||
|
||||
SRCS = fixedwing_att_control_main.c \
|
||||
fixedwing_att_control_att.c \
|
||||
fixedwing_att_control_rate.c
|
||||
@@ -0,0 +1,170 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: James Goppert
|
||||
*
|
||||
* 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 fixedwing_backside_main.cpp
|
||||
* @author James Goppert
|
||||
*
|
||||
* Fixedwing backside controller using control library
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <controllib/fixedwing.hpp>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <math.h>
|
||||
|
||||
static bool thread_should_exit = false; /**< Deamon exit flag */
|
||||
static bool thread_running = false; /**< Deamon status flag */
|
||||
static int deamon_task; /**< Handle of deamon task / thread */
|
||||
|
||||
/**
|
||||
* Deamon management function.
|
||||
*/
|
||||
extern "C" __EXPORT int fixedwing_backside_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Mainloop of deamon.
|
||||
*/
|
||||
int control_demo_thread_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Test function
|
||||
*/
|
||||
void test();
|
||||
|
||||
/**
|
||||
* Print the correct usage.
|
||||
*/
|
||||
static void usage(const char *reason);
|
||||
|
||||
static void
|
||||
usage(const char *reason)
|
||||
{
|
||||
if (reason)
|
||||
fprintf(stderr, "%s\n", reason);
|
||||
|
||||
fprintf(stderr, "usage: control_demo {start|stop|status} [-p <additional params>]\n\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
/**
|
||||
* The deamon app only briefly exists to start
|
||||
* the background job. The stack size assigned in the
|
||||
* Makefile does only apply to this management task.
|
||||
*
|
||||
* The actual stack size should be set in the call
|
||||
* to task_create().
|
||||
*/
|
||||
int fixedwing_backside_main(int argc, char *argv[])
|
||||
{
|
||||
|
||||
if (argc < 1)
|
||||
usage("missing command");
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
if (thread_running) {
|
||||
printf("control_demo already running\n");
|
||||
/* this is not an error */
|
||||
exit(0);
|
||||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("control_demo",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 10,
|
||||
5120,
|
||||
control_demo_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "test")) {
|
||||
test();
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "stop")) {
|
||||
thread_should_exit = true;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
if (thread_running) {
|
||||
printf("\tcontrol_demo app is running\n");
|
||||
|
||||
} else {
|
||||
printf("\tcontrol_demo app not started\n");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
usage("unrecognized command");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
int control_demo_thread_main(int argc, char *argv[])
|
||||
{
|
||||
|
||||
printf("[control_Demo] starting\n");
|
||||
|
||||
using namespace control;
|
||||
|
||||
fixedwing::BlockMultiModeBacksideAutopilot autopilot(NULL, "FWB");
|
||||
|
||||
thread_running = true;
|
||||
|
||||
while (!thread_should_exit) {
|
||||
autopilot.update();
|
||||
}
|
||||
|
||||
printf("[control_demo] exiting.\n");
|
||||
|
||||
thread_running = false;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void test()
|
||||
{
|
||||
printf("beginning control lib test\n");
|
||||
control::basicBlocksTest();
|
||||
}
|
||||
@@ -0,0 +1,40 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Fixedwing backside controller
|
||||
#
|
||||
|
||||
MODULE_COMMAND = fixedwing_backside
|
||||
|
||||
SRCS = fixedwing_backside_main.cpp
|
||||
@@ -0,0 +1,71 @@
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
// currently tuned for easystar from arkhangar in HIL
|
||||
//https://github.com/arktools/arkhangar
|
||||
|
||||
// 16 is max name length
|
||||
|
||||
// gyro low pass filter
|
||||
PARAM_DEFINE_FLOAT(FWB_P_LP, 300.0f); // roll rate low pass cut freq
|
||||
PARAM_DEFINE_FLOAT(FWB_Q_LP, 300.0f); // pitch rate low pass cut freq
|
||||
PARAM_DEFINE_FLOAT(FWB_R_LP, 300.0f); // yaw rate low pass cut freq
|
||||
|
||||
// yaw washout
|
||||
PARAM_DEFINE_FLOAT(FWB_R_HP, 1.0f); // yaw rate high pass
|
||||
|
||||
// stabilization mode
|
||||
PARAM_DEFINE_FLOAT(FWB_P2AIL, 0.3f); // roll rate 2 aileron
|
||||
PARAM_DEFINE_FLOAT(FWB_Q2ELV, 0.1f); // pitch rate 2 elevator
|
||||
PARAM_DEFINE_FLOAT(FWB_R2RDR, 0.1f); // yaw rate 2 rudder
|
||||
|
||||
// psi -> phi -> p
|
||||
PARAM_DEFINE_FLOAT(FWB_PSI2PHI, 0.5f); // heading 2 roll
|
||||
PARAM_DEFINE_FLOAT(FWB_PHI2P, 1.0f); // roll to roll rate
|
||||
PARAM_DEFINE_FLOAT(FWB_PHI_LIM_MAX, 0.3f); // roll limit, 28 deg
|
||||
|
||||
// velocity -> theta
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_P, 1.0f); // velocity to pitch angle PID, prop gain
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_I, 0.0f); // integral gain
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_D, 0.0f); // derivative gain
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_D_LP, 0.0f); // derivative low-pass
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_I_MAX, 0.0f); // integrator wind up guard
|
||||
PARAM_DEFINE_FLOAT(FWB_THE_MIN, -0.5f); // the max commanded pitch angle
|
||||
PARAM_DEFINE_FLOAT(FWB_THE_MAX, 0.5f); // the min commanded pitch angle
|
||||
|
||||
|
||||
// theta -> q
|
||||
PARAM_DEFINE_FLOAT(FWB_THE2Q_P, 1.0f); // pitch angle to pitch-rate PID
|
||||
PARAM_DEFINE_FLOAT(FWB_THE2Q_I, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_THE2Q_D, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_THE2Q_D_LP, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_THE2Q_I_MAX, 0.0f);
|
||||
|
||||
// h -> thr
|
||||
PARAM_DEFINE_FLOAT(FWB_H2THR_P, 0.01f); // altitude to throttle PID
|
||||
PARAM_DEFINE_FLOAT(FWB_H2THR_I, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_H2THR_D, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_H2THR_D_LP, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_H2THR_I_MAX, 0.0f);
|
||||
|
||||
// crosstrack
|
||||
PARAM_DEFINE_FLOAT(FWB_XT2YAW_MAX, 1.57f); // cross-track to yaw angle limit 90 deg
|
||||
PARAM_DEFINE_FLOAT(FWB_XT2YAW, 0.005f); // cross-track to yaw angle gain
|
||||
|
||||
// speed command
|
||||
PARAM_DEFINE_FLOAT(FWB_V_MIN, 10.0f); // minimum commanded velocity
|
||||
PARAM_DEFINE_FLOAT(FWB_V_CMD, 12.0f); // commanded velocity
|
||||
PARAM_DEFINE_FLOAT(FWB_V_MAX, 16.0f); // maximum commanded velocity
|
||||
|
||||
// rate of climb
|
||||
// this is what rate of climb is commanded (in m/s)
|
||||
// when the pitch stick is fully defelcted in simple mode
|
||||
PARAM_DEFINE_FLOAT(FWB_ROC_MAX, 1.0f);
|
||||
|
||||
// rate of climb -> thr
|
||||
PARAM_DEFINE_FLOAT(FWB_ROC2THR_P, 0.01f); // rate of climb to throttle PID
|
||||
PARAM_DEFINE_FLOAT(FWB_ROC2THR_I, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_ROC2THR_D, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_ROC2THR_D_LP, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_ROC2THR_I_MAX, 0.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(FWB_TRIM_THR, 0.8f); // trim throttle (0,1)
|
||||
@@ -0,0 +1,479 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* @author Doug Weibel <douglas.weibel@colorado.edu>
|
||||
*
|
||||
* 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 fixedwing_pos_control.c
|
||||
* Implementation of a fixed wing attitude controller.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <math.h>
|
||||
#include <poll.h>
|
||||
#include <time.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_global_position_setpoint.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/pid/pid.h>
|
||||
#include <systemlib/geo/geo.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
/*
|
||||
* Controller parameters, accessible via MAVLink
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_HEAD_P, 0.1f);
|
||||
PARAM_DEFINE_FLOAT(FW_HEADR_I, 0.1f);
|
||||
PARAM_DEFINE_FLOAT(FW_HEADR_LIM, 1.5f); //TODO: think about reasonable value
|
||||
PARAM_DEFINE_FLOAT(FW_XTRACK_P, 0.01745f); // Radians per meter off track
|
||||
PARAM_DEFINE_FLOAT(FW_ALT_P, 0.1f);
|
||||
PARAM_DEFINE_FLOAT(FW_ROLL_LIM, 0.7f); // Roll angle limit in radians
|
||||
PARAM_DEFINE_FLOAT(FW_HEADR_P, 0.1f);
|
||||
PARAM_DEFINE_FLOAT(FW_PITCH_LIM, 0.35f); /**< Pitch angle limit in radians per second */
|
||||
|
||||
struct fw_pos_control_params {
|
||||
float heading_p;
|
||||
float headingr_p;
|
||||
float headingr_i;
|
||||
float headingr_lim;
|
||||
float xtrack_p;
|
||||
float altitude_p;
|
||||
float roll_lim;
|
||||
float pitch_lim;
|
||||
};
|
||||
|
||||
struct fw_pos_control_param_handles {
|
||||
param_t heading_p;
|
||||
param_t headingr_p;
|
||||
param_t headingr_i;
|
||||
param_t headingr_lim;
|
||||
param_t xtrack_p;
|
||||
param_t altitude_p;
|
||||
param_t roll_lim;
|
||||
param_t pitch_lim;
|
||||
};
|
||||
|
||||
|
||||
struct planned_path_segments_s {
|
||||
bool segment_type;
|
||||
double start_lat; // Start of line or center of arc
|
||||
double start_lon;
|
||||
double end_lat;
|
||||
double end_lon;
|
||||
float radius; // Radius of arc
|
||||
float arc_start_bearing; // Bearing from center to start of arc
|
||||
float arc_sweep; // Angle (radians) swept out by arc around center.
|
||||
// Positive for clockwise, negative for counter-clockwise
|
||||
};
|
||||
|
||||
|
||||
/* Prototypes */
|
||||
/* Internal Prototypes */
|
||||
static int parameters_init(struct fw_pos_control_param_handles *h);
|
||||
static int parameters_update(const struct fw_pos_control_param_handles *h, struct fw_pos_control_params *p);
|
||||
|
||||
/**
|
||||
* Deamon management function.
|
||||
*/
|
||||
__EXPORT int fixedwing_pos_control_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Mainloop of deamon.
|
||||
*/
|
||||
int fixedwing_pos_control_thread_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Print the correct usage.
|
||||
*/
|
||||
static void usage(const char *reason);
|
||||
|
||||
/* Variables */
|
||||
static bool thread_should_exit = false; /**< Deamon exit flag */
|
||||
static bool thread_running = false; /**< Deamon status flag */
|
||||
static int deamon_task; /**< Handle of deamon task / thread */
|
||||
|
||||
|
||||
/**
|
||||
* Parameter management
|
||||
*/
|
||||
static int parameters_init(struct fw_pos_control_param_handles *h)
|
||||
{
|
||||
/* PID parameters */
|
||||
h->heading_p = param_find("FW_HEAD_P");
|
||||
h->headingr_p = param_find("FW_HEADR_P");
|
||||
h->headingr_i = param_find("FW_HEADR_I");
|
||||
h->headingr_lim = param_find("FW_HEADR_LIM");
|
||||
h->xtrack_p = param_find("FW_XTRACK_P");
|
||||
h->altitude_p = param_find("FW_ALT_P");
|
||||
h->roll_lim = param_find("FW_ROLL_LIM");
|
||||
h->pitch_lim = param_find("FW_PITCH_LIM");
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
static int parameters_update(const struct fw_pos_control_param_handles *h, struct fw_pos_control_params *p)
|
||||
{
|
||||
param_get(h->heading_p, &(p->heading_p));
|
||||
param_get(h->headingr_p, &(p->headingr_p));
|
||||
param_get(h->headingr_i, &(p->headingr_i));
|
||||
param_get(h->headingr_lim, &(p->headingr_lim));
|
||||
param_get(h->xtrack_p, &(p->xtrack_p));
|
||||
param_get(h->altitude_p, &(p->altitude_p));
|
||||
param_get(h->roll_lim, &(p->roll_lim));
|
||||
param_get(h->pitch_lim, &(p->pitch_lim));
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
|
||||
/* Main Thread */
|
||||
int fixedwing_pos_control_thread_main(int argc, char *argv[])
|
||||
{
|
||||
/* read arguments */
|
||||
bool verbose = false;
|
||||
|
||||
for (int i = 1; i < argc; i++) {
|
||||
if (strcmp(argv[i], "-v") == 0 || strcmp(argv[i], "--verbose") == 0) {
|
||||
verbose = true;
|
||||
}
|
||||
}
|
||||
|
||||
/* welcome user */
|
||||
printf("[fixedwing pos control] started\n");
|
||||
|
||||
/* declare and safely initialize all structs */
|
||||
struct vehicle_global_position_s global_pos;
|
||||
memset(&global_pos, 0, sizeof(global_pos));
|
||||
struct vehicle_global_position_s start_pos; // Temporary variable, replace with
|
||||
memset(&start_pos, 0, sizeof(start_pos)); // previous waypoint when available
|
||||
struct vehicle_global_position_setpoint_s global_setpoint;
|
||||
memset(&global_setpoint, 0, sizeof(global_setpoint));
|
||||
struct vehicle_attitude_s att;
|
||||
memset(&att, 0, sizeof(att));
|
||||
struct crosstrack_error_s xtrack_err;
|
||||
memset(&xtrack_err, 0, sizeof(xtrack_err));
|
||||
struct parameter_update_s param_update;
|
||||
memset(¶m_update, 0, sizeof(param_update));
|
||||
|
||||
/* output structs */
|
||||
struct vehicle_attitude_setpoint_s attitude_setpoint;
|
||||
memset(&attitude_setpoint, 0, sizeof(attitude_setpoint));
|
||||
|
||||
/* publish attitude setpoint */
|
||||
attitude_setpoint.roll_body = 0.0f;
|
||||
attitude_setpoint.pitch_body = 0.0f;
|
||||
attitude_setpoint.yaw_body = 0.0f;
|
||||
attitude_setpoint.thrust = 0.0f;
|
||||
orb_advert_t attitude_setpoint_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &attitude_setpoint);
|
||||
|
||||
/* subscribe */
|
||||
int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
|
||||
int global_setpoint_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
|
||||
int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
||||
int param_sub = orb_subscribe(ORB_ID(parameter_update));
|
||||
|
||||
/* Setup of loop */
|
||||
struct pollfd fds[2] = {
|
||||
{ .fd = param_sub, .events = POLLIN },
|
||||
{ .fd = att_sub, .events = POLLIN }
|
||||
};
|
||||
bool global_sp_updated_set_once = false;
|
||||
|
||||
float psi_track = 0.0f;
|
||||
|
||||
int counter = 0;
|
||||
|
||||
struct fw_pos_control_params p;
|
||||
struct fw_pos_control_param_handles h;
|
||||
|
||||
PID_t heading_controller;
|
||||
PID_t heading_rate_controller;
|
||||
PID_t offtrack_controller;
|
||||
PID_t altitude_controller;
|
||||
|
||||
parameters_init(&h);
|
||||
parameters_update(&h, &p);
|
||||
pid_init(&heading_controller, p.heading_p, 0.0f, 0.0f, 0.0f, 10000.0f, PID_MODE_DERIVATIV_NONE); //arbitrary high limit
|
||||
pid_init(&heading_rate_controller, p.headingr_p, p.headingr_i, 0.0f, 0.0f, p.roll_lim, PID_MODE_DERIVATIV_NONE);
|
||||
pid_init(&altitude_controller, p.altitude_p, 0.0f, 0.0f, 0.0f, p.pitch_lim, PID_MODE_DERIVATIV_NONE);
|
||||
pid_init(&offtrack_controller, p.xtrack_p, 0.0f, 0.0f, 0.0f , 60.0f * M_DEG_TO_RAD, PID_MODE_DERIVATIV_NONE); //TODO: remove hardcoded value
|
||||
|
||||
/* error and performance monitoring */
|
||||
perf_counter_t fw_interval_perf = perf_alloc(PC_INTERVAL, "fixedwing_pos_control_interval");
|
||||
perf_counter_t fw_err_perf = perf_alloc(PC_COUNT, "fixedwing_pos_control_err");
|
||||
|
||||
while (!thread_should_exit) {
|
||||
/* wait for a sensor update, check for exit condition every 500 ms */
|
||||
int ret = poll(fds, 2, 500);
|
||||
|
||||
if (ret < 0) {
|
||||
/* poll error, count it in perf */
|
||||
perf_count(fw_err_perf);
|
||||
|
||||
} else if (ret == 0) {
|
||||
/* no return value, ignore */
|
||||
} else {
|
||||
|
||||
/* only update parameters if they changed */
|
||||
if (fds[0].revents & POLLIN) {
|
||||
/* read from param to clear updated flag */
|
||||
struct parameter_update_s update;
|
||||
orb_copy(ORB_ID(parameter_update), param_sub, &update);
|
||||
|
||||
/* update parameters from storage */
|
||||
parameters_update(&h, &p);
|
||||
pid_set_parameters(&heading_controller, p.heading_p, 0, 0, 0, 10000.0f); //arbitrary high limit
|
||||
pid_set_parameters(&heading_rate_controller, p.headingr_p, p.headingr_i, 0, 0, p.roll_lim);
|
||||
pid_set_parameters(&altitude_controller, p.altitude_p, 0, 0, 0, p.pitch_lim);
|
||||
pid_set_parameters(&offtrack_controller, p.xtrack_p, 0, 0, 0, 60.0f * M_DEG_TO_RAD); //TODO: remove hardcoded value
|
||||
}
|
||||
|
||||
/* only run controller if attitude changed */
|
||||
if (fds[1].revents & POLLIN) {
|
||||
|
||||
|
||||
static uint64_t last_run = 0;
|
||||
const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
|
||||
last_run = hrt_absolute_time();
|
||||
|
||||
/* check if there is a new position or setpoint */
|
||||
bool pos_updated;
|
||||
orb_check(global_pos_sub, &pos_updated);
|
||||
bool global_sp_updated;
|
||||
orb_check(global_setpoint_sub, &global_sp_updated);
|
||||
|
||||
/* load local copies */
|
||||
orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
|
||||
|
||||
if (pos_updated) {
|
||||
orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos);
|
||||
}
|
||||
|
||||
if (global_sp_updated) {
|
||||
orb_copy(ORB_ID(vehicle_global_position_setpoint), global_setpoint_sub, &global_setpoint);
|
||||
start_pos = global_pos; //for now using the current position as the startpoint (= approx. last waypoint because the setpoint switch occurs at the waypoint)
|
||||
global_sp_updated_set_once = true;
|
||||
psi_track = get_bearing_to_next_waypoint((double)global_pos.lat / (double)1e7d, (double)global_pos.lon / (double)1e7d,
|
||||
(double)global_setpoint.lat / (double)1e7d, (double)global_setpoint.lon / (double)1e7d);
|
||||
|
||||
printf("next wp direction: %0.4f\n", (double)psi_track);
|
||||
}
|
||||
|
||||
/* Simple Horizontal Control */
|
||||
if (global_sp_updated_set_once) {
|
||||
// if (counter % 100 == 0)
|
||||
// printf("lat_sp %d, ln_sp %d, lat: %d, lon: %d\n", global_setpoint.lat, global_setpoint.lon, global_pos.lat, global_pos.lon);
|
||||
|
||||
/* calculate crosstrack error */
|
||||
// Only the case of a straight line track following handled so far
|
||||
int distance_res = get_distance_to_line(&xtrack_err, (double)global_pos.lat / (double)1e7d, (double)global_pos.lon / (double)1e7d,
|
||||
(double)start_pos.lat / (double)1e7d, (double)start_pos.lon / (double)1e7d,
|
||||
(double)global_setpoint.lat / (double)1e7d, (double)global_setpoint.lon / (double)1e7d);
|
||||
|
||||
// XXX what is xtrack_err.past_end?
|
||||
if (distance_res == OK /*&& !xtrack_err.past_end*/) {
|
||||
|
||||
float delta_psi_c = pid_calculate(&offtrack_controller, 0, xtrack_err.distance, 0.0f, 0.0f); //p.xtrack_p * xtrack_err.distance
|
||||
|
||||
float psi_c = psi_track + delta_psi_c;
|
||||
float psi_e = psi_c - att.yaw;
|
||||
|
||||
/* wrap difference back onto -pi..pi range */
|
||||
psi_e = _wrap_pi(psi_e);
|
||||
|
||||
if (verbose) {
|
||||
printf("xtrack_err.distance %.4f ", (double)xtrack_err.distance);
|
||||
printf("delta_psi_c %.4f ", (double)delta_psi_c);
|
||||
printf("psi_c %.4f ", (double)psi_c);
|
||||
printf("att.yaw %.4f ", (double)att.yaw);
|
||||
printf("psi_e %.4f ", (double)psi_e);
|
||||
}
|
||||
|
||||
/* calculate roll setpoint, do this artificially around zero */
|
||||
float delta_psi_rate_c = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f);
|
||||
float psi_rate_track = 0; //=V_gr/r_track , this will be needed for implementation of arc following
|
||||
float psi_rate_c = delta_psi_rate_c + psi_rate_track;
|
||||
|
||||
/* limit turn rate */
|
||||
if (psi_rate_c > p.headingr_lim) {
|
||||
psi_rate_c = p.headingr_lim;
|
||||
|
||||
} else if (psi_rate_c < -p.headingr_lim) {
|
||||
psi_rate_c = -p.headingr_lim;
|
||||
}
|
||||
|
||||
float psi_rate_e = psi_rate_c - att.yawspeed;
|
||||
|
||||
// XXX sanity check: Assume 10 m/s stall speed and no stall condition
|
||||
float ground_speed = sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy);
|
||||
|
||||
if (ground_speed < 10.0f) {
|
||||
ground_speed = 10.0f;
|
||||
}
|
||||
|
||||
float psi_rate_e_scaled = psi_rate_e * ground_speed / 9.81f; //* V_gr / g
|
||||
|
||||
attitude_setpoint.roll_body = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT);
|
||||
|
||||
if (verbose) {
|
||||
printf("psi_rate_c %.4f ", (double)psi_rate_c);
|
||||
printf("psi_rate_e_scaled %.4f ", (double)psi_rate_e_scaled);
|
||||
printf("rollbody %.4f\n", (double)attitude_setpoint.roll_body);
|
||||
}
|
||||
|
||||
if (verbose && counter % 100 == 0)
|
||||
printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n", xtrack_err.distance, delta_psi_c);
|
||||
|
||||
} else {
|
||||
if (verbose && counter % 100 == 0)
|
||||
printf("distance_res: %d, past_end %d\n", distance_res, xtrack_err.past_end);
|
||||
}
|
||||
|
||||
/* Very simple Altitude Control */
|
||||
if (pos_updated) {
|
||||
|
||||
//TODO: take care of relative vs. ab. altitude
|
||||
attitude_setpoint.pitch_body = pid_calculate(&altitude_controller, global_setpoint.altitude, global_pos.alt, 0.0f, 0.0f);
|
||||
|
||||
}
|
||||
|
||||
// XXX need speed control
|
||||
attitude_setpoint.thrust = 0.7f;
|
||||
|
||||
/* publish the attitude setpoint */
|
||||
orb_publish(ORB_ID(vehicle_attitude_setpoint), attitude_setpoint_pub, &attitude_setpoint);
|
||||
|
||||
/* measure in what intervals the controller runs */
|
||||
perf_count(fw_interval_perf);
|
||||
|
||||
counter++;
|
||||
|
||||
} else {
|
||||
// XXX no setpoint, decent default needed (loiter?)
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
printf("[fixedwing_pos_control] exiting.\n");
|
||||
thread_running = false;
|
||||
|
||||
|
||||
close(attitude_setpoint_pub);
|
||||
|
||||
fflush(stdout);
|
||||
exit(0);
|
||||
|
||||
return 0;
|
||||
|
||||
}
|
||||
|
||||
/* Startup Functions */
|
||||
|
||||
static void
|
||||
usage(const char *reason)
|
||||
{
|
||||
if (reason)
|
||||
fprintf(stderr, "%s\n", reason);
|
||||
|
||||
fprintf(stderr, "usage: fixedwing_pos_control {start|stop|status}\n\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
/**
|
||||
* The deamon app only briefly exists to start
|
||||
* the background job. The stack size assigned in the
|
||||
* Makefile does only apply to this management task.
|
||||
*
|
||||
* The actual stack size should be set in the call
|
||||
* to task_create().
|
||||
*/
|
||||
int fixedwing_pos_control_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 1)
|
||||
usage("missing command");
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
if (thread_running) {
|
||||
printf("fixedwing_pos_control already running\n");
|
||||
/* this is not an error */
|
||||
exit(0);
|
||||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("fixedwing_pos_control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 20,
|
||||
2048,
|
||||
fixedwing_pos_control_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
thread_running = true;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "stop")) {
|
||||
thread_should_exit = true;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
if (thread_running) {
|
||||
printf("\tfixedwing_pos_control is running\n");
|
||||
|
||||
} else {
|
||||
printf("\tfixedwing_pos_control not started\n");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
usage("unrecognized command");
|
||||
exit(1);
|
||||
}
|
||||
@@ -0,0 +1,40 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Fixedwing PositionControl application
|
||||
#
|
||||
|
||||
MODULE_COMMAND = fixedwing_pos_control
|
||||
|
||||
SRCS = fixedwing_pos_control_main.c
|
||||
Executable
+42
@@ -0,0 +1,42 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Makefile to build the multirotor attitude controller
|
||||
#
|
||||
|
||||
MODULE_COMMAND = multirotor_att_control
|
||||
|
||||
SRCS = multirotor_att_control_main.c \
|
||||
multirotor_attitude_control.c \
|
||||
multirotor_rate_control.c
|
||||
@@ -0,0 +1,485 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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
|
||||
* 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 multirotor_att_control_main.c
|
||||
*
|
||||
* Implementation of multirotor attitude control main loop.
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <stdbool.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
#include <getopt.h>
|
||||
#include <time.h>
|
||||
#include <math.h>
|
||||
#include <poll.h>
|
||||
#include <sys/prctl.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <drivers/drv_gyro.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <uORB/topics/offboard_control_setpoint.h>
|
||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
#include "multirotor_attitude_control.h"
|
||||
#include "multirotor_rate_control.h"
|
||||
|
||||
PARAM_DEFINE_FLOAT(MC_RCLOSS_THR, 0.0f); // This defines the throttle when the RC signal is lost.
|
||||
|
||||
__EXPORT int multirotor_att_control_main(int argc, char *argv[]);
|
||||
|
||||
static bool thread_should_exit;
|
||||
static int mc_task;
|
||||
static bool motor_test_mode = false;
|
||||
|
||||
static orb_advert_t actuator_pub;
|
||||
|
||||
static struct vehicle_status_s state;
|
||||
|
||||
static int
|
||||
mc_thread_main(int argc, char *argv[])
|
||||
{
|
||||
/* declare and safely initialize all structs */
|
||||
memset(&state, 0, sizeof(state));
|
||||
struct vehicle_attitude_s att;
|
||||
memset(&att, 0, sizeof(att));
|
||||
struct vehicle_attitude_setpoint_s att_sp;
|
||||
memset(&att_sp, 0, sizeof(att_sp));
|
||||
struct manual_control_setpoint_s manual;
|
||||
memset(&manual, 0, sizeof(manual));
|
||||
struct sensor_combined_s raw;
|
||||
memset(&raw, 0, sizeof(raw));
|
||||
struct offboard_control_setpoint_s offboard_sp;
|
||||
memset(&offboard_sp, 0, sizeof(offboard_sp));
|
||||
struct vehicle_rates_setpoint_s rates_sp;
|
||||
memset(&rates_sp, 0, sizeof(rates_sp));
|
||||
|
||||
struct actuator_controls_s actuators;
|
||||
memset(&actuators, 0, sizeof(actuators));
|
||||
|
||||
/* subscribe to attitude, motor setpoints and system state */
|
||||
int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
||||
int param_sub = orb_subscribe(ORB_ID(parameter_update));
|
||||
int att_setpoint_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
|
||||
int setpoint_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
|
||||
int state_sub = orb_subscribe(ORB_ID(vehicle_status));
|
||||
int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
|
||||
int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
|
||||
|
||||
/*
|
||||
* Do not rate-limit the loop to prevent aliasing
|
||||
* if rate-limiting would be desired later, the line below would
|
||||
* enable it.
|
||||
*
|
||||
* rate-limit the attitude subscription to 200Hz to pace our loop
|
||||
* orb_set_interval(att_sub, 5);
|
||||
*/
|
||||
struct pollfd fds[2] = {
|
||||
{ .fd = att_sub, .events = POLLIN },
|
||||
{ .fd = param_sub, .events = POLLIN }
|
||||
};
|
||||
|
||||
/* publish actuator controls */
|
||||
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) {
|
||||
actuators.control[i] = 0.0f;
|
||||
}
|
||||
|
||||
actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators);
|
||||
orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
|
||||
orb_advert_t rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
|
||||
int rates_sp_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint));
|
||||
|
||||
/* register the perf counter */
|
||||
perf_counter_t mc_loop_perf = perf_alloc(PC_ELAPSED, "multirotor_att_control_runtime");
|
||||
perf_counter_t mc_interval_perf = perf_alloc(PC_INTERVAL, "multirotor_att_control_interval");
|
||||
perf_counter_t mc_err_perf = perf_alloc(PC_COUNT, "multirotor_att_control_err");
|
||||
|
||||
/* welcome user */
|
||||
printf("[multirotor_att_control] starting\n");
|
||||
|
||||
/* store last control mode to detect mode switches */
|
||||
bool flag_control_manual_enabled = false;
|
||||
bool flag_control_attitude_enabled = false;
|
||||
bool flag_system_armed = false;
|
||||
|
||||
/* store if yaw position or yaw speed has been changed */
|
||||
bool control_yaw_position = true;
|
||||
|
||||
/* store if we stopped a yaw movement */
|
||||
bool first_time_after_yaw_speed_control = true;
|
||||
|
||||
/* prepare the handle for the failsafe throttle */
|
||||
param_t failsafe_throttle_handle = param_find("MC_RCLOSS_THR");
|
||||
float failsafe_throttle = 0.0f;
|
||||
|
||||
|
||||
while (!thread_should_exit) {
|
||||
|
||||
/* wait for a sensor update, check for exit condition every 500 ms */
|
||||
int ret = poll(fds, 2, 500);
|
||||
|
||||
if (ret < 0) {
|
||||
/* poll error, count it in perf */
|
||||
perf_count(mc_err_perf);
|
||||
|
||||
} else if (ret == 0) {
|
||||
/* no return value, ignore */
|
||||
} else {
|
||||
|
||||
/* only update parameters if they changed */
|
||||
if (fds[1].revents & POLLIN) {
|
||||
/* read from param to clear updated flag */
|
||||
struct parameter_update_s update;
|
||||
orb_copy(ORB_ID(parameter_update), param_sub, &update);
|
||||
|
||||
/* update parameters */
|
||||
// XXX no params here yet
|
||||
}
|
||||
|
||||
/* only run controller if attitude changed */
|
||||
if (fds[0].revents & POLLIN) {
|
||||
|
||||
perf_begin(mc_loop_perf);
|
||||
|
||||
/* get a local copy of system state */
|
||||
bool updated;
|
||||
orb_check(state_sub, &updated);
|
||||
|
||||
if (updated) {
|
||||
orb_copy(ORB_ID(vehicle_status), state_sub, &state);
|
||||
}
|
||||
|
||||
/* get a local copy of manual setpoint */
|
||||
orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual);
|
||||
/* get a local copy of attitude */
|
||||
orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
|
||||
/* get a local copy of attitude setpoint */
|
||||
orb_copy(ORB_ID(vehicle_attitude_setpoint), att_setpoint_sub, &att_sp);
|
||||
/* get a local copy of rates setpoint */
|
||||
orb_check(setpoint_sub, &updated);
|
||||
|
||||
if (updated) {
|
||||
orb_copy(ORB_ID(offboard_control_setpoint), setpoint_sub, &offboard_sp);
|
||||
}
|
||||
|
||||
/* get a local copy of the current sensor values */
|
||||
orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw);
|
||||
|
||||
|
||||
/** STEP 1: Define which input is the dominating control input */
|
||||
if (state.flag_control_offboard_enabled) {
|
||||
/* offboard inputs */
|
||||
if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES) {
|
||||
rates_sp.roll = offboard_sp.p1;
|
||||
rates_sp.pitch = offboard_sp.p2;
|
||||
rates_sp.yaw = offboard_sp.p3;
|
||||
rates_sp.thrust = offboard_sp.p4;
|
||||
// printf("thrust_rate=%8.4f\n",offboard_sp.p4);
|
||||
rates_sp.timestamp = hrt_absolute_time();
|
||||
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
|
||||
|
||||
} else if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) {
|
||||
att_sp.roll_body = offboard_sp.p1;
|
||||
att_sp.pitch_body = offboard_sp.p2;
|
||||
att_sp.yaw_body = offboard_sp.p3;
|
||||
att_sp.thrust = offboard_sp.p4;
|
||||
// printf("thrust_att=%8.4f\n",offboard_sp.p4);
|
||||
att_sp.timestamp = hrt_absolute_time();
|
||||
/* STEP 2: publish the result to the vehicle actuators */
|
||||
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
|
||||
}
|
||||
|
||||
|
||||
} else if (state.flag_control_manual_enabled) {
|
||||
|
||||
if (state.flag_control_attitude_enabled) {
|
||||
|
||||
/* initialize to current yaw if switching to manual or att control */
|
||||
if (state.flag_control_attitude_enabled != flag_control_attitude_enabled ||
|
||||
state.flag_control_manual_enabled != flag_control_manual_enabled ||
|
||||
state.flag_system_armed != flag_system_armed) {
|
||||
att_sp.yaw_body = att.yaw;
|
||||
}
|
||||
|
||||
static bool rc_loss_first_time = true;
|
||||
|
||||
/* if the RC signal is lost, try to stay level and go slowly back down to ground */
|
||||
if (state.rc_signal_lost) {
|
||||
/* the failsafe throttle is stored as a parameter, as it depends on the copter and the payload */
|
||||
param_get(failsafe_throttle_handle, &failsafe_throttle);
|
||||
att_sp.roll_body = 0.0f;
|
||||
att_sp.pitch_body = 0.0f;
|
||||
|
||||
/*
|
||||
* Only go to failsafe throttle if last known throttle was
|
||||
* high enough to create some lift to make hovering state likely.
|
||||
*
|
||||
* This is to prevent that someone landing, but not disarming his
|
||||
* multicopter (throttle = 0) does not make it jump up in the air
|
||||
* if shutting down his remote.
|
||||
*/
|
||||
if (isfinite(manual.throttle) && manual.throttle > 0.2f) {
|
||||
att_sp.thrust = failsafe_throttle;
|
||||
|
||||
} else {
|
||||
att_sp.thrust = 0.0f;
|
||||
}
|
||||
|
||||
/* keep current yaw, do not attempt to go to north orientation,
|
||||
* since if the pilot regains RC control, he will be lost regarding
|
||||
* the current orientation.
|
||||
*/
|
||||
if (rc_loss_first_time)
|
||||
att_sp.yaw_body = att.yaw;
|
||||
|
||||
rc_loss_first_time = false;
|
||||
|
||||
} else {
|
||||
rc_loss_first_time = true;
|
||||
|
||||
att_sp.roll_body = manual.roll;
|
||||
att_sp.pitch_body = manual.pitch;
|
||||
|
||||
/* set attitude if arming */
|
||||
if (!flag_control_attitude_enabled && state.flag_system_armed) {
|
||||
att_sp.yaw_body = att.yaw;
|
||||
}
|
||||
|
||||
/* act if stabilization is active or if the (nonsense) direct pass through mode is set */
|
||||
if (state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS ||
|
||||
state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
|
||||
|
||||
if (state.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_RATE) {
|
||||
rates_sp.yaw = manual.yaw;
|
||||
control_yaw_position = false;
|
||||
|
||||
} else {
|
||||
/*
|
||||
* This mode SHOULD be the default mode, which is:
|
||||
* VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS
|
||||
*
|
||||
* However, we fall back to this setting for all other (nonsense)
|
||||
* settings as well.
|
||||
*/
|
||||
|
||||
/* only move setpoint if manual input is != 0 */
|
||||
if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.3f) {
|
||||
rates_sp.yaw = manual.yaw;
|
||||
control_yaw_position = false;
|
||||
first_time_after_yaw_speed_control = true;
|
||||
|
||||
} else {
|
||||
if (first_time_after_yaw_speed_control) {
|
||||
att_sp.yaw_body = att.yaw;
|
||||
first_time_after_yaw_speed_control = false;
|
||||
}
|
||||
|
||||
control_yaw_position = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
att_sp.thrust = manual.throttle;
|
||||
att_sp.timestamp = hrt_absolute_time();
|
||||
}
|
||||
|
||||
/* STEP 2: publish the controller output */
|
||||
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
|
||||
|
||||
if (motor_test_mode) {
|
||||
printf("testmode");
|
||||
att_sp.roll_body = 0.0f;
|
||||
att_sp.pitch_body = 0.0f;
|
||||
att_sp.yaw_body = 0.0f;
|
||||
att_sp.thrust = 0.1f;
|
||||
att_sp.timestamp = hrt_absolute_time();
|
||||
/* STEP 2: publish the result to the vehicle actuators */
|
||||
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
|
||||
}
|
||||
|
||||
} else {
|
||||
/* manual rate inputs, from RC control or joystick */
|
||||
if (state.flag_control_rates_enabled &&
|
||||
state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_RATES) {
|
||||
rates_sp.roll = manual.roll;
|
||||
|
||||
rates_sp.pitch = manual.pitch;
|
||||
rates_sp.yaw = manual.yaw;
|
||||
rates_sp.thrust = manual.throttle;
|
||||
rates_sp.timestamp = hrt_absolute_time();
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/** STEP 3: Identify the controller setup to run and set up the inputs correctly */
|
||||
if (state.flag_control_attitude_enabled) {
|
||||
multirotor_control_attitude(&att_sp, &att, &rates_sp, control_yaw_position);
|
||||
|
||||
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
|
||||
}
|
||||
|
||||
/* measure in what intervals the controller runs */
|
||||
perf_count(mc_interval_perf);
|
||||
|
||||
float gyro[3];
|
||||
|
||||
/* get current rate setpoint */
|
||||
bool rates_sp_valid = false;
|
||||
orb_check(rates_sp_sub, &rates_sp_valid);
|
||||
|
||||
if (rates_sp_valid) {
|
||||
orb_copy(ORB_ID(vehicle_rates_setpoint), rates_sp_sub, &rates_sp);
|
||||
}
|
||||
|
||||
/* apply controller */
|
||||
gyro[0] = att.rollspeed;
|
||||
gyro[1] = att.pitchspeed;
|
||||
gyro[2] = att.yawspeed;
|
||||
|
||||
multirotor_control_rates(&rates_sp, gyro, &actuators);
|
||||
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
|
||||
|
||||
/* update state */
|
||||
flag_control_attitude_enabled = state.flag_control_attitude_enabled;
|
||||
flag_control_manual_enabled = state.flag_control_manual_enabled;
|
||||
flag_system_armed = state.flag_system_armed;
|
||||
|
||||
perf_end(mc_loop_perf);
|
||||
} /* end of poll call for attitude updates */
|
||||
} /* end of poll return value check */
|
||||
}
|
||||
|
||||
printf("[multirotor att control] stopping, disarming motors.\n");
|
||||
|
||||
/* kill all outputs */
|
||||
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++)
|
||||
actuators.control[i] = 0.0f;
|
||||
|
||||
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
|
||||
|
||||
|
||||
close(att_sub);
|
||||
close(state_sub);
|
||||
close(manual_sub);
|
||||
close(actuator_pub);
|
||||
close(att_sp_pub);
|
||||
|
||||
perf_print_counter(mc_loop_perf);
|
||||
perf_free(mc_loop_perf);
|
||||
|
||||
fflush(stdout);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
static void
|
||||
usage(const char *reason)
|
||||
{
|
||||
if (reason)
|
||||
fprintf(stderr, "%s\n", reason);
|
||||
|
||||
fprintf(stderr, "usage: multirotor_att_control [-m <mode>] [-t] {start|status|stop}\n");
|
||||
fprintf(stderr, " <mode> is 'rates' or 'attitude'\n");
|
||||
fprintf(stderr, " -t enables motor test mode with 10%% thrust\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
int multirotor_att_control_main(int argc, char *argv[])
|
||||
{
|
||||
int ch;
|
||||
unsigned int optioncount = 0;
|
||||
|
||||
while ((ch = getopt(argc, argv, "tm:")) != EOF) {
|
||||
switch (ch) {
|
||||
case 't':
|
||||
motor_test_mode = true;
|
||||
optioncount += 1;
|
||||
break;
|
||||
|
||||
case ':':
|
||||
usage("missing parameter");
|
||||
break;
|
||||
|
||||
default:
|
||||
fprintf(stderr, "option: -%c\n", ch);
|
||||
usage("unrecognized option");
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
argc -= optioncount;
|
||||
//argv += optioncount;
|
||||
|
||||
if (argc < 1)
|
||||
usage("missing command");
|
||||
|
||||
if (!strcmp(argv[1 + optioncount], "start")) {
|
||||
|
||||
thread_should_exit = false;
|
||||
mc_task = task_spawn("multirotor_att_control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 15,
|
||||
2048,
|
||||
mc_thread_main,
|
||||
NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1 + optioncount], "stop")) {
|
||||
thread_should_exit = true;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
usage("unrecognized command");
|
||||
exit(1);
|
||||
}
|
||||
@@ -0,0 +1,249 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
* @author Laurens Mackay <mackayl@student.ethz.ch>
|
||||
* @author Tobias Naegeli <naegelit@student.ethz.ch>
|
||||
* @author Martin Rutschmann <rutmarti@student.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
|
||||
* 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 multirotor_attitude_control.c
|
||||
* Implementation of attitude controller
|
||||
*/
|
||||
|
||||
#include "multirotor_attitude_control.h"
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <float.h>
|
||||
#include <math.h>
|
||||
#include <systemlib/pid/pid.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
PARAM_DEFINE_FLOAT(MC_YAWPOS_P, 0.3f);
|
||||
PARAM_DEFINE_FLOAT(MC_YAWPOS_I, 0.15f);
|
||||
PARAM_DEFINE_FLOAT(MC_YAWPOS_D, 0.0f);
|
||||
//PARAM_DEFINE_FLOAT(MC_YAWPOS_AWU, 1.0f);
|
||||
//PARAM_DEFINE_FLOAT(MC_YAWPOS_LIM, 3.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(MC_ATT_P, 0.2f);
|
||||
PARAM_DEFINE_FLOAT(MC_ATT_I, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(MC_ATT_D, 0.05f);
|
||||
//PARAM_DEFINE_FLOAT(MC_ATT_AWU, 0.05f);
|
||||
//PARAM_DEFINE_FLOAT(MC_ATT_LIM, 0.4f);
|
||||
|
||||
//PARAM_DEFINE_FLOAT(MC_ATT_XOFF, 0.0f);
|
||||
//PARAM_DEFINE_FLOAT(MC_ATT_YOFF, 0.0f);
|
||||
|
||||
struct mc_att_control_params {
|
||||
float yaw_p;
|
||||
float yaw_i;
|
||||
float yaw_d;
|
||||
//float yaw_awu;
|
||||
//float yaw_lim;
|
||||
|
||||
float att_p;
|
||||
float att_i;
|
||||
float att_d;
|
||||
//float att_awu;
|
||||
//float att_lim;
|
||||
|
||||
//float att_xoff;
|
||||
//float att_yoff;
|
||||
};
|
||||
|
||||
struct mc_att_control_param_handles {
|
||||
param_t yaw_p;
|
||||
param_t yaw_i;
|
||||
param_t yaw_d;
|
||||
//param_t yaw_awu;
|
||||
//param_t yaw_lim;
|
||||
|
||||
param_t att_p;
|
||||
param_t att_i;
|
||||
param_t att_d;
|
||||
//param_t att_awu;
|
||||
//param_t att_lim;
|
||||
|
||||
//param_t att_xoff;
|
||||
//param_t att_yoff;
|
||||
};
|
||||
|
||||
/**
|
||||
* Initialize all parameter handles and values
|
||||
*
|
||||
*/
|
||||
static int parameters_init(struct mc_att_control_param_handles *h);
|
||||
|
||||
/**
|
||||
* Update all parameters
|
||||
*
|
||||
*/
|
||||
static int parameters_update(const struct mc_att_control_param_handles *h, struct mc_att_control_params *p);
|
||||
|
||||
|
||||
static int parameters_init(struct mc_att_control_param_handles *h)
|
||||
{
|
||||
/* PID parameters */
|
||||
h->yaw_p = param_find("MC_YAWPOS_P");
|
||||
h->yaw_i = param_find("MC_YAWPOS_I");
|
||||
h->yaw_d = param_find("MC_YAWPOS_D");
|
||||
//h->yaw_awu = param_find("MC_YAWPOS_AWU");
|
||||
//h->yaw_lim = param_find("MC_YAWPOS_LIM");
|
||||
|
||||
h->att_p = param_find("MC_ATT_P");
|
||||
h->att_i = param_find("MC_ATT_I");
|
||||
h->att_d = param_find("MC_ATT_D");
|
||||
//h->att_awu = param_find("MC_ATT_AWU");
|
||||
//h->att_lim = param_find("MC_ATT_LIM");
|
||||
|
||||
//h->att_xoff = param_find("MC_ATT_XOFF");
|
||||
//h->att_yoff = param_find("MC_ATT_YOFF");
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
static int parameters_update(const struct mc_att_control_param_handles *h, struct mc_att_control_params *p)
|
||||
{
|
||||
param_get(h->yaw_p, &(p->yaw_p));
|
||||
param_get(h->yaw_i, &(p->yaw_i));
|
||||
param_get(h->yaw_d, &(p->yaw_d));
|
||||
//param_get(h->yaw_awu, &(p->yaw_awu));
|
||||
//param_get(h->yaw_lim, &(p->yaw_lim));
|
||||
|
||||
param_get(h->att_p, &(p->att_p));
|
||||
param_get(h->att_i, &(p->att_i));
|
||||
param_get(h->att_d, &(p->att_d));
|
||||
//param_get(h->att_awu, &(p->att_awu));
|
||||
//param_get(h->att_lim, &(p->att_lim));
|
||||
|
||||
//param_get(h->att_xoff, &(p->att_xoff));
|
||||
//param_get(h->att_yoff, &(p->att_yoff));
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
|
||||
const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position)
|
||||
{
|
||||
static uint64_t last_run = 0;
|
||||
static uint64_t last_input = 0;
|
||||
float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
|
||||
float dT_input = (hrt_absolute_time() - last_input) / 1000000.0f;
|
||||
last_run = hrt_absolute_time();
|
||||
|
||||
if (last_input != att_sp->timestamp) {
|
||||
last_input = att_sp->timestamp;
|
||||
}
|
||||
|
||||
static int sensor_delay;
|
||||
sensor_delay = hrt_absolute_time() - att->timestamp;
|
||||
|
||||
static int motor_skip_counter = 0;
|
||||
|
||||
static PID_t pitch_controller;
|
||||
static PID_t roll_controller;
|
||||
|
||||
static struct mc_att_control_params p;
|
||||
static struct mc_att_control_param_handles h;
|
||||
|
||||
static bool initialized = false;
|
||||
|
||||
static float yaw_error;
|
||||
|
||||
/* initialize the pid controllers when the function is called for the first time */
|
||||
if (initialized == false) {
|
||||
parameters_init(&h);
|
||||
parameters_update(&h, &p);
|
||||
|
||||
pid_init(&pitch_controller, p.att_p, p.att_i, p.att_d, 1000.0f,
|
||||
1000.0f, PID_MODE_DERIVATIV_SET);
|
||||
pid_init(&roll_controller, p.att_p, p.att_i, p.att_d, 1000.0f,
|
||||
1000.0f, PID_MODE_DERIVATIV_SET);
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
/* load new parameters with lower rate */
|
||||
if (motor_skip_counter % 500 == 0) {
|
||||
/* update parameters from storage */
|
||||
parameters_update(&h, &p);
|
||||
|
||||
/* apply parameters */
|
||||
pid_set_parameters(&pitch_controller, p.att_p, p.att_i, p.att_d, 1000.0f, 1000.0f);
|
||||
pid_set_parameters(&roll_controller, p.att_p, p.att_i, p.att_d, 1000.0f, 1000.0f);
|
||||
}
|
||||
|
||||
/* reset integral if on ground */
|
||||
if (att_sp->thrust < 0.1f) {
|
||||
pid_reset_integral(&pitch_controller);
|
||||
pid_reset_integral(&roll_controller);
|
||||
}
|
||||
|
||||
|
||||
/* calculate current control outputs */
|
||||
|
||||
/* control pitch (forward) output */
|
||||
rates_sp->pitch = pid_calculate(&pitch_controller, att_sp->pitch_body ,
|
||||
att->pitch, att->pitchspeed, deltaT);
|
||||
|
||||
/* control roll (left/right) output */
|
||||
rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body ,
|
||||
att->roll, att->rollspeed, deltaT);
|
||||
|
||||
if (control_yaw_position) {
|
||||
/* control yaw rate */
|
||||
|
||||
/* positive error: rotate to right, negative error, rotate to left (NED frame) */
|
||||
// yaw_error = _wrap_pi(att_sp->yaw_body - att->yaw);
|
||||
|
||||
yaw_error = att_sp->yaw_body - att->yaw;
|
||||
|
||||
if (yaw_error > M_PI_F) {
|
||||
yaw_error -= M_TWOPI_F;
|
||||
|
||||
} else if (yaw_error < -M_PI_F) {
|
||||
yaw_error += M_TWOPI_F;
|
||||
}
|
||||
|
||||
rates_sp->yaw = p.yaw_p * (yaw_error) - (p.yaw_d * att->yawspeed);
|
||||
}
|
||||
|
||||
rates_sp->thrust = att_sp->thrust;
|
||||
|
||||
motor_skip_counter++;
|
||||
}
|
||||
@@ -0,0 +1,57 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
* @author Laurens Mackay <mackayl@student.ethz.ch>
|
||||
* @author Tobias Naegeli <naegelit@student.ethz.ch>
|
||||
* @author Martin Rutschmann <rutmarti@student.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
|
||||
* 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 multirotor_attitude_control.h
|
||||
* Attitude control for multi rotors.
|
||||
*/
|
||||
|
||||
#ifndef MULTIROTOR_ATTITUDE_CONTROL_H_
|
||||
#define MULTIROTOR_ATTITUDE_CONTROL_H_
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
|
||||
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
|
||||
const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position);
|
||||
|
||||
#endif /* MULTIROTOR_ATTITUDE_CONTROL_H_ */
|
||||
@@ -0,0 +1,230 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Tobias Naegeli <naegelit@student.ethz.ch>
|
||||
* 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 multirotor_rate_control.c
|
||||
*
|
||||
* Implementation of rate controller
|
||||
*
|
||||
* @author Tobias Naegeli <naegelit@student.ethz.ch>
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#include "multirotor_rate_control.h"
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <float.h>
|
||||
#include <math.h>
|
||||
#include <systemlib/pid/pid.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.0f); /* same on Flamewheel */
|
||||
PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.0f);
|
||||
//PARAM_DEFINE_FLOAT(MC_YAWRATE_AWU, 0.0f);
|
||||
//PARAM_DEFINE_FLOAT(MC_YAWRATE_LIM, 1.0f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(MC_ATTRATE_P, 0.0f); /* 0.15 F405 Flamewheel */
|
||||
PARAM_DEFINE_FLOAT(MC_ATTRATE_D, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(MC_ATTRATE_I, 0.0f);
|
||||
//PARAM_DEFINE_FLOAT(MC_ATTRATE_AWU, 0.05f);
|
||||
//PARAM_DEFINE_FLOAT(MC_ATTRATE_LIM, 1.0f); /**< roughly < 500 deg/s limit */
|
||||
|
||||
struct mc_rate_control_params {
|
||||
|
||||
float yawrate_p;
|
||||
float yawrate_d;
|
||||
float yawrate_i;
|
||||
//float yawrate_awu;
|
||||
//float yawrate_lim;
|
||||
|
||||
float attrate_p;
|
||||
float attrate_d;
|
||||
float attrate_i;
|
||||
//float attrate_awu;
|
||||
//float attrate_lim;
|
||||
|
||||
float rate_lim;
|
||||
};
|
||||
|
||||
struct mc_rate_control_param_handles {
|
||||
|
||||
param_t yawrate_p;
|
||||
param_t yawrate_i;
|
||||
param_t yawrate_d;
|
||||
//param_t yawrate_awu;
|
||||
//param_t yawrate_lim;
|
||||
|
||||
param_t attrate_p;
|
||||
param_t attrate_i;
|
||||
param_t attrate_d;
|
||||
//param_t attrate_awu;
|
||||
//param_t attrate_lim;
|
||||
};
|
||||
|
||||
/**
|
||||
* Initialize all parameter handles and values
|
||||
*
|
||||
*/
|
||||
static int parameters_init(struct mc_rate_control_param_handles *h);
|
||||
|
||||
/**
|
||||
* Update all parameters
|
||||
*
|
||||
*/
|
||||
static int parameters_update(const struct mc_rate_control_param_handles *h, struct mc_rate_control_params *p);
|
||||
|
||||
|
||||
static int parameters_init(struct mc_rate_control_param_handles *h)
|
||||
{
|
||||
/* PID parameters */
|
||||
h->yawrate_p = param_find("MC_YAWRATE_P");
|
||||
h->yawrate_i = param_find("MC_YAWRATE_I");
|
||||
h->yawrate_d = param_find("MC_YAWRATE_D");
|
||||
//h->yawrate_awu = param_find("MC_YAWRATE_AWU");
|
||||
//h->yawrate_lim = param_find("MC_YAWRATE_LIM");
|
||||
|
||||
h->attrate_p = param_find("MC_ATTRATE_P");
|
||||
h->attrate_i = param_find("MC_ATTRATE_I");
|
||||
h->attrate_d = param_find("MC_ATTRATE_D");
|
||||
//h->attrate_awu = param_find("MC_ATTRATE_AWU");
|
||||
//h->attrate_lim = param_find("MC_ATTRATE_LIM");
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
static int parameters_update(const struct mc_rate_control_param_handles *h, struct mc_rate_control_params *p)
|
||||
{
|
||||
param_get(h->yawrate_p, &(p->yawrate_p));
|
||||
param_get(h->yawrate_i, &(p->yawrate_i));
|
||||
param_get(h->yawrate_d, &(p->yawrate_d));
|
||||
//param_get(h->yawrate_awu, &(p->yawrate_awu));
|
||||
//param_get(h->yawrate_lim, &(p->yawrate_lim));
|
||||
|
||||
param_get(h->attrate_p, &(p->attrate_p));
|
||||
param_get(h->attrate_i, &(p->attrate_i));
|
||||
param_get(h->attrate_d, &(p->attrate_d));
|
||||
//param_get(h->attrate_awu, &(p->attrate_awu));
|
||||
//param_get(h->attrate_lim, &(p->attrate_lim));
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
|
||||
const float rates[], struct actuator_controls_s *actuators)
|
||||
{
|
||||
static float roll_control_last = 0;
|
||||
static float pitch_control_last = 0;
|
||||
static uint64_t last_run = 0;
|
||||
const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
|
||||
static uint64_t last_input = 0;
|
||||
|
||||
float dT_input = (hrt_absolute_time() - last_input) / 1000000.0f;
|
||||
|
||||
if (last_input != rate_sp->timestamp) {
|
||||
last_input = rate_sp->timestamp;
|
||||
}
|
||||
|
||||
last_run = hrt_absolute_time();
|
||||
|
||||
static int motor_skip_counter = 0;
|
||||
|
||||
static struct mc_rate_control_params p;
|
||||
static struct mc_rate_control_param_handles h;
|
||||
|
||||
static bool initialized = false;
|
||||
|
||||
/* initialize the pid controllers when the function is called for the first time */
|
||||
if (initialized == false) {
|
||||
parameters_init(&h);
|
||||
parameters_update(&h, &p);
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
/* load new parameters with lower rate */
|
||||
if (motor_skip_counter % 2500 == 0) {
|
||||
/* update parameters from storage */
|
||||
parameters_update(&h, &p);
|
||||
// warnx("rate ctrl: p.yawrate_p: %8.4f, loop: %d Hz, input: %d Hz",
|
||||
// (double)p.yawrate_p, (int)(1.0f/deltaT), (int)(1.0f/dT_input));
|
||||
}
|
||||
|
||||
/* calculate current control outputs */
|
||||
|
||||
/* control pitch (forward) output */
|
||||
float pitch_control = p.attrate_p * (rate_sp->pitch - rates[1]) - (p.attrate_d * pitch_control_last);
|
||||
|
||||
/* increase resilience to faulty control inputs */
|
||||
if (isfinite(pitch_control)) {
|
||||
pitch_control_last = pitch_control;
|
||||
|
||||
} else {
|
||||
pitch_control = 0.0f;
|
||||
warnx("rej. NaN ctrl pitch");
|
||||
}
|
||||
|
||||
/* control roll (left/right) output */
|
||||
float roll_control = p.attrate_p * (rate_sp->roll - rates[0]) - (p.attrate_d * roll_control_last);
|
||||
|
||||
/* increase resilience to faulty control inputs */
|
||||
if (isfinite(roll_control)) {
|
||||
roll_control_last = roll_control;
|
||||
|
||||
} else {
|
||||
roll_control = 0.0f;
|
||||
warnx("rej. NaN ctrl roll");
|
||||
}
|
||||
|
||||
/* control yaw rate */
|
||||
float yaw_rate_control = p.yawrate_p * (rate_sp->yaw - rates[2]);
|
||||
|
||||
/* increase resilience to faulty control inputs */
|
||||
if (!isfinite(yaw_rate_control)) {
|
||||
yaw_rate_control = 0.0f;
|
||||
warnx("rej. NaN ctrl yaw");
|
||||
}
|
||||
|
||||
actuators->control[0] = roll_control;
|
||||
actuators->control[1] = pitch_control;
|
||||
actuators->control[2] = yaw_rate_control;
|
||||
actuators->control[3] = rate_sp->thrust;
|
||||
|
||||
motor_skip_counter++;
|
||||
}
|
||||
@@ -0,0 +1,56 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
* @author Laurens Mackay <mackayl@student.ethz.ch>
|
||||
* @author Tobias Naegeli <naegelit@student.ethz.ch>
|
||||
* @author Martin Rutschmann <rutmarti@student.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
|
||||
* 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 multirotor_attitude_control.h
|
||||
* Attitude control for multi rotors.
|
||||
*/
|
||||
|
||||
#ifndef MULTIROTOR_RATE_CONTROL_H_
|
||||
#define MULTIROTOR_RATE_CONTROL_H_
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
|
||||
void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
|
||||
const float rates[], struct actuator_controls_s *actuators);
|
||||
|
||||
#endif /* MULTIROTOR_RATE_CONTROL_H_ */
|
||||
@@ -0,0 +1,41 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Build multirotor position control
|
||||
#
|
||||
|
||||
MODULE_COMMAND = multirotor_pos_control
|
||||
|
||||
SRCS = multirotor_pos_control.c \
|
||||
multirotor_pos_control_params.c
|
||||
@@ -0,0 +1,238 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-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
|
||||
* 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 multirotor_pos_control.c
|
||||
*
|
||||
* Skeleton for multirotor position controller
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <stdbool.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
#include <termios.h>
|
||||
#include <time.h>
|
||||
#include <sys/prctl.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/vehicle_local_position_setpoint.h>
|
||||
#include <uORB/topics/vehicle_vicon_position.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
#include "multirotor_pos_control_params.h"
|
||||
|
||||
|
||||
static bool thread_should_exit = false; /**< Deamon exit flag */
|
||||
static bool thread_running = false; /**< Deamon status flag */
|
||||
static int deamon_task; /**< Handle of deamon task / thread */
|
||||
|
||||
__EXPORT int multirotor_pos_control_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Mainloop of position controller.
|
||||
*/
|
||||
static int multirotor_pos_control_thread_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Print the correct usage.
|
||||
*/
|
||||
static void usage(const char *reason);
|
||||
|
||||
static void
|
||||
usage(const char *reason)
|
||||
{
|
||||
if (reason)
|
||||
fprintf(stderr, "%s\n", reason);
|
||||
fprintf(stderr, "usage: deamon {start|stop|status} [-p <additional params>]\n\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
/**
|
||||
* The deamon app only briefly exists to start
|
||||
* the background job. The stack size assigned in the
|
||||
* Makefile does only apply to this management task.
|
||||
*
|
||||
* The actual stack size should be set in the call
|
||||
* to task_spawn().
|
||||
*/
|
||||
int multirotor_pos_control_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 1)
|
||||
usage("missing command");
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
if (thread_running) {
|
||||
printf("multirotor pos control already running\n");
|
||||
/* this is not an error */
|
||||
exit(0);
|
||||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("multirotor pos control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 60,
|
||||
4096,
|
||||
multirotor_pos_control_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "stop")) {
|
||||
thread_should_exit = true;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
if (thread_running) {
|
||||
printf("\tmultirotor pos control app is running\n");
|
||||
} else {
|
||||
printf("\tmultirotor pos control app not started\n");
|
||||
}
|
||||
exit(0);
|
||||
}
|
||||
|
||||
usage("unrecognized command");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
static int
|
||||
multirotor_pos_control_thread_main(int argc, char *argv[])
|
||||
{
|
||||
/* welcome user */
|
||||
printf("[multirotor pos control] Control started, taking over position control\n");
|
||||
|
||||
/* structures */
|
||||
struct vehicle_status_s state;
|
||||
struct vehicle_attitude_s att;
|
||||
//struct vehicle_global_position_setpoint_s global_pos_sp;
|
||||
struct vehicle_local_position_setpoint_s local_pos_sp;
|
||||
struct vehicle_vicon_position_s local_pos;
|
||||
struct manual_control_setpoint_s manual;
|
||||
struct vehicle_attitude_setpoint_s att_sp;
|
||||
|
||||
/* subscribe to attitude, motor setpoints and system state */
|
||||
int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
||||
int state_sub = orb_subscribe(ORB_ID(vehicle_status));
|
||||
int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
|
||||
int local_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position));
|
||||
//int global_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
|
||||
int local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
|
||||
|
||||
/* publish attitude setpoint */
|
||||
orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
|
||||
|
||||
thread_running = true;
|
||||
|
||||
int loopcounter = 0;
|
||||
|
||||
struct multirotor_position_control_params p;
|
||||
struct multirotor_position_control_param_handles h;
|
||||
parameters_init(&h);
|
||||
parameters_update(&h, &p);
|
||||
|
||||
|
||||
while (1) {
|
||||
/* get a local copy of the vehicle state */
|
||||
orb_copy(ORB_ID(vehicle_status), state_sub, &state);
|
||||
/* get a local copy of manual setpoint */
|
||||
orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual);
|
||||
/* get a local copy of attitude */
|
||||
orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
|
||||
/* get a local copy of local position */
|
||||
orb_copy(ORB_ID(vehicle_vicon_position), local_pos_sub, &local_pos);
|
||||
/* get a local copy of local position setpoint */
|
||||
orb_copy(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_sub, &local_pos_sp);
|
||||
|
||||
if (loopcounter == 500) {
|
||||
parameters_update(&h, &p);
|
||||
loopcounter = 0;
|
||||
}
|
||||
|
||||
// if (state.state_machine == SYSTEM_STATE_AUTO) {
|
||||
|
||||
// XXX IMPLEMENT POSITION CONTROL HERE
|
||||
|
||||
float dT = 1.0f / 50.0f;
|
||||
|
||||
float x_setpoint = 0.0f;
|
||||
|
||||
// XXX enable switching between Vicon and local position estimate
|
||||
/* local pos is the Vicon position */
|
||||
|
||||
// XXX just an example, lacks rotation around world-body transformation
|
||||
att_sp.pitch_body = (local_pos.x - x_setpoint) * p.p;
|
||||
att_sp.roll_body = 0.0f;
|
||||
att_sp.yaw_body = 0.0f;
|
||||
att_sp.thrust = 0.3f;
|
||||
att_sp.timestamp = hrt_absolute_time();
|
||||
|
||||
/* publish new attitude setpoint */
|
||||
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
|
||||
// } else if (state.state_machine == SYSTEM_STATE_STABILIZED) {
|
||||
/* set setpoint to current position */
|
||||
// XXX select pos reset channel on remote
|
||||
/* reset setpoint to current position (position hold) */
|
||||
// if (1 == 2) {
|
||||
// local_pos_sp.x = local_pos.x;
|
||||
// local_pos_sp.y = local_pos.y;
|
||||
// local_pos_sp.z = local_pos.z;
|
||||
// local_pos_sp.yaw = att.yaw;
|
||||
// }
|
||||
// }
|
||||
|
||||
/* run at approximately 50 Hz */
|
||||
usleep(20000);
|
||||
loopcounter++;
|
||||
|
||||
}
|
||||
|
||||
printf("[multirotor pos control] ending now...\n");
|
||||
|
||||
thread_running = false;
|
||||
|
||||
fflush(stdout);
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -0,0 +1,62 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Tobias Naegeli <naegelit@student.ethz.ch>
|
||||
* 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 multirotor_position_control_params.c
|
||||
*
|
||||
* Parameters for EKF filter
|
||||
*/
|
||||
|
||||
#include "multirotor_pos_control_params.h"
|
||||
|
||||
/* Extended Kalman Filter covariances */
|
||||
|
||||
/* controller parameters */
|
||||
PARAM_DEFINE_FLOAT(MC_POS_P, 0.2f);
|
||||
|
||||
int parameters_init(struct multirotor_position_control_param_handles *h)
|
||||
{
|
||||
/* PID parameters */
|
||||
h->p = param_find("MC_POS_P");
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int parameters_update(const struct multirotor_position_control_param_handles *h, struct multirotor_position_control_params *p)
|
||||
{
|
||||
param_get(h->p, &(p->p));
|
||||
|
||||
return OK;
|
||||
}
|
||||
@@ -0,0 +1,66 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Tobias Naegeli <naegelit@student.ethz.ch>
|
||||
* 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 multirotor_position_control_params.h
|
||||
*
|
||||
* Parameters for position controller
|
||||
*/
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
struct multirotor_position_control_params {
|
||||
float p;
|
||||
float i;
|
||||
float d;
|
||||
};
|
||||
|
||||
struct multirotor_position_control_param_handles {
|
||||
param_t p;
|
||||
param_t i;
|
||||
param_t d;
|
||||
};
|
||||
|
||||
/**
|
||||
* Initialize all parameter handles and values
|
||||
*
|
||||
*/
|
||||
int parameters_init(struct multirotor_position_control_param_handles *h);
|
||||
|
||||
/**
|
||||
* Update all parameters
|
||||
*
|
||||
*/
|
||||
int parameters_update(const struct multirotor_position_control_param_handles *h, struct multirotor_position_control_params *p);
|
||||
@@ -0,0 +1,235 @@
|
||||
// /****************************************************************************
|
||||
// *
|
||||
// * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
|
||||
// * Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
// * @author Laurens Mackay <mackayl@student.ethz.ch>
|
||||
// * @author Tobias Naegeli <naegelit@student.ethz.ch>
|
||||
// * @author Martin Rutschmann <rutmarti@student.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 multirotor_position_control.c
|
||||
// * Implementation of the position control for a multirotor VTOL
|
||||
// */
|
||||
|
||||
// #include <stdio.h>
|
||||
// #include <stdlib.h>
|
||||
// #include <stdio.h>
|
||||
// #include <stdint.h>
|
||||
// #include <math.h>
|
||||
// #include <stdbool.h>
|
||||
// #include <float.h>
|
||||
// #include <systemlib/pid/pid.h>
|
||||
|
||||
// #include "multirotor_position_control.h"
|
||||
|
||||
// void control_multirotor_position(const struct vehicle_state_s *vstatus, const struct vehicle_manual_control_s *manual,
|
||||
// const struct vehicle_attitude_s *att, const struct vehicle_local_position_s *local_pos,
|
||||
// const struct vehicle_local_position_setpoint_s *local_pos_sp, struct vehicle_attitude_setpoint_s *att_sp)
|
||||
// {
|
||||
// static PID_t distance_controller;
|
||||
|
||||
// static int read_ret;
|
||||
// static global_data_position_t position_estimated;
|
||||
|
||||
// static uint16_t counter;
|
||||
|
||||
// static bool initialized;
|
||||
// static uint16_t pm_counter;
|
||||
|
||||
// static float lat_next;
|
||||
// static float lon_next;
|
||||
|
||||
// static float pitch_current;
|
||||
|
||||
// static float thrust_total;
|
||||
|
||||
|
||||
// if (initialized == false) {
|
||||
|
||||
// pid_init(&distance_controller,
|
||||
// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_P],
|
||||
// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_I],
|
||||
// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_D],
|
||||
// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_AWU],
|
||||
// PID_MODE_DERIVATIV_CALC, 150);//150
|
||||
|
||||
// // pid_pos_lim = global_data_parameter_storage->pm.param_values[PARAM_PID_POS_LIM];
|
||||
// // pid_pos_z_lim = global_data_parameter_storage->pm.param_values[PARAM_PID_POS_Z_LIM];
|
||||
|
||||
// thrust_total = 0.0f;
|
||||
|
||||
// /* Position initialization */
|
||||
// /* Wait for new position estimate */
|
||||
// do {
|
||||
// read_ret = read_lock_position(&position_estimated);
|
||||
// } while (read_ret != 0);
|
||||
|
||||
// lat_next = position_estimated.lat;
|
||||
// lon_next = position_estimated.lon;
|
||||
|
||||
// /* attitude initialization */
|
||||
// global_data_lock(&global_data_attitude->access_conf);
|
||||
// pitch_current = global_data_attitude->pitch;
|
||||
// global_data_unlock(&global_data_attitude->access_conf);
|
||||
|
||||
// initialized = true;
|
||||
// }
|
||||
|
||||
// /* load new parameters with 10Hz */
|
||||
// if (counter % 50 == 0) {
|
||||
// if (global_data_trylock(&global_data_parameter_storage->access_conf) == 0) {
|
||||
// /* check whether new parameters are available */
|
||||
// if (global_data_parameter_storage->counter > pm_counter) {
|
||||
// pid_set_parameters(&distance_controller,
|
||||
// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_P],
|
||||
// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_I],
|
||||
// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_D],
|
||||
// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_AWU]);
|
||||
|
||||
// //
|
||||
// // pid_pos_lim = global_data_parameter_storage->pm.param_values[PARAM_PID_POS_LIM];
|
||||
// // pid_pos_z_lim = global_data_parameter_storage->pm.param_values[PARAM_PID_POS_Z_LIM];
|
||||
|
||||
// pm_counter = global_data_parameter_storage->counter;
|
||||
// printf("Position controller changed pid parameters\n");
|
||||
// }
|
||||
// }
|
||||
|
||||
// global_data_unlock(&global_data_parameter_storage->access_conf);
|
||||
// }
|
||||
|
||||
|
||||
// /* Wait for new position estimate */
|
||||
// do {
|
||||
// read_ret = read_lock_position(&position_estimated);
|
||||
// } while (read_ret != 0);
|
||||
|
||||
// /* Get next waypoint */ //TODO: add local copy
|
||||
|
||||
// if (0 == global_data_trylock(&global_data_position_setpoint->access_conf)) {
|
||||
// lat_next = global_data_position_setpoint->x;
|
||||
// lon_next = global_data_position_setpoint->y;
|
||||
// global_data_unlock(&global_data_position_setpoint->access_conf);
|
||||
// }
|
||||
|
||||
// /* Get distance to waypoint */
|
||||
// float distance_to_waypoint = get_distance_to_next_waypoint(position_estimated.lat , position_estimated.lon, lat_next, lon_next);
|
||||
// // if(counter % 5 == 0)
|
||||
// // printf("distance_to_waypoint: %.4f\n", distance_to_waypoint);
|
||||
|
||||
// /* Get bearing to waypoint (direction on earth surface to next waypoint) */
|
||||
// float bearing = get_bearing_to_next_waypoint(position_estimated.lat, position_estimated.lon, lat_next, lon_next);
|
||||
|
||||
// if (counter % 5 == 0)
|
||||
// printf("bearing: %.4f\n", bearing);
|
||||
|
||||
// /* Calculate speed in direction of bearing (needed for controller) */
|
||||
// float speed_norm = sqrtf(position_estimated.vx * position_estimated.vx + position_estimated.vy * position_estimated.vy);
|
||||
// // if(counter % 5 == 0)
|
||||
// // printf("speed_norm: %.4f\n", speed_norm);
|
||||
// float speed_to_waypoint = 0; //(position_estimated.vx * cosf(bearing) + position_estimated.vy * sinf(bearing))/speed_norm; //FIXME, TODO: re-enable this once we have a full estimate of the speed, then we can do a PID for the distance controller
|
||||
|
||||
// /* Control Thrust in bearing direction */
|
||||
// float horizontal_thrust = -pid_calculate(&distance_controller, 0, distance_to_waypoint, speed_to_waypoint,
|
||||
// CONTROL_PID_POSITION_INTERVAL); //TODO: maybe this "-" sign is an error somewhere else
|
||||
|
||||
// // if(counter % 5 == 0)
|
||||
// // printf("horizontal thrust: %.4f\n", horizontal_thrust);
|
||||
|
||||
// /* Get total thrust (from remote for now) */
|
||||
// if (0 == global_data_trylock(&global_data_rc_channels->access_conf)) {
|
||||
// thrust_total = (float)global_data_rc_channels->chan[THROTTLE].scale; //TODO: how should we use the RC_CHANNELS_FUNCTION enum?
|
||||
// global_data_unlock(&global_data_rc_channels->access_conf);
|
||||
// }
|
||||
|
||||
// const float max_gas = 500.0f;
|
||||
// thrust_total *= max_gas / 20000.0f; //TODO: check this
|
||||
// thrust_total += max_gas / 2.0f;
|
||||
|
||||
|
||||
// if (horizontal_thrust > thrust_total) {
|
||||
// horizontal_thrust = thrust_total;
|
||||
|
||||
// } else if (horizontal_thrust < -thrust_total) {
|
||||
// horizontal_thrust = -thrust_total;
|
||||
// }
|
||||
|
||||
|
||||
|
||||
// //TODO: maybe we want to add a speed controller later...
|
||||
|
||||
// /* Calclulate thrust in east and north direction */
|
||||
// float thrust_north = cosf(bearing) * horizontal_thrust;
|
||||
// float thrust_east = sinf(bearing) * horizontal_thrust;
|
||||
|
||||
// if (counter % 10 == 0) {
|
||||
// printf("thrust north: %.4f\n", thrust_north);
|
||||
// printf("thrust east: %.4f\n", thrust_east);
|
||||
// fflush(stdout);
|
||||
// }
|
||||
|
||||
// /* Get current attitude */
|
||||
// if (0 == global_data_trylock(&global_data_attitude->access_conf)) {
|
||||
// pitch_current = global_data_attitude->pitch;
|
||||
// global_data_unlock(&global_data_attitude->access_conf);
|
||||
// }
|
||||
|
||||
// /* Get desired pitch & roll */
|
||||
// float pitch_desired = 0.0f;
|
||||
// float roll_desired = 0.0f;
|
||||
|
||||
// if (thrust_total != 0) {
|
||||
// float pitch_fraction = -thrust_north / thrust_total;
|
||||
// float roll_fraction = thrust_east / (cosf(pitch_current) * thrust_total);
|
||||
|
||||
// if (roll_fraction < -1) {
|
||||
// roll_fraction = -1;
|
||||
|
||||
// } else if (roll_fraction > 1) {
|
||||
// roll_fraction = 1;
|
||||
// }
|
||||
|
||||
// // if(counter % 5 == 0)
|
||||
// // {
|
||||
// // printf("pitch_fraction: %.4f, roll_fraction: %.4f\n",pitch_fraction, roll_fraction);
|
||||
// // fflush(stdout);
|
||||
// // }
|
||||
|
||||
// pitch_desired = asinf(pitch_fraction);
|
||||
// roll_desired = asinf(roll_fraction);
|
||||
// }
|
||||
|
||||
// att_sp.roll = roll_desired;
|
||||
// att_sp.pitch = pitch_desired;
|
||||
|
||||
// counter++;
|
||||
// }
|
||||
@@ -0,0 +1,50 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* @author Laurens Mackay <mackayl@student.ethz.ch>
|
||||
* @author Tobias Naegeli <naegelit@student.ethz.ch>
|
||||
* @author Martin Rutschmann <rutmarti@student.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 multirotor_position_control.h
|
||||
* Definition of the position control for a multirotor VTOL
|
||||
*/
|
||||
|
||||
// #ifndef POSITION_CONTROL_H_
|
||||
// #define POSITION_CONTROL_H_
|
||||
|
||||
// void control_multirotor_position(const struct vehicle_state_s *vstatus, const struct vehicle_manual_control_s *manual,
|
||||
// const struct vehicle_attitude_s *att, const struct vehicle_local_position_s *local_pos,
|
||||
// const struct vehicle_local_position_setpoint_s *local_pos_sp, struct vehicle_attitude_setpoint_s *att_sp);
|
||||
|
||||
// #endif /* POSITION_CONTROL_H_ */
|
||||
@@ -0,0 +1,44 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Makefile to build the position estimator
|
||||
#
|
||||
|
||||
MODULE_COMMAND = position_estimator
|
||||
|
||||
# XXX this should be converted to a deamon, its a pretty bad example app
|
||||
MODULE_PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||
MODULE_STACKSIZE = 4096
|
||||
|
||||
SRCS = position_estimator_main.c
|
||||
@@ -0,0 +1,423 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Tobias Naegeli <naegelit@student.ethz.ch>
|
||||
* Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* Julian Oes <joes@student.ethz.ch>
|
||||
* 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 position_estimator_main.c
|
||||
* Model-identification based position estimator for multirotors
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <float.h>
|
||||
#include <nuttx/sched.h>
|
||||
#include <sys/prctl.h>
|
||||
#include <termios.h>
|
||||
#include <errno.h>
|
||||
#include <limits.h>
|
||||
#include <math.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_status.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_local_position.h>
|
||||
#include <poll.h>
|
||||
|
||||
#define N_STATES 6
|
||||
#define ERROR_COVARIANCE_INIT 3
|
||||
#define R_EARTH 6371000.0
|
||||
|
||||
#define PROJECTION_INITIALIZE_COUNTER_LIMIT 5000
|
||||
#define REPROJECTION_COUNTER_LIMIT 125
|
||||
|
||||
__EXPORT int position_estimator_main(int argc, char *argv[]);
|
||||
|
||||
static uint16_t position_estimator_counter_position_information;
|
||||
|
||||
/* values for map projection */
|
||||
static double phi_1;
|
||||
static double sin_phi_1;
|
||||
static double cos_phi_1;
|
||||
static double lambda_0;
|
||||
static double scale;
|
||||
|
||||
/**
|
||||
* Initializes the map transformation.
|
||||
*
|
||||
* Initializes the transformation between the geographic coordinate system and the azimuthal equidistant plane
|
||||
* @param lat in degrees (47.1234567°, not 471234567°)
|
||||
* @param lon in degrees (8.1234567°, not 81234567°)
|
||||
*/
|
||||
static void map_projection_init(double lat_0, double lon_0) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
|
||||
{
|
||||
/* notation and formulas according to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
|
||||
phi_1 = lat_0 / 180.0 * M_PI;
|
||||
lambda_0 = lon_0 / 180.0 * M_PI;
|
||||
|
||||
sin_phi_1 = sin(phi_1);
|
||||
cos_phi_1 = cos(phi_1);
|
||||
|
||||
/* calculate local scale by using the relation of true distance and the distance on plane */ //TODO: this is a quick solution, there are probably easier ways to determine the scale
|
||||
|
||||
/* 1) calculate true distance d on sphere to a point: http://www.movable-type.co.uk/scripts/latlong.html */
|
||||
const double r_earth = 6371000;
|
||||
|
||||
double lat1 = phi_1;
|
||||
double lon1 = lambda_0;
|
||||
|
||||
double lat2 = phi_1 + 0.5 / 180 * M_PI;
|
||||
double lon2 = lambda_0 + 0.5 / 180 * M_PI;
|
||||
double sin_lat_2 = sin(lat2);
|
||||
double cos_lat_2 = cos(lat2);
|
||||
double d = acos(sin(lat1) * sin_lat_2 + cos(lat1) * cos_lat_2 * cos(lon2 - lon1)) * r_earth;
|
||||
|
||||
/* 2) calculate distance rho on plane */
|
||||
double k_bar = 0;
|
||||
double c = acos(sin_phi_1 * sin_lat_2 + cos_phi_1 * cos_lat_2 * cos(lon2 - lambda_0));
|
||||
|
||||
if (0 != c)
|
||||
k_bar = c / sin(c);
|
||||
|
||||
double x2 = k_bar * (cos_lat_2 * sin(lon2 - lambda_0)); //Projection of point 2 on plane
|
||||
double y2 = k_bar * ((cos_phi_1 * sin_lat_2 - sin_phi_1 * cos_lat_2 * cos(lon2 - lambda_0)));
|
||||
double rho = sqrt(pow(x2, 2) + pow(y2, 2));
|
||||
|
||||
scale = d / rho;
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* Transforms a point in the geographic coordinate system to the local azimuthal equidistant plane
|
||||
* @param x north
|
||||
* @param y east
|
||||
* @param lat in degrees (47.1234567°, not 471234567°)
|
||||
* @param lon in degrees (8.1234567°, not 81234567°)
|
||||
*/
|
||||
static void map_projection_project(double lat, double lon, float *x, float *y)
|
||||
{
|
||||
/* notation and formulas accoring to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
|
||||
double phi = lat / 180.0 * M_PI;
|
||||
double lambda = lon / 180.0 * M_PI;
|
||||
|
||||
double sin_phi = sin(phi);
|
||||
double cos_phi = cos(phi);
|
||||
|
||||
double k_bar = 0;
|
||||
/* using small angle approximation (formula in comment is without aproximation) */
|
||||
double c = acos(sin_phi_1 * sin_phi + cos_phi_1 * cos_phi * (1 - pow((lambda - lambda_0), 2) / 2)); //double c = acos( sin_phi_1 * sin_phi + cos_phi_1 * cos_phi * cos(lambda - lambda_0) );
|
||||
|
||||
if (0 != c)
|
||||
k_bar = c / sin(c);
|
||||
|
||||
/* using small angle approximation (formula in comment is without aproximation) */
|
||||
*y = k_bar * (cos_phi * (lambda - lambda_0)) * scale;//*y = k_bar * (cos_phi * sin(lambda - lambda_0)) * scale;
|
||||
*x = k_bar * ((cos_phi_1 * sin_phi - sin_phi_1 * cos_phi * (1 - pow((lambda - lambda_0), 2) / 2))) * scale; // *x = k_bar * ((cos_phi_1 * sin_phi - sin_phi_1 * cos_phi * cos(lambda - lambda_0))) * scale;
|
||||
|
||||
// printf("%phi_1=%.10f, lambda_0 =%.10f\n", phi_1, lambda_0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Transforms a point in the local azimuthal equidistant plane to the geographic coordinate system
|
||||
*
|
||||
* @param x north
|
||||
* @param y east
|
||||
* @param lat in degrees (47.1234567°, not 471234567°)
|
||||
* @param lon in degrees (8.1234567°, not 81234567°)
|
||||
*/
|
||||
static void map_projection_reproject(float x, float y, double *lat, double *lon)
|
||||
{
|
||||
/* notation and formulas accoring to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
|
||||
|
||||
double x_descaled = x / scale;
|
||||
double y_descaled = y / scale;
|
||||
|
||||
double c = sqrt(pow(x_descaled, 2) + pow(y_descaled, 2));
|
||||
double sin_c = sin(c);
|
||||
double cos_c = cos(c);
|
||||
|
||||
double lat_sphere = 0;
|
||||
|
||||
if (c != 0)
|
||||
lat_sphere = asin(cos_c * sin_phi_1 + (x_descaled * sin_c * cos_phi_1) / c);
|
||||
else
|
||||
lat_sphere = asin(cos_c * sin_phi_1);
|
||||
|
||||
// printf("lat_sphere = %.10f\n",lat_sphere);
|
||||
|
||||
double lon_sphere = 0;
|
||||
|
||||
if (phi_1 == M_PI / 2) {
|
||||
//using small angle approximation (formula in comment is without aproximation)
|
||||
lon_sphere = (lambda_0 - y_descaled / x_descaled); //lon_sphere = (lambda_0 + atan2(-y_descaled, x_descaled));
|
||||
|
||||
} else if (phi_1 == -M_PI / 2) {
|
||||
//using small angle approximation (formula in comment is without aproximation)
|
||||
lon_sphere = (lambda_0 + y_descaled / x_descaled); //lon_sphere = (lambda_0 + atan2(y_descaled, x_descaled));
|
||||
|
||||
} else {
|
||||
|
||||
lon_sphere = (lambda_0 + atan2(y_descaled * sin_c , c * cos_phi_1 * cos_c - x_descaled * sin_phi_1 * sin_c));
|
||||
//using small angle approximation
|
||||
// double denominator = (c * cos_phi_1 * cos_c - x_descaled * sin_phi_1 * sin_c);
|
||||
// if(denominator != 0)
|
||||
// {
|
||||
// lon_sphere = (lambda_0 + (y_descaled * sin_c) / denominator);
|
||||
// }
|
||||
// else
|
||||
// {
|
||||
// ...
|
||||
// }
|
||||
}
|
||||
|
||||
// printf("lon_sphere = %.10f\n",lon_sphere);
|
||||
|
||||
*lat = lat_sphere * 180.0 / M_PI;
|
||||
*lon = lon_sphere * 180.0 / M_PI;
|
||||
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* main
|
||||
****************************************************************************/
|
||||
|
||||
int position_estimator_main(int argc, char *argv[])
|
||||
{
|
||||
|
||||
/* welcome user */
|
||||
printf("[multirotor position_estimator] started\n");
|
||||
|
||||
/* initialize values */
|
||||
static float u[2] = {0, 0};
|
||||
static float z[3] = {0, 0, 0};
|
||||
static float xapo[N_STATES] = {0, 0, 0, 0, 0, 0};
|
||||
static float Papo[N_STATES * N_STATES] = {ERROR_COVARIANCE_INIT, 0, 0, 0, 0, 0,
|
||||
ERROR_COVARIANCE_INIT, 0, 0, 0, 0, 0,
|
||||
ERROR_COVARIANCE_INIT, 0, 0, 0, 0, 0,
|
||||
ERROR_COVARIANCE_INIT, 0, 0, 0, 0, 0,
|
||||
ERROR_COVARIANCE_INIT, 0, 0, 0, 0, 0,
|
||||
ERROR_COVARIANCE_INIT, 0, 0, 0, 0, 0
|
||||
};
|
||||
|
||||
static float xapo1[N_STATES];
|
||||
static float Papo1[36];
|
||||
|
||||
static float gps_covariance[3] = {0.0f, 0.0f, 0.0f};
|
||||
|
||||
static uint16_t counter = 0;
|
||||
position_estimator_counter_position_information = 0;
|
||||
|
||||
uint8_t predict_only = 1;
|
||||
|
||||
bool gps_valid = false;
|
||||
|
||||
bool new_initialization = true;
|
||||
|
||||
static double lat_current = 0.0d;//[°]] --> 47.0
|
||||
static double lon_current = 0.0d; //[°]] -->8.5
|
||||
float alt_current = 0.0f;
|
||||
|
||||
|
||||
//TODO: handle flight without gps but with estimator
|
||||
|
||||
/* subscribe to vehicle status, attitude, gps */
|
||||
struct vehicle_gps_position_s gps;
|
||||
gps.fix_type = 0;
|
||||
struct vehicle_status_s vstatus;
|
||||
struct vehicle_attitude_s att;
|
||||
|
||||
int vehicle_gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
|
||||
int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
|
||||
|
||||
/* subscribe to attitude at 100 Hz */
|
||||
int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
||||
|
||||
/* wait until gps signal turns valid, only then can we initialize the projection */
|
||||
while (gps.fix_type < 3) {
|
||||
struct pollfd fds[1] = { {.fd = vehicle_gps_sub, .events = POLLIN} };
|
||||
|
||||
/* wait for GPS updates, BUT READ VEHICLE STATUS (!)
|
||||
* this choice is critical, since the vehicle status might not
|
||||
* actually change, if this app is started after GPS lock was
|
||||
* aquired.
|
||||
*/
|
||||
if (poll(fds, 1, 5000)) {
|
||||
/* Wait for the GPS update to propagate (we have some time) */
|
||||
usleep(5000);
|
||||
/* Read wether the vehicle status changed */
|
||||
orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_sub, &gps);
|
||||
gps_valid = (gps.fix_type > 2);
|
||||
}
|
||||
}
|
||||
|
||||
/* get gps value for first initialization */
|
||||
orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_sub, &gps);
|
||||
lat_current = ((double)(gps.lat)) * 1e-7;
|
||||
lon_current = ((double)(gps.lon)) * 1e-7;
|
||||
alt_current = gps.alt * 1e-3;
|
||||
|
||||
/* initialize coordinates */
|
||||
map_projection_init(lat_current, lon_current);
|
||||
|
||||
/* publish global position messages only after first GPS message */
|
||||
struct vehicle_local_position_s local_pos = {
|
||||
.x = 0,
|
||||
.y = 0,
|
||||
.z = 0
|
||||
};
|
||||
orb_advert_t local_pos_pub = orb_advertise(ORB_ID(vehicle_local_position), &local_pos);
|
||||
|
||||
printf("[multirotor position estimator] initialized projection with: lat: %.10f, lon:%.10f\n", lat_current, lon_current);
|
||||
|
||||
while (1) {
|
||||
|
||||
/*This runs at the rate of the sensors, if we have also a new gps update this is used in the position_estimator function */
|
||||
struct pollfd fds[1] = { {.fd = vehicle_attitude_sub, .events = POLLIN} };
|
||||
|
||||
if (poll(fds, 1, 5000) <= 0) {
|
||||
/* error / timeout */
|
||||
} else {
|
||||
|
||||
orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
|
||||
/* got attitude, updating pos as well */
|
||||
orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_sub, &gps);
|
||||
orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &vstatus);
|
||||
|
||||
/*copy attitude */
|
||||
u[0] = att.roll;
|
||||
u[1] = att.pitch;
|
||||
|
||||
/* initialize map projection with the last estimate (not at full rate) */
|
||||
if (gps.fix_type > 2) {
|
||||
/* Project gps lat lon (Geographic coordinate system) to plane*/
|
||||
map_projection_project(((double)(gps.lat)) * 1e-7, ((double)(gps.lon)) * 1e-7, &(z[0]), &(z[1]));
|
||||
|
||||
local_pos.x = z[0];
|
||||
local_pos.y = z[1];
|
||||
/* negative offset from initialization altitude */
|
||||
local_pos.z = alt_current - (gps.alt) * 1e-3;
|
||||
|
||||
|
||||
orb_publish(ORB_ID(vehicle_local_position), local_pos_pub, &local_pos);
|
||||
}
|
||||
|
||||
|
||||
// gps_covariance[0] = gps.eph; //TODO: needs scaling
|
||||
// gps_covariance[1] = gps.eph;
|
||||
// gps_covariance[2] = gps.epv;
|
||||
|
||||
// } else {
|
||||
// /* we can not use the gps signal (it is of low quality) */
|
||||
// predict_only = 1;
|
||||
// }
|
||||
|
||||
// // predict_only = 0; //TODO: only for testing, removeme, XXX
|
||||
// // z[0] = sinf(((float)counter)/180.0f*3.14159265f); //TODO: only for testing, removeme, XXX
|
||||
// // usleep(100000); //TODO: only for testing, removeme, XXX
|
||||
|
||||
|
||||
// /*Get new estimation (this is calculated in the plane) */
|
||||
// //TODO: if new_initialization == true: use 0,0,0, else use xapo
|
||||
// if (true == new_initialization) { //TODO,XXX: uncomment!
|
||||
// xapo[0] = 0; //we have a new plane initialization. the current estimate is in the center of the plane
|
||||
// xapo[2] = 0;
|
||||
// xapo[4] = 0;
|
||||
// position_estimator(u, z, xapo, Papo, gps_covariance, predict_only, xapo1, Papo1);
|
||||
|
||||
// } else {
|
||||
// position_estimator(u, z, xapo, Papo, gps_covariance, predict_only, xapo1, Papo1);
|
||||
// }
|
||||
|
||||
|
||||
|
||||
// /* Copy values from xapo1 to xapo */
|
||||
// int i;
|
||||
|
||||
// for (i = 0; i < N_STATES; i++) {
|
||||
// xapo[i] = xapo1[i];
|
||||
// }
|
||||
|
||||
// if ((counter % REPROJECTION_COUNTER_LIMIT == 0) || (counter % (PROJECTION_INITIALIZE_COUNTER_LIMIT - 1) == 0)) {
|
||||
// /* Reproject from plane to geographic coordinate system */
|
||||
// // map_projection_reproject(xapo1[0], xapo1[2], map_scale, phi_1, lambda_0, &lat_current, &lon_current) //TODO,XXX: uncomment!
|
||||
// map_projection_reproject(z[0], z[1], &lat_current, &lon_current); //do not use estimator for projection testing, removeme
|
||||
// // //DEBUG
|
||||
// // if(counter%500 == 0)
|
||||
// // {
|
||||
// // printf("phi_1: %.10f\n", phi_1);
|
||||
// // printf("lambda_0: %.10f\n", lambda_0);
|
||||
// // printf("lat_estimated: %.10f\n", lat_current);
|
||||
// // printf("lon_estimated: %.10f\n", lon_current);
|
||||
// // printf("z[0]=%.10f, z[1]=%.10f, z[2]=%f\n", z[0], z[1], z[2]);
|
||||
// // fflush(stdout);
|
||||
// //
|
||||
// // }
|
||||
|
||||
// // if(!isnan(lat_current) && !isnan(lon_current))// && !isnan(xapo1[4]) && !isnan(xapo1[1]) && !isnan(xapo1[3]) && !isnan(xapo1[5]))
|
||||
// // {
|
||||
// /* send out */
|
||||
|
||||
// global_pos.lat = lat_current;
|
||||
// global_pos.lon = lon_current;
|
||||
// global_pos.alt = xapo1[4];
|
||||
// global_pos.vx = xapo1[1];
|
||||
// global_pos.vy = xapo1[3];
|
||||
// global_pos.vz = xapo1[5];
|
||||
|
||||
/* publish current estimate */
|
||||
// orb_publish(ORB_ID(vehicle_global_position), global_pos_pub, &global_pos);
|
||||
// }
|
||||
// else
|
||||
// {
|
||||
// printf("[position estimator] ERROR: nan values, lat_current=%.4f, lon_current=%.4f, z[0]=%.4f z[1]=%.4f\n", lat_current, lon_current, z[0], z[1]);
|
||||
// fflush(stdout);
|
||||
// }
|
||||
|
||||
// }
|
||||
|
||||
counter++;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user