aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rwxr-xr-xROMFS/px4fmu_common/init.d/rcS5
-rw-r--r--makefiles/config_px4fmu-v1_backside.mk1
-rw-r--r--makefiles/config_px4fmu-v1_default.mk1
-rw-r--r--makefiles/config_px4fmu-v2_default.mk1
-rw-r--r--src/lib/geo/geo.c22
-rw-r--r--src/lib/geo/geo.h14
-rw-r--r--src/modules/controllib/uorb/blocks.cpp18
-rw-r--r--src/modules/controllib/uorb/blocks.hpp9
-rw-r--r--src/modules/dataman/dataman.c739
-rw-r--r--src/modules/dataman/dataman.h116
-rw-r--r--src/modules/dataman/module.mk42
-rw-r--r--src/modules/fixedwing_backside/fixedwing.cpp10
-rw-r--r--src/modules/fixedwing_backside/fixedwing.hpp2
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp110
-rw-r--r--src/modules/mavlink/missionlib.c84
-rw-r--r--src/modules/mavlink/orb_topics.h2
-rw-r--r--src/modules/mavlink/waypoints.c78
-rw-r--r--src/modules/navigator/module.mk2
-rw-r--r--src/modules/navigator/navigator_main.cpp522
-rw-r--r--src/modules/uORB/objects_common.cpp7
-rw-r--r--src/modules/uORB/topics/fence.h80
-rw-r--r--src/modules/uORB/topics/mission.h12
-rw-r--r--src/modules/uORB/topics/mission_item_triplet.h (renamed from src/modules/uORB/topics/vehicle_global_position_set_triplet.h)25
-rw-r--r--src/systemcmds/tests/module.mk3
-rw-r--r--src/systemcmds/tests/test_dataman.c179
-rw-r--r--src/systemcmds/tests/tests.h1
-rw-r--r--src/systemcmds/tests/tests_main.c1
27 files changed, 1783 insertions, 303 deletions
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index d8b5cb608..5f52969d1 100755
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -111,6 +111,11 @@ then
#
commander start
+ #
+ # Start the Navigator
+ #
+ navigator start
+
if param compare SYS_AUTOSTART 1000
then
sh /etc/init.d/1000_rc_fw_easystar.hil
diff --git a/makefiles/config_px4fmu-v1_backside.mk b/makefiles/config_px4fmu-v1_backside.mk
index e1a42530b..c07f7ab1a 100644
--- a/makefiles/config_px4fmu-v1_backside.mk
+++ b/makefiles/config_px4fmu-v1_backside.mk
@@ -106,6 +106,7 @@ MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
MODULES += modules/controllib
MODULES += modules/uORB
+MODULES += modules/dataman
#
# Libraries
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index 306827086..1e1d0f419 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -105,6 +105,7 @@ MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
MODULES += modules/controllib
MODULES += modules/uORB
+MODULES += modules/dataman
#
# Libraries
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index 761fb8d9d..b9aec79fe 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -102,6 +102,7 @@ MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
MODULES += modules/controllib
MODULES += modules/uORB
+MODULES += modules/dataman
#
# Libraries
diff --git a/src/lib/geo/geo.c b/src/lib/geo/geo.c
index 43105fdba..8aeca5be7 100644
--- a/src/lib/geo/geo.c
+++ b/src/lib/geo/geo.c
@@ -465,4 +465,26 @@ __EXPORT float _wrap_360(float bearing)
return bearing;
}
+__EXPORT bool inside_geofence(const struct vehicle_global_position_s *vehicle, const struct fence_s *fence)
+{
+
+ /* Adaptation of algorithm originally presented as
+ * PNPOLY - Point Inclusion in Polygon Test
+ * W. Randolph Franklin (WRF) */
+
+ unsigned int i, j, vertices = fence->count;
+ bool c = false;
+ double lat = vehicle->lat / 1e7;
+ double lon = vehicle->lon / 1e7;
+
+ // skip vertex 0 (return point)
+ for (i = 0, j = vertices - 1; i < vertices; j = i++)
+ if (((fence->vertices[i].lon) >= lon != (fence->vertices[j].lon >= lon)) &&
+ (lat <= (fence->vertices[j].lat - fence->vertices[i].lat) * (lon - fence->vertices[i].lon) /
+ (fence->vertices[j].lon - fence->vertices[i].lon) + fence->vertices[i].lat))
+ c = !c;
+ return c;
+}
+
+
diff --git a/src/lib/geo/geo.h b/src/lib/geo/geo.h
index 123ff80f1..6bce9309b 100644
--- a/src/lib/geo/geo.h
+++ b/src/lib/geo/geo.h
@@ -47,6 +47,9 @@
#pragma once
+#include "uORB/topics/fence.h"
+#include "uORB/topics/vehicle_global_position.h"
+
__BEGIN_DECLS
#include <stdbool.h>
@@ -126,4 +129,15 @@ __EXPORT float _wrap_360(float bearing);
__EXPORT float _wrap_pi(float bearing);
__EXPORT float _wrap_2pi(float bearing);
+/**
+ * Return whether craft is inside geofence.
+ *
+ * Calculate whether point is inside arbitrary polygon
+ * @param craft pointer craft coordinates
+ * @param fence pointer to array of coordinates, one per vertex. First and last vertex are assumed connected
+ * @return true: craft is inside fence, false:craft is outside fence
+ */
+__EXPORT bool inside_geofence(const struct vehicle_global_position_s *craft, const struct fence_s *fence);
+
+
__END_DECLS
diff --git a/src/modules/controllib/uorb/blocks.cpp b/src/modules/controllib/uorb/blocks.cpp
index 448a42a99..e213ac17f 100644
--- a/src/modules/controllib/uorb/blocks.cpp
+++ b/src/modules/controllib/uorb/blocks.cpp
@@ -54,26 +54,26 @@ BlockWaypointGuidance::~BlockWaypointGuidance() {};
void BlockWaypointGuidance::update(vehicle_global_position_s &pos,
vehicle_attitude_s &att,
- vehicle_global_position_setpoint_s &posCmd,
- vehicle_global_position_setpoint_s &lastPosCmd)
+ mission_item_s &missionCmd,
+ mission_item_s &lastMissionCmd)
{
// heading to waypoint
float psiTrack = get_bearing_to_next_waypoint(
(double)pos.lat / (double)1e7d,
(double)pos.lon / (double)1e7d,
- (double)posCmd.lat / (double)1e7d,
- (double)posCmd.lon / (double)1e7d);
+ missionCmd.lat,
+ missionCmd.lon);
// cross track
struct crosstrack_error_s xtrackError;
get_distance_to_line(&xtrackError,
(double)pos.lat / (double)1e7d,
(double)pos.lon / (double)1e7d,
- (double)lastPosCmd.lat / (double)1e7d,
- (double)lastPosCmd.lon / (double)1e7d,
- (double)posCmd.lat / (double)1e7d,
- (double)posCmd.lon / (double)1e7d);
+ lastMissionCmd.lat,
+ lastMissionCmd.lon,
+ missionCmd.lat,
+ missionCmd.lon);
_psiCmd = _wrap_2pi(psiTrack -
_xtYawLimit.update(_xt2Yaw.update(xtrackError.distance)));
@@ -86,7 +86,7 @@ BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const c
_attCmd(&getSubscriptions(), ORB_ID(vehicle_attitude_setpoint), 20),
_ratesCmd(&getSubscriptions(), ORB_ID(vehicle_rates_setpoint), 20),
_pos(&getSubscriptions() , ORB_ID(vehicle_global_position), 20),
- _posCmd(&getSubscriptions(), ORB_ID(vehicle_global_position_set_triplet), 20),
+ _missionCmd(&getSubscriptions(), ORB_ID(mission_item_triplet), 20),
_manual(&getSubscriptions(), ORB_ID(manual_control_setpoint), 20),
_status(&getSubscriptions(), ORB_ID(vehicle_status), 20),
_param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz
diff --git a/src/modules/controllib/uorb/blocks.hpp b/src/modules/controllib/uorb/blocks.hpp
index 46dc1bec2..335439fb7 100644
--- a/src/modules/controllib/uorb/blocks.hpp
+++ b/src/modules/controllib/uorb/blocks.hpp
@@ -43,7 +43,8 @@
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_global_position_set_triplet.h>
+#include <uORB/topics/vehicle_global_position_setpoint.h>
+#include <uORB/topics/mission_item_triplet.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_controls.h>
@@ -82,8 +83,8 @@ public:
virtual ~BlockWaypointGuidance();
void update(vehicle_global_position_s &pos,
vehicle_attitude_s &att,
- vehicle_global_position_setpoint_s &posCmd,
- vehicle_global_position_setpoint_s &lastPosCmd);
+ mission_item_s &missionCmd,
+ mission_item_s &lastMissionCmd);
float getPsiCmd() { return _psiCmd; }
};
@@ -98,7 +99,7 @@ protected:
UOrbSubscription<vehicle_attitude_setpoint_s> _attCmd;
UOrbSubscription<vehicle_rates_setpoint_s> _ratesCmd;
UOrbSubscription<vehicle_global_position_s> _pos;
- UOrbSubscription<vehicle_global_position_set_triplet_s> _posCmd;
+ UOrbSubscription<mission_item_triplet_s> _missionCmd;
UOrbSubscription<manual_control_setpoint_s> _manual;
UOrbSubscription<vehicle_status_s> _status;
UOrbSubscription<parameter_update_s> _param_update;
diff --git a/src/modules/dataman/dataman.c b/src/modules/dataman/dataman.c
new file mode 100644
index 000000000..05b77da20
--- /dev/null
+++ b/src/modules/dataman/dataman.c
@@ -0,0 +1,739 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier
+ * Jean Cyr
+ *
+ * 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 navigator_main.c
+ * Implementation of the main navigation state machine.
+ *
+ * Handles missions, geo fencing and failsafe navigation behavior.
+ */
+
+#include <nuttx/config.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <math.h>
+#include <poll.h>
+#include <time.h>
+#include <sys/ioctl.h>
+#include <systemlib/systemlib.h>
+#include <systemlib/err.h>
+#include <queue.h>
+
+#include "dataman.h"
+
+/**
+ * data manager app start / stop handling function
+ *
+ * @ingroup apps
+ */
+
+__EXPORT int dataman_main(int argc, char *argv[]);
+__EXPORT ssize_t dm_read(dm_item_t item, unsigned char index, void *buffer, size_t buflen);
+__EXPORT ssize_t dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const void *buffer, size_t buflen);
+__EXPORT int dm_clear(dm_item_t item);
+__EXPORT int dm_restart(dm_reset_reason restart_type);
+
+/* Types of function calls supported by the worker task */
+typedef enum {
+ dm_write_func = 0,
+ dm_read_func,
+ dm_clear_func,
+ dm_restart_func,
+ dm_number_of_funcs
+} dm_function_t;
+
+/* Work task work item */
+typedef struct {
+ sq_entry_t link; /**< list linkage */
+ sem_t wait_sem;
+ dm_function_t func;
+ ssize_t result;
+ union {
+ struct {
+ dm_item_t item;
+ unsigned char index;
+ dm_persitence_t persistence;
+ const void *buf;
+ size_t count;
+ } write_params;
+ struct {
+ dm_item_t item;
+ unsigned char index;
+ void *buf;
+ size_t count;
+ } read_params;
+ struct {
+ dm_item_t item;
+ } clear_params;
+ struct {
+ dm_reset_reason reason;
+ } restart_params;
+ };
+} work_q_item_t;
+
+/* Usage statistics */
+static unsigned g_func_counts[dm_number_of_funcs];
+
+/* table of maximum number of instances for each item type */
+static const unsigned g_per_item_max_index[DM_KEY_NUM_KEYS] = {
+ DM_KEY_SAFE_POINTS_MAX,
+ DM_KEY_FENCE_POINTS_MAX,
+ DM_KEY_WAY_POINTS_MAX,
+};
+
+/* Table of offset for index 0 of each item type */
+static unsigned int g_key_offsets[DM_KEY_NUM_KEYS];
+
+/* The data manager store file handle and file name */
+static int g_fd = -1, g_task_fd = -1;
+static const char *k_data_manager_device_path = "/fs/microsd/dataman";
+
+/* The data manager work queues */
+
+typedef struct {
+ sq_queue_t q;
+ sem_t mutex; /* Mutual exclusion on work queue adds and deletes */
+ unsigned size;
+ unsigned max_size;
+} work_q_t;
+
+static work_q_t g_free_q;
+static work_q_t g_work_q;
+
+sem_t g_work_queued_sema;
+sem_t g_init_sema;
+
+static bool g_task_should_exit; /**< if true, sensor task should exit */
+
+#define DM_SECTOR_HDR_SIZE 4
+static const unsigned k_sector_size = DM_MAX_DATA_SIZE + DM_SECTOR_HDR_SIZE;
+
+static void init_q(work_q_t *q)
+{
+ sq_init(&(q->q));
+ sem_init(&(q->mutex), 1, 1);
+ q->size = q->max_size = 0;
+}
+
+static void destroy_q(work_q_t *q)
+{
+ sem_destroy(&(q->mutex));
+}
+
+static inline void
+lock_queue(work_q_t *q)
+{
+ sem_wait(&(q->mutex));
+}
+
+static inline void
+unlock_queue(work_q_t *q)
+{
+ sem_post(&(q->mutex));
+}
+
+static work_q_item_t *
+create_work_item(void)
+{
+ work_q_item_t *item;
+
+ lock_queue(&g_free_q);
+ if ((item = (work_q_item_t *)sq_remfirst(&(g_free_q.q))))
+ g_free_q.size--;
+ unlock_queue(&g_free_q);
+
+ if (item == NULL)
+ item = (work_q_item_t *)malloc(sizeof(work_q_item_t));
+
+ if (item)
+ sem_init(&item->wait_sem, 1, 0); /* Caller will wait on this... initially locked */
+
+ return item;
+}
+
+/* Work queue management functions */
+static void
+enqueue_work_item(work_q_item_t *item)
+{
+ /* put the work item on the work queue */
+ lock_queue(&g_work_q);
+ sq_addlast(&item->link, &(g_work_q.q));
+
+ if (++g_work_q.size > g_work_q.max_size)
+ g_work_q.max_size = g_work_q.size;
+
+ unlock_queue(&g_work_q);
+
+ /* tell the work thread that work is available */
+ sem_post(&g_work_queued_sema);
+}
+
+static void
+destroy_work_item(work_q_item_t *item)
+{
+ sem_destroy(&item->wait_sem);
+ lock_queue(&g_free_q);
+ sq_addfirst(&item->link, &(g_free_q.q));
+
+ if (++g_free_q.size > g_free_q.max_size)
+ g_free_q.max_size = g_free_q.size;
+
+ unlock_queue(&g_free_q);
+}
+
+static work_q_item_t *
+dequeue_work_item(void)
+{
+ work_q_item_t *work;
+ lock_queue(&g_work_q);
+
+ if ((work = (work_q_item_t *)sq_remfirst(&g_work_q.q)))
+ g_work_q.size--;
+
+ unlock_queue(&g_work_q);
+ return work;
+}
+
+/* Calculate the offset in file of specific item */
+static int
+calculate_offset(dm_item_t item, unsigned char index)
+{
+
+ /* Make sure the item type is valid */
+ if (item >= DM_KEY_NUM_KEYS)
+ return -1;
+
+ /* Make sure the index for this item type is valid */
+ if (index >= g_per_item_max_index[item])
+ return -1;
+
+ /* Calculate and return the item index based on type and index */
+ return g_key_offsets[item] + (index * k_sector_size);
+}
+
+/* Each data item is stored as follows
+ *
+ * byte 0: Length of user data item
+ * byte 1: Persistence of this data item
+ * byte DM_SECTOR_HDR_SIZE... : data item value
+ *
+ * The total size must not exceed k_sector_size
+ */
+
+/* write to the data manager file */
+static ssize_t
+_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const void *buf, size_t count)
+{
+ unsigned char buffer[k_sector_size];
+ size_t len;
+ int offset;
+
+ /* Get the offset for this item */
+ offset = calculate_offset(item, index);
+
+ if (offset < 0)
+ return -1;
+
+ /* Make sure caller has not given us more data than we can handle */
+ if (count > DM_MAX_DATA_SIZE)
+ return -1;
+
+ /* Write out the data, prefixed with length and persistence level */
+ buffer[0] = count;
+ buffer[1] = persistence;
+ buffer[2] = 0;
+ buffer[3] = 0;
+ memcpy(buffer + DM_SECTOR_HDR_SIZE, buf, count);
+ count += DM_SECTOR_HDR_SIZE;
+
+ len = -1;
+
+ if (lseek(g_task_fd, offset, SEEK_SET) == offset)
+ if ((len = write(g_task_fd, buffer, count)) == count)
+ fsync(g_task_fd);
+
+ if (len != count)
+ return -1;
+
+ /* All is well... return the number of user data written */
+ return count - DM_SECTOR_HDR_SIZE;
+}
+
+/* Retrieve from the data manager file */
+static ssize_t
+_read(dm_item_t item, unsigned char index, void *buf, size_t count)
+{
+ unsigned char buffer[k_sector_size];
+ int len, offset;
+
+ /* Get the offset for this item */
+ offset = calculate_offset(item, index);
+
+ if (offset < 0)
+ return -1;
+
+ /* Make sure the caller hasn't asked for more data than we can handle */
+ if (count > DM_MAX_DATA_SIZE)
+ return -1;
+
+ /* Read the prefix and data */
+ len = -1;
+ if (lseek(g_task_fd, offset, SEEK_SET) == offset)
+ len = read(g_task_fd, buffer, count + DM_SECTOR_HDR_SIZE);
+
+ /* Check for length issues */
+ if (len < 0)
+ return -1;
+
+ if (len == 0)
+ buffer[0] = 0;
+
+ if (buffer[0] > 0) {
+ if (buffer[0] > count)
+ return -1;
+
+ /* Looks good, copy it to the caller's buffer */
+ memcpy(buf, buffer + DM_SECTOR_HDR_SIZE, buffer[0]);
+ }
+
+ /* Return the number of bytes of caller data read */
+ return buffer[0];
+}
+
+static int
+_clear(dm_item_t item)
+{
+ int i, result = 0;
+
+ int offset = calculate_offset(item, 0);
+
+ if (offset < 0)
+ return -1;
+
+ for (i = 0; (unsigned)i < g_per_item_max_index[item]; i++) {
+ char buf[1];
+
+ if (lseek(g_task_fd, offset, SEEK_SET) != offset) {
+ result = -1;
+ break;
+ }
+
+ if (read(g_task_fd, buf, 1) < 1)
+ break;
+
+ if (buf[0]) {
+ if (lseek(g_task_fd, offset, SEEK_SET) != offset) {
+ result = -1;
+ break;
+ }
+
+ buf[0] = 0;
+
+ if (write(g_task_fd, buf, 1) != 1) {
+ result = -1;
+ break;
+ }
+ }
+
+ offset += k_sector_size;
+ }
+
+ fsync(g_task_fd);
+ return result;
+}
+
+/* Tell the data manager about the type of the last reset */
+static int
+_restart(dm_reset_reason reason)
+{
+ unsigned char buffer[2];
+ int offset, result = 0;
+
+ /* We need to scan the entire file and invalidate and data that should not persist after the last reset */
+
+ /* Loop through all of the data segments and delete those that are not persistent */
+ offset = 0;
+
+ while (1) {
+ size_t len;
+
+ /* Get data segment at current offset */
+ if (lseek(g_task_fd, offset, SEEK_SET) != offset) {
+ result = -1;
+ break;
+ }
+
+ len = read(g_task_fd, buffer, sizeof(buffer));
+
+ if (len == 0)
+ break;
+
+ /* check if segment contains data */
+ if (buffer[0]) {
+ int clear_entry = 0;
+
+ /* Whether data gets deleted depends on reset type and data segment's persistence setting */
+ if (reason == DM_INIT_REASON_POWER_ON) {
+ if (buffer[1] != DM_PERSIST_POWER_ON_RESET) {
+ clear_entry = 1;
+ }
+
+ } else {
+ if ((buffer[1] != DM_PERSIST_POWER_ON_RESET) && (buffer[1] != DM_PERSIST_IN_FLIGHT_RESET)) {
+ clear_entry = 1;
+ }
+ }
+
+ /* Set segment to unused if data does not persist */
+ if (clear_entry) {
+ if (lseek(g_task_fd, offset, SEEK_SET) != offset) {
+ result = -1;
+ break;
+ }
+
+ buffer[0] = 0;
+
+ len = write(g_task_fd, buffer, 1);
+
+ if (len != 1) {
+ result = -1;
+ break;
+ }
+ }
+ }
+
+ offset += k_sector_size;
+ }
+
+ fsync(g_task_fd);
+
+ /* tell the caller how it went */
+ return result;
+}
+
+/* write to the data manager file */
+__EXPORT ssize_t
+dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const void *buf, size_t count)
+{
+ work_q_item_t *work;
+
+ if ((g_fd < 0) || g_task_should_exit)
+ return -1;
+
+ /* Will return with queues locked */
+ if ((work = create_work_item()) == NULL)
+ return -1; /* queues unlocked on failure */
+
+ work->func = dm_write_func;
+ work->write_params.item = item;
+ work->write_params.index = index;
+ work->write_params.persistence = persistence;
+ work->write_params.buf = buf;
+ work->write_params.count = count;
+ enqueue_work_item(work);
+
+ sem_wait(&work->wait_sem);
+ ssize_t result = work->result;
+ destroy_work_item(work);
+ return result;
+}
+
+/* Retrieve from the data manager file */
+__EXPORT ssize_t
+dm_read(dm_item_t item, unsigned char index, void *buf, size_t count)
+{
+ work_q_item_t *work;
+
+ if ((g_fd < 0) || g_task_should_exit)
+ return -1;
+
+ /* Will return with queues locked */
+ if ((work = create_work_item()) == NULL)
+ return -1; /* queues unlocked on failure */
+
+ work->func = dm_read_func;
+ work->read_params.item = item;
+ work->read_params.index = index;
+ work->read_params.buf = buf;
+ work->read_params.count = count;
+ enqueue_work_item(work);
+
+ sem_wait(&work->wait_sem);
+ ssize_t result = work->result;
+ destroy_work_item(work);
+ return result;
+}
+
+__EXPORT int
+dm_clear(dm_item_t item)
+{
+ work_q_item_t *work;
+
+ if ((g_fd < 0) || g_task_should_exit)
+ return -1;
+
+ /* Will return with queues locked */
+ if ((work = create_work_item()) == NULL)
+ return -1; /* queues unlocked on failure */
+
+ work->func = dm_clear_func;
+ work->clear_params.item = item;
+ enqueue_work_item(work);
+
+ sem_wait(&work->wait_sem);
+ int result = work->result;
+ destroy_work_item(work);
+ return result;
+}
+
+/* Tell the data manager about the type of the last reset */
+__EXPORT int
+dm_restart(dm_reset_reason reason)
+{
+ work_q_item_t *work;
+
+ if ((g_fd < 0) || g_task_should_exit)
+ return -1;
+
+ /* Will return with queues locked */
+ if ((work = create_work_item()) == NULL)
+ return -1; /* queues unlocked on failure */
+
+ work->func = dm_restart_func;
+ work->restart_params.reason = reason;
+ enqueue_work_item(work);
+
+ sem_wait(&work->wait_sem);
+ int result = work->result;
+ destroy_work_item(work);
+ return result;
+}
+
+static int
+task_main(int argc, char *argv[])
+{
+ work_q_item_t *work;
+
+ /* inform about start */
+ warnx("Initializing..");
+
+ /* Initialize global variables */
+ g_key_offsets[0] = 0;
+
+ for (unsigned i = 0; i < (DM_KEY_NUM_KEYS - 1); i++)
+ g_key_offsets[i + 1] = g_key_offsets[i] + (g_per_item_max_index[i] * k_sector_size);
+
+ unsigned max_offset = g_key_offsets[DM_KEY_NUM_KEYS - 1] + (g_per_item_max_index[DM_KEY_NUM_KEYS - 1] * k_sector_size);
+
+ for (unsigned i = 0; i < dm_number_of_funcs; i++)
+ g_func_counts[i] = 0;
+
+ g_task_should_exit = false;
+
+ init_q(&g_work_q);
+ init_q(&g_free_q);
+
+ sem_init(&g_work_queued_sema, 1, 0);
+
+ g_task_fd = open(k_data_manager_device_path, O_RDWR | O_CREAT | O_BINARY);
+ if (g_task_fd < 0) {
+ warnx("Could not open data manager file %s", k_data_manager_device_path);
+ return -1;
+ }
+ if (lseek(g_task_fd, max_offset, SEEK_SET) != max_offset) {
+ close(g_task_fd);
+ warnx("Could not seek data manager file %s", k_data_manager_device_path);
+ return -1;
+ }
+ fsync(g_task_fd);
+
+ g_fd = g_task_fd;
+
+ warnx("Initialized, data manager file '%s' size is %d bytes", k_data_manager_device_path, max_offset);
+
+ sem_post(&g_init_sema);
+
+ /* Start the endless loop, waiting for then processing work requests */
+ while (true) {
+
+ /* do we need to exit ??? */
+ if ((g_task_should_exit) && (g_fd >= 0)) {
+ /* Close the file handle to stop further queueing */
+ g_fd = -1;
+ }
+
+ if (!g_task_should_exit) {
+ /* wait for work */
+ sem_wait(&g_work_queued_sema);
+ }
+
+ /* Empty the work queue */
+ while ((work = dequeue_work_item())) {
+
+ switch (work->func) {
+ case dm_write_func:
+ g_func_counts[dm_write_func]++;
+ work->result =
+ _write(work->write_params.item, work->write_params.index, work->write_params.persistence, work->write_params.buf, work->write_params.count);
+ break;
+
+ case dm_read_func:
+ g_func_counts[dm_read_func]++;
+ work->result =
+ _read(work->read_params.item, work->read_params.index, work->read_params.buf, work->read_params.count);
+ break;
+
+ case dm_clear_func:
+ g_func_counts[dm_clear_func]++;
+ work->result = _clear(work->clear_params.item);
+ break;
+
+ case dm_restart_func:
+ g_func_counts[dm_restart_func]++;
+ work->result = _restart(work->restart_params.reason);
+ break;
+
+ default: /* should never happen */
+ work->result = -1;
+ break;
+ }
+
+ /* Inform the caller that work is done */
+ sem_post(&work->wait_sem);
+ }
+
+ /* time to go???? */
+ if ((g_task_should_exit) && (g_fd < 0))
+ break;
+ }
+
+ close(g_task_fd);
+ g_task_fd = -1;
+
+ /* Empty the work queue */
+ for (;;) {
+ if ((work = (work_q_item_t *)sq_remfirst(&(g_free_q.q))) == NULL)
+ break;
+
+ free(work);
+ }
+
+ destroy_q(&g_work_q);
+ destroy_q(&g_free_q);
+ sem_destroy(&g_work_queued_sema);
+
+ return 0;
+}
+
+static int
+start(void)
+{
+ int task;
+
+ sem_init(&g_init_sema, 1, 0);
+
+ /* start the task */
+ if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2048, task_main, NULL)) <= 0) {
+ warn("task start failed");
+ return -1;
+ }
+
+ /* wait for the thread to actuall initialize */
+ sem_wait(&g_init_sema);
+ sem_destroy(&g_init_sema);
+
+ return 0;
+}
+
+static void
+status(void)
+{
+ /* display usage statistics */
+ warnx("Writes %d", g_func_counts[dm_write_func]);
+ warnx("Reads %d", g_func_counts[dm_read_func]);
+ warnx("Clears %d", g_func_counts[dm_clear_func]);
+ warnx("Restarts %d", g_func_counts[dm_restart_func]);
+ warnx("Max Q lengths work %d, free %d", g_work_q.max_size, g_free_q.max_size);
+}
+
+static void
+stop(void)
+{
+ /* Tell the worker task to shut down */
+ g_task_should_exit = true;
+ sem_post(&g_work_queued_sema);
+}
+
+static void
+usage(void)
+{
+ errx(1, "usage: dataman {start|stop|status}");
+}
+
+int
+dataman_main(int argc, char *argv[])
+{
+ if (argc < 2)
+ usage();
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (g_fd >= 0)
+ errx(1, "already running");
+
+ start();
+
+ if (g_fd < 0)
+ errx(1, "start failed");
+
+ return 0;
+ }
+
+ if (g_fd < 0)
+ errx(1, "not running");
+
+ if (!strcmp(argv[1], "stop"))
+ stop();
+ else if (!strcmp(argv[1], "status"))
+ status();
+ else
+ usage();
+
+ return 0;
+}
+
diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h
new file mode 100644
index 000000000..41ddfaf61
--- /dev/null
+++ b/src/modules/dataman/dataman.h
@@ -0,0 +1,116 @@
+/****************************************************************************
+ *
+ * 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 dataman.h
+ *
+ * DATAMANAGER driver.
+ */
+#ifndef _DATAMANAGER_H
+#define _DATAMANAGER_H
+
+#include <uORB/topics/mission.h>
+#include <uORB/topics/fence.h>
+#include <mavlink/waypoints.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+ /* Types of items that the data manager can store */
+ typedef enum {
+ DM_KEY_SAFE_POINTS = 0, /* Safe points coordinates, safe point 0 is home point */
+ DM_KEY_FENCE_POINTS, /* Fence vertex coordinates */
+ DM_KEY_WAY_POINTS, /* Mission way point coordinates */
+ DM_KEY_NUM_KEYS /* Total number of item types defined */
+ } dm_item_t;
+
+ /* The maximum number of instances for each item type */
+ enum {
+ DM_KEY_SAFE_POINTS_MAX = 8,
+ DM_KEY_FENCE_POINTS_MAX = GEOFENCE_MAX_VERTICES,
+ DM_KEY_WAY_POINTS_MAX = MAVLINK_WPM_MAX_WP_COUNT,
+ };
+
+ /* Data persistence levels */
+ typedef enum {
+ DM_PERSIST_POWER_ON_RESET = 0, /* Data survives all resets */
+ DM_PERSIST_IN_FLIGHT_RESET, /* Data survives in-flight resets only */
+ DM_PERSIST_VOLATILE /* Data does not survive resets */
+ } dm_persitence_t;
+
+ /* The reason for the last reset */
+ typedef enum {
+ DM_INIT_REASON_POWER_ON = 0, /* Data survives resets */
+ DM_INIT_REASON_IN_FLIGHT /* Data survives in-flight resets only */
+ } dm_reset_reason;
+
+ /* Maximum size in bytes of a single item instance */
+ #define DM_MAX_DATA_SIZE 126
+
+ /* Retrieve from the data manager store */
+ __EXPORT ssize_t
+ dm_read(
+ dm_item_t item, /* The item type to retrieve */
+ unsigned char index, /* The index of the item */
+ void *buffer, /* Pointer to caller data buffer */
+ size_t buflen /* Length in bytes of data to retrieve */
+ );
+
+ /* write to the data manager store */
+ __EXPORT ssize_t
+ dm_write(
+ dm_item_t item, /* The item type to store */
+ unsigned char index, /* The index of the item */
+ dm_persitence_t persistence, /* The persistence level of this item */
+ const void *buffer, /* Pointer to caller data buffer */
+ size_t buflen /* Length in bytes of data to retrieve */
+ );
+
+ /* Retrieve from the data manager store */
+ __EXPORT int
+ dm_clear(
+ dm_item_t item /* The item type to clear */
+ );
+
+ /* Tell the data manager about the type of the last reset */
+ __EXPORT int
+ dm_restart(
+ dm_reset_reason restart_type /* The last reset type */
+ );
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/src/modules/dataman/module.mk b/src/modules/dataman/module.mk
new file mode 100644
index 000000000..dce7a6235
--- /dev/null
+++ b/src/modules/dataman/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# 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.
+#
+############################################################################
+
+#
+# Main Navigation Controller
+#
+
+MODULE_COMMAND = dataman
+
+SRCS = dataman.c
+
+INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
diff --git a/src/modules/fixedwing_backside/fixedwing.cpp b/src/modules/fixedwing_backside/fixedwing.cpp
index 6dc19df41..108e9896d 100644
--- a/src/modules/fixedwing_backside/fixedwing.cpp
+++ b/src/modules/fixedwing_backside/fixedwing.cpp
@@ -117,7 +117,7 @@ BlockMultiModeBacksideAutopilot::BlockMultiModeBacksideAutopilot(SuperBlock *par
_vCmd(this, "V_CMD"),
_crMax(this, "CR_MAX"),
_attPoll(),
- _lastPosCmd(),
+ _lastMissionCmd(),
_timeStamp(0)
{
_attPoll.fd = _att.getHandle();
@@ -141,8 +141,8 @@ void BlockMultiModeBacksideAutopilot::update()
setDt(dt);
// store old position command before update if new command sent
- if (_posCmd.updated()) {
- _lastPosCmd = _posCmd.getData();
+ if (_missionCmd.updated()) {
+ _lastMissionCmd = _missionCmd.getData();
}
// check for new updates
@@ -159,7 +159,7 @@ void BlockMultiModeBacksideAutopilot::update()
if (_status.main_state == MAIN_STATE_AUTO) {
// TODO use vehicle_control_mode here?
// update guidance
- _guide.update(_pos, _att, _posCmd.current, _lastPosCmd.current);
+ _guide.update(_pos, _att, _missionCmd.current, _lastMissionCmd.current);
}
// XXX handle STABILIZED (loiter on spot) as well
@@ -182,7 +182,7 @@ void BlockMultiModeBacksideAutopilot::update()
float vCmd = _vLimit.update(_vCmd.get());
// altitude hold
- float dThrottle = _h2Thr.update(_posCmd.current.altitude - _pos.alt);
+ float dThrottle = _h2Thr.update(_missionCmd.current.altitude - _pos.alt);
// heading hold
float psiError = _wrap_pi(_guide.getPsiCmd() - _att.yaw);
diff --git a/src/modules/fixedwing_backside/fixedwing.hpp b/src/modules/fixedwing_backside/fixedwing.hpp
index 567efeb35..b4dbc36b0 100644
--- a/src/modules/fixedwing_backside/fixedwing.hpp
+++ b/src/modules/fixedwing_backside/fixedwing.hpp
@@ -264,7 +264,7 @@ private:
BlockParamFloat _crMax;
struct pollfd _attPoll;
- vehicle_global_position_set_triplet_s _lastPosCmd;
+ mission_item_triplet_s _lastMissionCmd;
enum {CH_AIL, CH_ELV, CH_RDR, CH_THR};
uint64_t _timeStamp;
public:
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index 84983785b..cfa98e573 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -67,7 +67,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_global_position_set_triplet.h>
+#include <uORB/topics/mission_item_triplet.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/actuator_controls.h>
@@ -123,7 +123,7 @@ private:
int _control_task; /**< task handle for sensor task */
int _global_pos_sub;
- int _global_set_triplet_sub;
+ int _mission_item_triplet_sub;
int _att_sub; /**< vehicle attitude subscription */
int _attitude_sub; /**< raw rc channels data subscription */
int _airspeed_sub; /**< airspeed subscription */
@@ -142,7 +142,7 @@ private:
struct airspeed_s _airspeed; /**< airspeed */
struct vehicle_control_mode_s _control_mode; /**< vehicle status */
struct vehicle_global_position_s _global_pos; /**< global vehicle position */
- struct vehicle_global_position_set_triplet_s _global_triplet; /**< triplet of global setpoints */
+ struct mission_item_triplet_s _mission_item_triplet; /**< triplet of mission items */
struct accel_report _accel; /**< body frame accelerations */
perf_counter_t _loop_perf; /**< loop performance counter */
@@ -315,10 +315,10 @@ private:
* Control position.
*/
bool control_position(const math::Vector2f &global_pos, const math::Vector2f &ground_speed,
- const struct vehicle_global_position_set_triplet_s &global_triplet);
+ const struct mission_item_triplet_s &_mission_item_triplet);
float calculate_target_airspeed(float airspeed_demand);
- void calculate_gndspeed_undershoot(const math::Vector2f &current_position, const math::Vector2f &ground_speed, const struct vehicle_global_position_set_triplet_s &global_triplet);
+ void calculate_gndspeed_undershoot(const math::Vector2f &current_position, const math::Vector2f &ground_speed, const struct mission_item_triplet_s &mission_item_triplet);
/**
* Shim for calling task_main from task_create.
@@ -350,7 +350,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
/* subscriptions */
_global_pos_sub(-1),
- _global_set_triplet_sub(-1),
+ _mission_item_triplet_sub(-1),
_att_sub(-1),
_airspeed_sub(-1),
_control_mode_sub(-1),
@@ -388,7 +388,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
airspeed_s _airspeed = {0};
vehicle_control_mode_s _control_mode = {0};
vehicle_global_position_s _global_pos = {0};
- vehicle_global_position_set_triplet_s _global_triplet = {0};
+ mission_item_triplet_s _mission_item_triplet = {0};
accel_report _accel = {0};
@@ -618,11 +618,11 @@ void
FixedwingPositionControl::vehicle_setpoint_poll()
{
/* check if there is a new setpoint */
- bool global_sp_updated;
- orb_check(_global_set_triplet_sub, &global_sp_updated);
+ bool mission_item_triplet_updated;
+ orb_check(_mission_item_triplet_sub, &mission_item_triplet_updated);
- if (global_sp_updated) {
- orb_copy(ORB_ID(vehicle_global_position_set_triplet), _global_set_triplet_sub, &_global_triplet);
+ if (mission_item_triplet_updated) {
+ orb_copy(ORB_ID(mission_item_triplet), _mission_item_triplet_sub, &_mission_item_triplet);
_setpoint_valid = true;
}
}
@@ -665,7 +665,7 @@ FixedwingPositionControl::calculate_target_airspeed(float airspeed_demand)
}
void
-FixedwingPositionControl::calculate_gndspeed_undershoot(const math::Vector2f &current_position, const math::Vector2f &ground_speed, const struct vehicle_global_position_set_triplet_s &global_triplet)
+FixedwingPositionControl::calculate_gndspeed_undershoot(const math::Vector2f &current_position, const math::Vector2f &ground_speed, const struct mission_item_triplet_s &mission_item_triplet)
{
if (_global_pos_valid) {
@@ -678,12 +678,12 @@ FixedwingPositionControl::calculate_gndspeed_undershoot(const math::Vector2f &cu
/* The minimum desired ground speed is the minimum airspeed projected on to the ground using the altitude and horizontal difference between the waypoints if available*/
float distance = 0.0f;
float delta_altitude = 0.0f;
- if (global_triplet.previous_valid) {
- distance = get_distance_to_next_waypoint(global_triplet.previous.lat * 1e-7f, global_triplet.previous.lon * 1e-7f, global_triplet.current.lat * 1e-7f, global_triplet.current.lon * 1e-7f);
- delta_altitude = global_triplet.current.altitude - global_triplet.previous.altitude;
+ if (mission_item_triplet.previous_valid) {
+ distance = get_distance_to_next_waypoint(mission_item_triplet.previous.lat, mission_item_triplet.previous.lon, mission_item_triplet.current.lat, mission_item_triplet.current.lon);
+ delta_altitude = mission_item_triplet.current.altitude - mission_item_triplet.previous.altitude;
} else {
- distance = get_distance_to_next_waypoint(current_position.getX(), current_position.getY(), global_triplet.current.lat * 1e-7f, global_triplet.current.lon * 1e-7f);
- delta_altitude = global_triplet.current.altitude - _global_pos.alt;
+ distance = get_distance_to_next_waypoint(current_position.getX(), current_position.getY(), mission_item_triplet.current.lat, mission_item_triplet.current.lon);
+ delta_altitude = mission_item_triplet.current.altitude - _global_pos.alt;
}
float ground_speed_desired = _parameters.airspeed_min * cosf(atan2f(delta_altitude, distance));
@@ -712,11 +712,11 @@ float FixedwingPositionControl::getLandingSlopeAbsoluteAltitude(float wp_distanc
bool
FixedwingPositionControl::control_position(const math::Vector2f &current_position, const math::Vector2f &ground_speed,
- const struct vehicle_global_position_set_triplet_s &global_triplet)
+ const struct mission_item_triplet_s &mission_item_triplet)
{
bool setpoint = true;
- calculate_gndspeed_undershoot(current_position, ground_speed, global_triplet);
+ calculate_gndspeed_undershoot(current_position, ground_speed, mission_item_triplet);
float eas2tas = 1.0f; // XXX calculate actual number based on current measurements
@@ -728,7 +728,7 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
math::Vector3 accel_earth = _R_nb.transpose() * accel_body;
_tecs.update_50hz(baro_altitude, _airspeed.indicated_airspeed_m_s, _R_nb, accel_body, accel_earth);
- float altitude_error = _global_triplet.current.altitude - _global_pos.alt;
+ float altitude_error = _mission_item_triplet.current.altitude - _global_pos.alt;
/* no throttle limit as default */
float throttle_max = 1.0f;
@@ -749,27 +749,31 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
if (_setpoint_valid && _control_mode.flag_control_auto_enabled) {
/* current waypoint (the one currently heading for) */
- math::Vector2f curr_wp(global_triplet.current.lat / 1e7f, global_triplet.current.lon / 1e7f);
+ math::Vector2f next_wp(mission_item_triplet.current.lat, mission_item_triplet.current.lon);
+
+ /* current waypoint (the one currently heading for) */
+ math::Vector2f curr_wp(mission_item_triplet.current.lat, mission_item_triplet.current.lon);
+
/* previous waypoint */
math::Vector2f prev_wp;
- if (global_triplet.previous_valid) {
- prev_wp.setX(global_triplet.previous.lat / 1e7f);
- prev_wp.setY(global_triplet.previous.lon / 1e7f);
+ if (mission_item_triplet.previous_valid) {
+ prev_wp.setX(mission_item_triplet.previous.lat);
+ prev_wp.setY(mission_item_triplet.previous.lon);
} else {
/*
* No valid previous waypoint, go for the current wp.
* This is automatically handled by the L1 library.
*/
- prev_wp.setX(global_triplet.current.lat / 1e7f);
- prev_wp.setY(global_triplet.current.lon / 1e7f);
+ prev_wp.setX(mission_item_triplet.current.lat);
+ prev_wp.setY(mission_item_triplet.current.lon);
}
// XXX add RTL switch
- if (global_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH && _launch_valid) {
+ if (mission_item_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH && _launch_valid) {
math::Vector2f rtl_pos(_launch_lat, _launch_lon);
@@ -785,35 +789,35 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
// XXX handle case when having arrived at home (loiter)
- } else if (global_triplet.current.nav_cmd == NAV_CMD_WAYPOINT) {
+ } else if (mission_item_triplet.current.nav_cmd == NAV_CMD_WAYPOINT) {
/* waypoint is a plain navigation waypoint */
_l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed);
_att_sp.roll_body = _l1_control.nav_roll();
_att_sp.yaw_body = _l1_control.nav_bearing();
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _mission_item_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
_airspeed.indicated_airspeed_m_s, eas2tas,
false, math::radians(_parameters.pitch_limit_min),
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
- } else if (global_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
- global_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
- global_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
+ } else if (mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
/* waypoint is a loiter waypoint */
- _l1_control.navigate_loiter(curr_wp, current_position, global_triplet.current.loiter_radius,
- global_triplet.current.loiter_direction, ground_speed);
+ _l1_control.navigate_loiter(curr_wp, current_position, mission_item_triplet.current.loiter_radius,
+ mission_item_triplet.current.loiter_direction, ground_speed);
_att_sp.roll_body = _l1_control.nav_roll();
_att_sp.yaw_body = _l1_control.nav_bearing();
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _mission_item_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
_airspeed.indicated_airspeed_m_s, eas2tas,
false, math::radians(_parameters.pitch_limit_min),
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
- } else if (global_triplet.current.nav_cmd == NAV_CMD_LAND) {
+ } else if (mission_item_triplet.current.nav_cmd == NAV_CMD_LAND) {
/* Horizontal landing control */
/* switch to heading hold for the last meters, continue heading hold after */
@@ -825,7 +829,7 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
/* heading hold, along the line connecting this and the last waypoint */
- // if (global_triplet.previous_valid) {
+ // if (mission_item_triplet.previous_valid) {
// target_bearing = get_bearing_to_next_waypoint(prev_wp.getX(), prev_wp.getY(), next_wp.getX(), next_wp.getY());
// } else {
@@ -844,6 +848,7 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
/* normal navigation */
_l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed);
}
+
_att_sp.roll_body = _l1_control.nav_roll();
_att_sp.yaw_body = _l1_control.nav_bearing();
@@ -858,7 +863,7 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
/* apply minimum pitch (flare) and limit roll if close to touch down, altitude error is negative (going down) */
// XXX this could make a great param
- float flare_angle_rad = -math::radians(5.0f);//math::radians(global_triplet.current.param1)
+ float flare_angle_rad = -math::radians(5.0f);//math::radians(mission_item_triplet.current.param1)
float land_pitch_min = math::radians(5.0f);
float throttle_land = _parameters.throttle_min + (_parameters.throttle_max - _parameters.throttle_min) * 0.1f;
float airspeed_land = 1.3f * _parameters.airspeed_min;
@@ -874,10 +879,10 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
float flare_constant = (H0 * d1)/flare_relative_alt;//-flare_length/(logf(H1/H0));
float flare_length = - logf(H1/H0) * flare_constant;//d1+20.0f;//-logf(0.01f/flare_relative_alt);
float horizontal_slope_displacement = (flare_length - d1);
- float L_altitude = getLandingSlopeAbsoluteAltitude(L_wp_distance, _global_triplet.current.altitude, landing_slope_angle_rad, horizontal_slope_displacement);
- float landing_slope_alt_desired = getLandingSlopeAbsoluteAltitude(wp_distance, _global_triplet.current.altitude, landing_slope_angle_rad, horizontal_slope_displacement);
+ float L_altitude = getLandingSlopeAbsoluteAltitude(L_wp_distance, _mission_item_triplet.current.altitude, landing_slope_angle_rad, horizontal_slope_displacement);
+ float landing_slope_alt_desired = getLandingSlopeAbsoluteAltitude(wp_distance, _mission_item_triplet.current.altitude, landing_slope_angle_rad, horizontal_slope_displacement);
- if ( (_global_pos.alt < _global_triplet.current.altitude + flare_relative_alt) || land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
+ if ( (_global_pos.alt < _mission_item_triplet.current.altitude + flare_relative_alt) || land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
/* land with minimal speed */
@@ -896,12 +901,12 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
}
- float flare_curve_alt = _global_triplet.current.altitude + H0 * expf(-math::max(0.0f, flare_length - wp_distance)/flare_constant) - H1;
+ float flare_curve_alt = _mission_item_triplet.current.altitude + H0 * expf(-math::max(0.0f, flare_length - wp_distance)/flare_constant) - H1;
/* avoid climbout */
if (flare_curve_alt_last < flare_curve_alt && land_noreturn_vertical || land_stayonground)
{
- flare_curve_alt = global_triplet.current.altitude;
+ flare_curve_alt = mission_item_triplet.current.altitude;
land_stayonground = true;
}
@@ -961,7 +966,7 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
}
- } else if (global_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
+ } else if (mission_item_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
_l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed);
_att_sp.roll_body = _l1_control.nav_roll();
@@ -971,9 +976,9 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
if (altitude_error > 15.0f) {
/* enforce a minimum of 10 degrees pitch up on takeoff, or take parameter */
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_min),
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _mission_item_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_min),
_airspeed.indicated_airspeed_m_s, eas2tas,
- true, math::max(math::radians(global_triplet.current.param1), math::radians(10.0f)),
+ true, math::max(math::radians(mission_item_triplet.current.radius), math::radians(10.0f)),
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
@@ -982,7 +987,7 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
} else {
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _mission_item_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
_airspeed.indicated_airspeed_m_s, eas2tas,
false, math::radians(_parameters.pitch_limit_min),
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
@@ -993,7 +998,7 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
// warnx("nav bearing: %8.4f bearing err: %8.4f target bearing: %8.4f", (double)_l1_control.nav_bearing(),
// (double)_l1_control.bearing_error(), (double)_l1_control.target_bearing());
// warnx("prev wp: %8.4f/%8.4f, next wp: %8.4f/%8.4f prev:%s", (double)prev_wp.getX(), (double)prev_wp.getY(),
- // (double)next_wp.getX(), (double)next_wp.getY(), (global_triplet.previous_valid) ? "valid" : "invalid");
+ // (double)next_wp.getX(), (double)next_wp.getY(), (mission_item_triplet.previous_valid) ? "valid" : "invalid");
// XXX at this point we always want no loiter hold if a
// mission is active
@@ -1047,7 +1052,7 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
}
/* reset land state */
- if (global_triplet.current.nav_cmd != NAV_CMD_LAND) {
+ if (mission_item_triplet.current.nav_cmd != NAV_CMD_LAND) {
land_noreturn_horizontal = false;
land_noreturn_vertical = false;
land_stayonground = false;
@@ -1167,7 +1172,7 @@ FixedwingPositionControl::task_main()
* do subscriptions
*/
_global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
- _global_set_triplet_sub = orb_subscribe(ORB_ID(vehicle_global_position_set_triplet));
+ _mission_item_triplet_sub = orb_subscribe(ORB_ID(mission_item_triplet));
_att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
_accel_sub = orb_subscribe(ORB_ID(sensor_accel));
_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
@@ -1257,7 +1262,7 @@ FixedwingPositionControl::task_main()
* Attempt to control position, on success (= sensors present and not in manual mode),
* publish setpoint.
*/
- if (control_position(current_position, ground_speed, _global_triplet)) {
+ if (control_position(current_position, ground_speed, _mission_item_triplet)) {
_att_sp.timestamp = hrt_absolute_time();
/* lazily publish the setpoint only once available */
@@ -1270,7 +1275,8 @@ FixedwingPositionControl::task_main()
_attitude_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &_att_sp);
}
- float turn_distance = _l1_control.switch_distance(_global_triplet.current.turn_distance_xy);
+ /* XXX check if radius makes sense here */
+ float turn_distance = _l1_control.switch_distance(_mission_item_triplet.current.radius);
/* lazily publish navigation capabilities */
if (turn_distance != _nav_capabilities.turn_distance && turn_distance > 0) {
diff --git a/src/modules/mavlink/missionlib.c b/src/modules/mavlink/missionlib.c
index bb857dc69..a7f9a6acf 100644
--- a/src/modules/mavlink/missionlib.c
+++ b/src/modules/mavlink/missionlib.c
@@ -206,7 +206,7 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command)
{
static orb_advert_t global_position_setpoint_pub = -1;
- static orb_advert_t global_position_set_triplet_pub = -1;
+ // static orb_advert_t global_position_set_triplet_pub = -1;
static orb_advert_t local_position_setpoint_pub = -1;
static unsigned last_waypoint_index = -1;
char buf[50] = {0};
@@ -234,10 +234,10 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
/* fill triplet: previous, current, next waypoint */
- struct vehicle_global_position_set_triplet_s triplet;
+ // struct vehicle_global_position_set_triplet_s triplet;
/* current waypoint is same as sp */
- memcpy(&(triplet.current), &sp, sizeof(sp));
+ // memcpy(&(triplet.current), &sp, sizeof(sp));
/*
* Check if previous WP (in mission, not in execution order)
@@ -291,48 +291,48 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
/* populate last and next */
- triplet.previous_valid = false;
- triplet.next_valid = false;
-
- if (last_setpoint_valid) {
- triplet.previous_valid = true;
- struct vehicle_global_position_setpoint_s sp;
- sp.lat = wpm->waypoints[last_setpoint_index].x * 1e7f;
- sp.lon = wpm->waypoints[last_setpoint_index].y * 1e7f;
- sp.altitude = wpm->waypoints[last_setpoint_index].z;
- sp.altitude_is_relative = false;
- sp.yaw = (wpm->waypoints[last_setpoint_index].param4 / 180.0f) * M_PI_F - M_PI_F;
- set_special_fields(wpm->waypoints[last_setpoint_index].param1,
- wpm->waypoints[last_setpoint_index].param2,
- wpm->waypoints[last_setpoint_index].param3,
- wpm->waypoints[last_setpoint_index].param4,
- wpm->waypoints[last_setpoint_index].command, &sp);
- memcpy(&(triplet.previous), &sp, sizeof(sp));
- }
-
- if (next_setpoint_valid) {
- triplet.next_valid = true;
- struct vehicle_global_position_setpoint_s sp;
- sp.lat = wpm->waypoints[next_setpoint_index].x * 1e7f;
- sp.lon = wpm->waypoints[next_setpoint_index].y * 1e7f;
- sp.altitude = wpm->waypoints[next_setpoint_index].z;
- sp.altitude_is_relative = false;
- sp.yaw = (wpm->waypoints[next_setpoint_index].param4 / 180.0f) * M_PI_F - M_PI_F;
- set_special_fields(wpm->waypoints[next_setpoint_index].param1,
- wpm->waypoints[next_setpoint_index].param2,
- wpm->waypoints[next_setpoint_index].param3,
- wpm->waypoints[next_setpoint_index].param4,
- wpm->waypoints[next_setpoint_index].command, &sp);
- memcpy(&(triplet.next), &sp, sizeof(sp));
- }
+ // triplet.previous_valid = false;
+ // triplet.next_valid = false;
+
+ // if (last_setpoint_valid) {
+ // triplet.previous_valid = true;
+ // struct vehicle_global_position_setpoint_s sp;
+ // sp.lat = wpm->waypoints[last_setpoint_index].x * 1e7f;
+ // sp.lon = wpm->waypoints[last_setpoint_index].y * 1e7f;
+ // sp.altitude = wpm->waypoints[last_setpoint_index].z;
+ // sp.altitude_is_relative = false;
+ // sp.yaw = (wpm->waypoints[last_setpoint_index].param4 / 180.0f) * M_PI_F - M_PI_F;
+ // set_special_fields(wpm->waypoints[last_setpoint_index].param1,
+ // wpm->waypoints[last_setpoint_index].param2,
+ // wpm->waypoints[last_setpoint_index].param3,
+ // wpm->waypoints[last_setpoint_index].param4,
+ // wpm->waypoints[last_setpoint_index].command, &sp);
+ // memcpy(&(triplet.previous), &sp, sizeof(sp));
+ // }
+
+ // if (next_setpoint_valid) {
+ // triplet.next_valid = true;
+ // struct vehicle_global_position_setpoint_s sp;
+ // sp.lat = wpm->waypoints[next_setpoint_index].x * 1e7f;
+ // sp.lon = wpm->waypoints[next_setpoint_index].y * 1e7f;
+ // sp.altitude = wpm->waypoints[next_setpoint_index].z;
+ // sp.altitude_is_relative = false;
+ // sp.yaw = (wpm->waypoints[next_setpoint_index].param4 / 180.0f) * M_PI_F - M_PI_F;
+ // set_special_fields(wpm->waypoints[next_setpoint_index].param1,
+ // wpm->waypoints[next_setpoint_index].param2,
+ // wpm->waypoints[next_setpoint_index].param3,
+ // wpm->waypoints[next_setpoint_index].param4,
+ // wpm->waypoints[next_setpoint_index].command, &sp);
+ // memcpy(&(triplet.next), &sp, sizeof(sp));
+ // }
/* Initialize triplet publication if necessary */
- if (global_position_set_triplet_pub < 0) {
- global_position_set_triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &triplet);
+ // if (global_position_set_triplet_pub < 0) {
+ // global_position_set_triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &triplet);
- } else {
- orb_publish(ORB_ID(vehicle_global_position_set_triplet), global_position_set_triplet_pub, &triplet);
- }
+ // } else {
+ // orb_publish(ORB_ID(vehicle_global_position_set_triplet), global_position_set_triplet_pub, &triplet);
+ // }
sprintf(buf, "[mp] WP#%i lat: % 3.6f/lon % 3.6f/alt % 4.6f/hdg %3.4f\n", (int)index, (double)param5_lat_x, (double)param6_lon_y, (double)param7_alt_z, (double)param4);
diff --git a/src/modules/mavlink/orb_topics.h b/src/modules/mavlink/orb_topics.h
index 91773843b..2cba25338 100644
--- a/src/modules/mavlink/orb_topics.h
+++ b/src/modules/mavlink/orb_topics.h
@@ -52,7 +52,7 @@
#include <uORB/topics/vehicle_local_position_setpoint.h>
#include <uORB/topics/vehicle_vicon_position.h>
#include <uORB/topics/vehicle_global_position_setpoint.h>
-#include <uORB/topics/vehicle_global_position_set_triplet.h>
+#include <uORB/topics/mission_item_triplet.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/vehicle_control_mode.h>
diff --git a/src/modules/mavlink/waypoints.c b/src/modules/mavlink/waypoints.c
index 7e4a2688f..5fdbd57e1 100644
--- a/src/modules/mavlink/waypoints.c
+++ b/src/modules/mavlink/waypoints.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
* Author: @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
@@ -49,6 +49,9 @@
#include "missionlib.h"
#include "waypoints.h"
#include "util.h"
+#include <uORB/uORB.h>
+#include <uORB/topics/mission.h>
+
#ifndef FM_PI
#define FM_PI 3.1415926535897932384626433832795f
@@ -58,10 +61,39 @@ bool debug = false;
bool verbose = false;
-#define MAVLINK_WPM_NO_PRINTF
+//#define MAVLINK_WPM_NO_PRINTF
+#define MAVLINK_WPM_VERBOSE 1
uint8_t mavlink_wpm_comp_id = MAV_COMP_ID_MISSIONPLANNER;
+void map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item)
+{
+ mission_item->lat = (double)mavlink_mission_item->x;
+ mission_item->lon = (double)mavlink_mission_item->y;
+ mission_item->altitude = mavlink_mission_item->z;
+ mission_item->yaw = mavlink_mission_item->param4*M_DEG_TO_RAD_F;
+ mission_item->loiter_radius = fabsf(mavlink_mission_item->param3);
+ mission_item->loiter_direction = (mavlink_mission_item->param3 > 0) ? 1 : -1; /* 1 if positive CW, -1 if negative CCW */
+ mission_item->nav_cmd = NAV_CMD_WAYPOINT; // TODO correct
+ mission_item->radius = mavlink_mission_item->param1;
+ mission_item->time_inside = mavlink_mission_item->param2;
+}
+
+void map_mission_item_to_mavlink_mission_item(const struct mission_item_s *mission_item, const uint16_t seq, mavlink_mission_item_t *mavlink_mission_item)
+{
+
+ mavlink_mission_item->x = (float)mission_item->lat;
+ mavlink_mission_item->y = (float)mission_item->lon;
+ mavlink_mission_item->z = mission_item->altitude;
+ mavlink_mission_item->param4 = mission_item->yaw*M_RAD_TO_DEG_F;
+ mavlink_mission_item->param3 = mission_item->loiter_radius*(float)mission_item->loiter_direction;
+ mavlink_mission_item->command = MAV_CMD_NAV_WAYPOINT; // TODO add
+ mavlink_mission_item->param1 = mission_item->radius;
+ mavlink_mission_item->param2 = mission_item->time_inside;
+
+ mavlink_mission_item->seq = seq;
+}
+
void mavlink_wpm_init(mavlink_wpm_storage *state)
{
// Set all waypoints to zero
@@ -185,11 +217,12 @@ void mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t cou
// FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
}
-void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq)
+void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, mavlink_mission_item_t *wp)
{
- if (seq < wpm->size) {
+
+ // if (seq < wpm->size) {
mavlink_message_t msg;
- mavlink_mission_item_t *wp = &(wpm->waypoints[seq]);
+ // mavlink_mission_item_t *wp = &(wpm->waypoints[seq]);
wp->target_system = wpm->current_partner_sysid;
wp->target_component = wpm->current_partner_compid;
mavlink_msg_mission_item_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, wp);
@@ -199,9 +232,9 @@ void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq)
// FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
- } else {
- if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index out of bounds\n");
- }
+ // } else {
+ // if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index out of bounds\n");
+ // }
}
void mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t seq)
@@ -523,6 +556,9 @@ int mavlink_waypoint_eventloop(uint64_t now, const struct vehicle_global_positio
void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehicle_global_position_s *global_pos , struct vehicle_local_position_s *local_pos)
{
+ static orb_advert_t mission_pub = -1;
+ static struct mission_s mission;
+
uint64_t now = mavlink_missionlib_get_system_timestamp();
switch (msg->msgid) {
@@ -671,7 +707,10 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS;
wpm->current_wp_id = wpr.seq;
- mavlink_wpm_send_waypoint(wpm->current_partner_sysid, wpm->current_partner_compid, wpr.seq);
+
+ mavlink_mission_item_t wp;
+ map_mission_item_to_mavlink_mission_item(&mission.items[wpr.seq], wpr.seq, &wp);
+ mavlink_wpm_send_waypoint(wpm->current_partner_sysid, wpm->current_partner_compid, &wp);
} else {
// if (verbose)
@@ -794,6 +833,16 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
wpm->current_partner_compid = msg->compid;
wpm->current_count = wpc.count;
+ /* prepare mission topic */
+ mission.count = wpc.count;
+ mission.items = (struct mission_item_s*)malloc(sizeof(struct mission_item_s) * mission.count);
+
+ if (!mission.items) {
+ mission.count = 0;
+ /* XXX reject waypoints if this fails */
+ warnx("no free RAM to allocate mission, rejecting any waypoints");
+ }
+
#ifdef MAVLINK_WPM_NO_PRINTF
mavlink_missionlib_send_gcs_string("CLR RCV BUF: READY");
#else
@@ -933,7 +982,18 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
for (i = 0; i < wpm->current_count; ++i) {
wpm->waypoints[i] = wpm->rcv_waypoints[i];
+ map_mavlink_mission_item_to_mission_item(&wpm->rcv_waypoints[i], &mission.items[i]);
}
+ // TODO: update count?
+
+ /* Initialize mission publication if necessary */
+ if (mission_pub < 0) {
+ mission_pub = orb_advertise(ORB_ID(mission), &mission);
+
+ } else {
+ orb_publish(ORB_ID(mission), mission_pub, &mission);
+ }
+
wpm->size = wpm->current_count;
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index 0404b06c7..7f7443c43 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = navigator
SRCS = navigator_main.cpp \
navigator_params.c
+
+INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index f6c44444a..a255797c6 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -1,7 +1,9 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier
+ * Authors: Lorenz Meier
+ * Jean Cyr
+ * Julian Oes
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -48,26 +50,25 @@
#include <math.h>
#include <poll.h>
#include <time.h>
+#include <sys/ioctl.h>
+#include <drivers/device/device.h>
#include <drivers/drv_hrt.h>
#include <arch/board/board.h>
#include <uORB/uORB.h>
-#include <uORB/topics/airspeed.h>
#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_global_position_set_triplet.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/mission_item_triplet.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/mission.h>
+#include <uORB/topics/fence.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <geo/geo.h>
#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
#include <mathlib/mathlib.h>
+#include <dataman/dataman.h>
+
/**
* navigator app start / stop handling function
@@ -90,41 +91,57 @@ public:
~Navigator();
/**
- * Start the sensors task.
+ * Start the navigator task.
*
* @return OK on success.
*/
int start();
+ /**
+ * Display the navigator status.
+ */
+ void status();
+
+ /**
+ * Load fence parameters.
+ */
+ bool load_fence(unsigned vertices);
+
+ /**
+ * Specify fence vertex position.
+ */
+ void fence_point(int argc, char *argv[]);
+
private:
bool _task_should_exit; /**< if true, sensor task should exit */
- int _navigator_task; /**< task handle for sensor task */
+ int _navigator_task; /**< task handle for sensor task */
int _global_pos_sub;
- int _att_sub; /**< vehicle attitude subscription */
- int _attitude_sub; /**< raw rc channels data subscription */
- int _airspeed_sub; /**< airspeed subscription */
int _vstatus_sub; /**< vehicle status subscription */
int _params_sub; /**< notification of parameter updates */
- int _manual_control_sub; /**< notification of manual control updates */
- int _mission_sub;
+ int _mission_sub; /**< notification of mission updates */
+ int _capabilities_sub; /**< notification of vehicle capabilities updates */
- orb_advert_t _triplet_pub; /**< position setpoint */
+ orb_advert_t _triplet_pub; /**< publish position setpoint triplet */
+ orb_advert_t _fence_pub; /**< publish fence topic */
- struct vehicle_attitude_s _att; /**< vehicle attitude */
- struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */
- struct manual_control_setpoint_s _manual; /**< r/c channel data */
- struct airspeed_s _airspeed; /**< airspeed */
struct vehicle_status_s _vstatus; /**< vehicle status */
struct vehicle_global_position_s _global_pos; /**< global vehicle position */
- struct vehicle_global_position_set_triplet_s _global_triplet; /**< triplet of global setpoints */
+ struct mission_item_triplet_s _mission_item_triplet; /**< triplet of mission items */
perf_counter_t _loop_perf; /**< loop performance counter */
- unsigned _mission_items_maxcount; /**< maximum number of mission items supported */
- struct mission_item_s * _mission_items; /**< storage for mission items */
- bool _mission_valid; /**< flag if mission is valid */
+ unsigned _mission_item_count; /**< maximum number of mission items supported */
+ struct mission_item_s * _mission_items; /**< storage for mission */
+ bool _mission_valid; /**< flag if mission is valid */
+
+
+ struct fence_s _fence; /**< storage for fence vertices */
+ bool _fence_valid; /**< flag if fence is valid */
+ bool _inside_fence; /**< vehicle is inside fence */
+
+ struct navigation_capabilities_s _nav_caps;
/** manual control states */
float _seatbelt_hold_heading; /**< heading the system should hold in seatbelt mode */
@@ -155,19 +172,9 @@ private:
void control_update();
/**
- * Check for changes in vehicle status.
- */
- void vehicle_status_poll();
-
- /**
- * Check for position updates.
- */
- void vehicle_attitude_poll();
-
- /**
- * Check for set triplet updates.
- */
- void mission_poll();
+ * Retrieve mission.
+ */
+ void mission_update();
/**
* Control throttle.
@@ -179,10 +186,6 @@ private:
*/
float control_pitch(float altitude_error);
- void calculate_airspeed_errors();
- void calculate_gndspeed_undershoot();
- void calculate_altitude_error();
-
/**
* Shim for calling task_main from task_create.
*/
@@ -192,6 +195,14 @@ private:
* Main sensor collection task.
*/
void task_main() __attribute__((noreturn));
+
+ void publish_fence(unsigned vertices);
+
+ void publish_safepoints(unsigned points);
+
+ bool fence_valid(const struct fence_s &fence);
+
+ void current_waypoint_changed(unsigned next_setpoint_index);
};
namespace navigator
@@ -213,31 +224,29 @@ Navigator::Navigator() :
/* subscriptions */
_global_pos_sub(-1),
- _att_sub(-1),
- _airspeed_sub(-1),
_vstatus_sub(-1),
_params_sub(-1),
- _manual_control_sub(-1),
+ _mission_sub(-1),
+ _capabilities_sub(-1),
/* publications */
_triplet_pub(-1),
+ _fence_pub(-1),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "navigator")),
/* states */
- _mission_items_maxcount(20),
+ _mission_item_count(0),
_mission_valid(false),
+ _fence_valid(false),
+ _inside_fence(true),
_loiter_hold(false)
{
- _mission_items = (mission_item_s*)malloc(sizeof(mission_item_s) * _mission_items_maxcount);
- if (!_mission_items) {
- _mission_items_maxcount = 0;
- warnx("no free RAM to allocate mission, rejecting any waypoints");
- }
-
+ _global_pos.valid = false;
+ memset(&_fence, 0, sizeof(_fence));
_parameter_handles.throttle_cruise = param_find("NAV_DUMMY");
- /* fetch initial parameter values */
+ /* fetch initial values */
parameters_update();
}
@@ -276,59 +285,35 @@ Navigator::parameters_update()
}
void
-Navigator::vehicle_status_poll()
-{
- bool vstatus_updated;
-
- /* Check HIL state if vehicle status has changed */
- orb_check(_vstatus_sub, &vstatus_updated);
-
- if (vstatus_updated) {
-
- orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus);
- }
-}
-
-void
-Navigator::vehicle_attitude_poll()
-{
- /* check if there is a new position */
- bool att_updated;
- orb_check(_att_sub, &att_updated);
-
- if (att_updated) {
- orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
- }
-}
-
-void
-Navigator::mission_poll()
+Navigator::mission_update()
{
- /* check if there is a new setpoint */
- bool mission_updated;
- orb_check(_mission_sub, &mission_updated);
-
- if (mission_updated) {
-
- struct mission_s mission;
- orb_copy(ORB_ID(mission), _mission_sub, &mission);
-
+ struct mission_s mission;
+ if (orb_copy(ORB_ID(mission), _mission_sub, &mission) == OK) {
// XXX this is not optimal yet, but a first prototype /
// test implementation
- if (mission.count <= _mission_items_maxcount) {
- /*
- * Perform an atomic copy & state update
- */
- irqstate_t flags = irqsave();
+ if (mission.count > _mission_item_count) {
+ _mission_items = (mission_item_s*)malloc(sizeof(mission_item_s) * _mission_item_count);
+ if (!_mission_items) {
+ _mission_item_count = 0;
+ warnx("no free RAM to allocate mission, rejecting any waypoints");
+ }
+ }
- memcpy(_mission_items, mission.items, mission.count * sizeof(struct mission_item_s));
- _mission_valid = true;
+ /*
+ * Perform an atomic copy & state update
+ */
+ irqstate_t flags = irqsave();
- irqrestore(flags);
- } else {
- warnx("mission larger than storage space");
- }
+ memcpy(_mission_items, mission.items, mission.count * sizeof(struct mission_item_s));
+ _mission_valid = true;
+ _mission_item_count = mission.count;
+
+ irqrestore(flags);
+
+ /* Reset to 0 for now when a waypoint is changed */
+ /* TODO add checks if and how the mission has changed */
+ current_waypoint_changed(0);
}
}
@@ -351,11 +336,16 @@ Navigator::task_main()
*/
_global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
_mission_sub = orb_subscribe(ORB_ID(mission));
- _att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- _airspeed_sub = orb_subscribe(ORB_ID(airspeed));
+ _capabilities_sub = orb_subscribe(ORB_ID(navigation_capabilities));
_vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
- _manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+
+ // Load initial states
+ if (orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus) != OK) {
+ _vstatus.arming_state = ARMING_STATE_STANDBY; // for testing... commander may not be running
+ }
+
+ mission_update();
/* rate limit vehicle status updates to 5Hz */
orb_set_interval(_vstatus_sub, 200);
@@ -364,23 +354,35 @@ Navigator::task_main()
parameters_update();
+ _fence_valid = load_fence(GEOFENCE_MAX_VERTICES);
+
+ /* load the craft capabilities */
+ orb_copy(ORB_ID(navigation_capabilities), _capabilities_sub, &_nav_caps);
+
/* wakeup source(s) */
- struct pollfd fds[2];
+ struct pollfd fds[5];
/* Setup of loop */
fds[0].fd = _params_sub;
fds[0].events = POLLIN;
fds[1].fd = _global_pos_sub;
fds[1].events = POLLIN;
+ fds[2].fd = _capabilities_sub;
+ fds[2].events = POLLIN;
+ fds[3].fd = _mission_sub;
+ fds[3].events = POLLIN;
+ fds[4].fd = _vstatus_sub;
+ fds[4].events = POLLIN;
while (!_task_should_exit) {
- /* wait for up to 500ms for data */
+ /* wait for up to 100ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
/* timed out - periodic check for _task_should_exit, etc. */
- if (pret == 0)
+ if (pret == 0) {
continue;
+ }
/* this is undesirable but not much we can do - might want to flag unhappy status */
if (pret < 0) {
@@ -390,10 +392,13 @@ Navigator::task_main()
perf_begin(_loop_perf);
- /* check vehicle status for changes to publication state */
- vehicle_status_poll();
-
/* only update parameters if they changed */
+ if (fds[4].revents & POLLIN) {
+ /* read from param to clear updated flag */
+ orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus);
+ }
+
+ /* only update vehicle status if it changed */
if (fds[0].revents & POLLIN) {
/* read from param to clear updated flag */
struct parameter_update_s update;
@@ -403,28 +408,37 @@ Navigator::task_main()
parameters_update();
}
+ /* only update craft capabilities if they have changed */
+ if (fds[2].revents & POLLIN) {
+ orb_copy(ORB_ID(navigation_capabilities), _capabilities_sub, &_nav_caps);
+ }
+
+ if (fds[3].revents & POLLIN) {
+ mission_update();
+ }
+
/* only run controller if position changed */
if (fds[1].revents & POLLIN) {
+ /* load local copies */
+ orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
static uint64_t last_run = 0;
float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
last_run = hrt_absolute_time();
/* guard against too large deltaT's */
- if (deltaT > 1.0f)
+ if (deltaT > 1.0f) {
deltaT = 0.01f;
+ }
- /* load local copies */
- orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
-
- vehicle_attitude_poll();
-
- mission_poll();
+ if (_fence_valid && _global_pos.valid) {
+ _inside_fence = inside_geofence(&_global_pos, &_fence);
+ }
math::Vector2f ground_speed(_global_pos.vx, _global_pos.vy);
// Current waypoint
- math::Vector2f next_wp(_global_triplet.current.lat / 1e7f, _global_triplet.current.lon / 1e7f);
+ math::Vector2f next_wp(_mission_item_triplet.current.lat / 1e7f, _mission_item_triplet.current.lon / 1e7f);
// Global position
math::Vector2f current_position(_global_pos.lat / 1e7f, _global_pos.lon / 1e7f);
@@ -438,17 +452,17 @@ Navigator::task_main()
// Next waypoint
math::Vector2f prev_wp;
- if (_global_triplet.previous_valid) {
- prev_wp.setX(_global_triplet.previous.lat / 1e7f);
- prev_wp.setY(_global_triplet.previous.lon / 1e7f);
+ if (_mission_item_triplet.previous_valid) {
+ prev_wp.setX(_mission_item_triplet.previous.lat / 1e7f);
+ prev_wp.setY(_mission_item_triplet.previous.lon / 1e7f);
} else {
/*
* No valid next waypoint, go for heading hold.
* This is automatically handled by the L1 library.
*/
- prev_wp.setX(_global_triplet.current.lat / 1e7f);
- prev_wp.setY(_global_triplet.current.lon / 1e7f);
+ prev_wp.setX(_mission_item_triplet.current.lat / 1e7f);
+ prev_wp.setY(_mission_item_triplet.current.lon / 1e7f);
}
@@ -458,16 +472,16 @@ Navigator::task_main()
// XXX to be put in its own class
- if (_global_triplet.current.nav_cmd == NAV_CMD_WAYPOINT) {
+ if (_mission_item_triplet.current.nav_cmd == NAV_CMD_WAYPOINT) {
/* waypoint is a plain navigation waypoint */
-
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
- _global_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
- _global_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
+
+ } else if (_mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
/* waypoint is a loiter waypoint */
-
+
}
// XXX at this point we always want no loiter hold if a
@@ -501,36 +515,37 @@ Navigator::task_main()
/******** MAIN NAVIGATION STATE MACHINE ********/
- if (_global_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
+ if (_mission_item_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
// XXX define launch position and return
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_LAND) {
+ } else if (_mission_item_triplet.current.nav_cmd == NAV_CMD_LAND) {
// XXX flared descent on final approach
- } else if (_global_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
+ } else if (_mission_item_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
/* apply minimum pitch if altitude has not yet been reached */
- if (_global_pos.alt < _global_triplet.current.altitude) {
- _att_sp.pitch_body = math::max(_att_sp.pitch_body, _global_triplet.current.param1);
- }
+ // if (_global_pos.alt < _mission_item_triplet.current.altitude) {
+ // _att_sp.pitch_body = math::max(_att_sp.pitch_body, _mission_item_triplet.current.param1);
+ // }
}
/* lazily publish the setpoint only once available */
if (_triplet_pub > 0) {
/* publish the attitude setpoint */
- orb_publish(ORB_ID(vehicle_global_position_set_triplet), _triplet_pub, &_global_triplet);
+ orb_publish(ORB_ID(mission_item_triplet), _triplet_pub, &_mission_item_triplet);
} else {
/* advertise and publish */
- _triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &_global_triplet);
+ _triplet_pub = orb_advertise(ORB_ID(mission_item_triplet), &_mission_item_triplet);
}
}
perf_end(_loop_perf);
+
}
- warnx("exiting.\n");
+ warnx("exiting.");
_navigator_task = -1;
_exit(0);
@@ -543,11 +558,11 @@ Navigator::start()
/* start the task */
_navigator_task = task_spawn_cmd("navigator",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 5,
- 2048,
- (main_t)&Navigator::task_main_trampoline,
- nullptr);
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2048,
+ (main_t)&Navigator::task_main_trampoline,
+ nullptr);
if (_navigator_task < 0) {
warn("task start failed");
@@ -557,20 +572,211 @@ Navigator::start()
return OK;
}
+void
+Navigator::status()
+{
+ warnx("Global position is %svalid", _global_pos.valid ? "" : "in");
+ if (_global_pos.valid) {
+ warnx("Longitude %5.5f degrees, latitude %5.5f degrees", _global_pos.lon / 1e7, _global_pos.lat / 1e7);
+ warnx("Altitude %5.5f meters, altitude above home %5.5f meters",
+ (double)_global_pos.alt, (double)_global_pos.relative_alt);
+ warnx("Ground velocity in m/s, x %5.5f, y %5.5f, z %5.5f",
+ (double)_global_pos.vx, (double)_global_pos.vy, (double)_global_pos.vz);
+ warnx("Compass heading in degrees %5.5f", (double)_global_pos.yaw * 57.2957795);
+ }
+ if (_fence_valid) {
+ warnx("Geofence is valid");
+ warnx("Vertex longitude latitude");
+ for (unsigned i = 0; i < _fence.count; i++)
+ warnx("%6u %9.5f %8.5f", i, (double)_fence.vertices[i].lon, (double)_fence.vertices[i].lat);
+ } else
+ warnx("Geofence not set");
+}
+
+void
+Navigator::publish_fence(unsigned vertices)
+{
+ if (_fence_pub == -1)
+ _fence_pub = orb_advertise(ORB_ID(fence), &vertices);
+ else
+ orb_publish(ORB_ID(fence), _fence_pub, &vertices);
+}
+
+bool
+Navigator::fence_valid(const struct fence_s &fence)
+{
+ // NULL fence is valid
+ if (fence.count == 0) {
+ return true;
+ }
+
+ // Otherwise
+ if ((fence.count < 4) || (fence.count > GEOFENCE_MAX_VERTICES)) {
+ warnx("Fence must have at least 3 sides and not more than %d", GEOFENCE_MAX_VERTICES - 1);
+ return false;
+ }
+
+ return true;
+}
+
+bool
+Navigator::load_fence(unsigned vertices)
+{
+ struct fence_s temp_fence;
+
+ unsigned i;
+ for (i = 0; i < vertices; i++) {
+ if (dm_read(DM_KEY_FENCE_POINTS, i, temp_fence.vertices + i, sizeof(struct fence_vertex_s)) != sizeof(struct fence_vertex_s)) {
+ break;
+ }
+ }
+
+ temp_fence.count = i;
+
+ if (fence_valid(temp_fence))
+ memcpy(&_fence, &temp_fence, sizeof(_fence));
+ else
+ warnx("Invalid fence file, ignored!");
+
+ return _fence.count != 0;
+}
+
+void
+Navigator::fence_point(int argc, char *argv[])
+{
+ int ix, last;
+ double lon, lat;
+ struct fence_vertex_s vertex;
+ char *end;
+
+ if ((argc == 1) && (strcmp("-clear", argv[0]) == 0)) {
+ dm_clear(DM_KEY_FENCE_POINTS);
+ publish_fence(0);
+ return;
+ }
+
+ if (argc < 3)
+ errx(1, "Specify: -clear | sequence latitude longitude [-publish]");
+
+ ix = atoi(argv[0]);
+ if (ix >= DM_KEY_FENCE_POINTS_MAX)
+ errx(1, "Sequence must be less than %d", DM_KEY_FENCE_POINTS_MAX);
+
+ lat = strtod(argv[1], &end);
+ lon = strtod(argv[2], &end);
+
+ last = 0;
+ if ((argc > 3) && (strcmp(argv[3], "-publish") == 0))
+ last = 1;
+
+ vertex.lat = (float)lat;
+ vertex.lon = (float)lon;
+
+ if (dm_write(DM_KEY_FENCE_POINTS, ix, DM_PERSIST_POWER_ON_RESET, &vertex, sizeof(vertex)) == sizeof(vertex)) {
+ if (last)
+ publish_fence((unsigned)ix + 1);
+ return;
+ }
+
+ errx(1, "can't store fence point");
+}
+
+void
+Navigator::current_waypoint_changed(unsigned new_setpoint_index)
+{
+ /* TODO: extend this to different frames, global for now */
+
+ _mission_item_triplet.current_valid = false;
+
+ if (_mission_item_count > 0 && new_setpoint_index < _mission_item_count) {
+ _mission_item_triplet.current_valid = true;
+ memcpy(&_mission_item_triplet.current, &_mission_items[new_setpoint_index], sizeof(mission_item_s));
+ }
+
+ int previous_setpoint_index = -1;
+ _mission_item_triplet.previous_valid = false;
+
+ if (new_setpoint_index > 0) {
+ previous_setpoint_index = new_setpoint_index - 1;
+ }
+
+ while (previous_setpoint_index >= 0) {
+
+ if ((_mission_items[previous_setpoint_index].nav_cmd == (int)MAV_CMD_NAV_WAYPOINT ||
+ _mission_items[previous_setpoint_index].nav_cmd == (int)MAV_CMD_NAV_LOITER_TURNS ||
+ _mission_items[previous_setpoint_index].nav_cmd == (int)MAV_CMD_NAV_LOITER_TIME ||
+ _mission_items[previous_setpoint_index].nav_cmd == (int)MAV_CMD_NAV_LOITER_UNLIM)) {
+
+ _mission_item_triplet.previous_valid = true;
+ memcpy(&_mission_item_triplet.previous, &_mission_items[previous_setpoint_index], sizeof(mission_item_s));
+ break;
+ }
+
+ previous_setpoint_index--;
+ }
+
+ /*
+ * Check if next WP (in mission, not in execution order)
+ * is available and identify correct index
+ */
+ int next_setpoint_index = -1;
+ _mission_item_triplet.next_valid = false;
+
+ /* next waypoint */
+ if (_mission_item_count > 1) {
+ next_setpoint_index = new_setpoint_index + 1;
+ }
+
+ while (next_setpoint_index < _mission_item_count - 1) {
+
+ if ((_mission_items[next_setpoint_index].nav_cmd == (int)MAV_CMD_NAV_WAYPOINT ||
+ _mission_items[next_setpoint_index].nav_cmd == (int)MAV_CMD_NAV_LOITER_TURNS ||
+ _mission_items[next_setpoint_index].nav_cmd == (int)MAV_CMD_NAV_LOITER_TIME ||
+ _mission_items[next_setpoint_index].nav_cmd == (int)MAV_CMD_NAV_LOITER_UNLIM)) {
+
+ _mission_item_triplet.next_valid = true;
+ memcpy(&_mission_item_triplet.next, &_mission_items[next_setpoint_index], sizeof(mission_item_s));
+ break;
+ }
+
+ next_setpoint_index++;
+ }
+
+
+ /* lazily publish the setpoint only once available */
+ if (_triplet_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(mission_item_triplet), _triplet_pub, &_mission_item_triplet);
+
+ } else {
+ /* advertise and publish */
+ _triplet_pub = orb_advertise(ORB_ID(mission_item_triplet), &_mission_item_triplet);
+ }
+
+}
+
+static void usage()
+{
+ errx(1, "usage: navigator {start|stop|status|fence}");
+}
+
int navigator_main(int argc, char *argv[])
{
- if (argc < 1)
- errx(1, "usage: navigator {start|stop|status}");
+ if (argc < 2) {
+ usage();
+ }
if (!strcmp(argv[1], "start")) {
- if (navigator::g_navigator != nullptr)
+ if (navigator::g_navigator != nullptr) {
errx(1, "already running");
+ }
navigator::g_navigator = new Navigator;
- if (navigator::g_navigator == nullptr)
+ if (navigator::g_navigator == nullptr) {
errx(1, "alloc failed");
+ }
if (OK != navigator::g_navigator->start()) {
delete navigator::g_navigator;
@@ -578,27 +784,25 @@ int navigator_main(int argc, char *argv[])
err(1, "start failed");
}
- exit(0);
+ return 0;
}
- if (!strcmp(argv[1], "stop")) {
- if (navigator::g_navigator == nullptr)
- errx(1, "not running");
+ if (navigator::g_navigator == nullptr)
+ errx(1, "not running");
+ if (!strcmp(argv[1], "stop")) {
delete navigator::g_navigator;
navigator::g_navigator = nullptr;
- exit(0);
- }
- if (!strcmp(argv[1], "status")) {
- if (navigator::g_navigator) {
- errx(0, "running");
+ } else if (!strcmp(argv[1], "status")) {
+ navigator::g_navigator->status();
- } else {
- errx(1, "not running");
- }
+ } else if (!strcmp(argv[1], "fence")) {
+ navigator::g_navigator->fence_point(argc - 2, argv + 2);
+
+ } else {
+ usage();
}
- warnx("unrecognized command");
- return 1;
+ return 0;
}
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index 3514dca24..ecc1a3b3a 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -120,8 +120,8 @@ ORB_DEFINE(vehicle_bodyframe_speed_setpoint, struct vehicle_bodyframe_speed_setp
#include "topics/vehicle_global_position_setpoint.h"
ORB_DEFINE(vehicle_global_position_setpoint, struct vehicle_global_position_setpoint_s);
-#include "topics/vehicle_global_position_set_triplet.h"
-ORB_DEFINE(vehicle_global_position_set_triplet, struct vehicle_global_position_set_triplet_s);
+#include "topics/mission_item_triplet.h"
+ORB_DEFINE(mission_item_triplet, struct mission_item_triplet_s);
#include "topics/vehicle_global_velocity_setpoint.h"
ORB_DEFINE(vehicle_global_velocity_setpoint, struct vehicle_global_velocity_setpoint_s);
@@ -129,6 +129,9 @@ ORB_DEFINE(vehicle_global_velocity_setpoint, struct vehicle_global_velocity_setp
#include "topics/mission.h"
ORB_DEFINE(mission, struct mission_s);
+#include "topics/fence.h"
+ORB_DEFINE(fence, unsigned);
+
#include "topics/vehicle_attitude_setpoint.h"
ORB_DEFINE(vehicle_attitude_setpoint, struct vehicle_attitude_setpoint_s);
diff --git a/src/modules/uORB/topics/fence.h b/src/modules/uORB/topics/fence.h
new file mode 100644
index 000000000..6f16c51cf
--- /dev/null
+++ b/src/modules/uORB/topics/fence.h
@@ -0,0 +1,80 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Jean Cyr <jean.m.cyr@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 fence.h
+ * Definition of geofence.
+ */
+
+#ifndef TOPIC_FENCE_H_
+#define TOPIC_FENCE_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+#define GEOFENCE_MAX_VERTICES 16
+
+/**
+ * This is the position of a geofence vertex
+ *
+ */
+struct fence_vertex_s {
+ // Worst case float precision gives us 2 meter resolution at the equator
+ float lat; /**< latitude in degrees */
+ float lon; /**< longitude in degrees */
+};
+
+/**
+ * This is the position of a geofence
+ *
+ */
+struct fence_s {
+ unsigned count; /**< number of actual vertices */
+ struct fence_vertex_s vertices[GEOFENCE_MAX_VERTICES];
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(fence);
+
+#endif
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h
index 978a3383a..ec7835279 100644
--- a/src/modules/uORB/topics/mission.h
+++ b/src/modules/uORB/topics/mission.h
@@ -35,8 +35,8 @@
****************************************************************************/
/**
- * @file mission_item.h
- * Definition of one mission item.
+ * @file mission.h
+ * Definition of a mission consisting of mission items.
*/
#ifndef TOPIC_MISSION_H_
@@ -75,12 +75,10 @@ struct mission_item_s
float altitude; /**< altitude in meters */
float yaw; /**< in radians NED -PI..+PI */
float loiter_radius; /**< loiter radius in meters, 0 for a VTOL to hover */
- uint8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
+ int8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
enum NAV_CMD nav_cmd; /**< true if loitering is enabled */
- float param1;
- float param2;
- float param3;
- float param4;
+ float radius; /**< radius in which the mission is accepted as reached in meters */
+ float time_inside; /**< time that the MAV should stay inside the radius before advancing in milliseconds */
};
struct mission_s
diff --git a/src/modules/uORB/topics/vehicle_global_position_set_triplet.h b/src/modules/uORB/topics/mission_item_triplet.h
index 8516b263f..48553b0ac 100644
--- a/src/modules/uORB/topics/vehicle_global_position_set_triplet.h
+++ b/src/modules/uORB/topics/mission_item_triplet.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
* Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
@@ -35,18 +35,18 @@
****************************************************************************/
/**
- * @file vehicle_global_position_setpoint.h
+ * @file mission_item_triplet.h
* Definition of the global WGS84 position setpoint uORB topic.
*/
-#ifndef TOPIC_VEHICLE_GLOBAL_POSITION_SET_TRIPLET_H_
-#define TOPIC_VEHICLE_GLOBAL_POSITION_SET_TRIPLET_H_
+#ifndef TOPIC_MISSION_ITEM_TRIPLET_H_
+#define TOPIC_MISSION_ITEM_TRIPLET_H_
#include <stdint.h>
#include <stdbool.h>
#include "../uORB.h"
-#include "vehicle_global_position_setpoint.h"
+#include "mission.h"
/**
* @addtogroup topics
@@ -58,14 +58,15 @@
*
* This are the three next waypoints (or just the next two or one).
*/
-struct vehicle_global_position_set_triplet_s
+struct mission_item_triplet_s
{
- bool previous_valid; /**< flag indicating previous position is valid */
- bool next_valid; /**< flag indicating next position is valid */
+ bool previous_valid;
+ bool current_valid; /**< flag indicating previous mission item is valid */
+ bool next_valid; /**< flag indicating next mission item is valid */
- struct vehicle_global_position_setpoint_s previous;
- struct vehicle_global_position_setpoint_s current;
- struct vehicle_global_position_setpoint_s next;
+ struct mission_item_s previous;
+ struct mission_item_s current;
+ struct mission_item_s next;
};
/**
@@ -73,6 +74,6 @@ struct vehicle_global_position_set_triplet_s
*/
/* register this as object request broker structure */
-ORB_DECLARE(vehicle_global_position_set_triplet);
+ORB_DECLARE(mission_item_triplet);
#endif
diff --git a/src/systemcmds/tests/module.mk b/src/systemcmds/tests/module.mk
index 6729ce4ae..53c0e6b4f 100644
--- a/src/systemcmds/tests/module.mk
+++ b/src/systemcmds/tests/module.mk
@@ -24,6 +24,9 @@ SRCS = test_adc.c \
test_uart_loopback.c \
test_uart_send.c \
test_mixer.cpp \
+ test_dataman.c \
tests_file.c \
tests_main.c \
tests_param.c
+
+INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
diff --git a/src/systemcmds/tests/test_dataman.c b/src/systemcmds/tests/test_dataman.c
new file mode 100644
index 000000000..e33c5aceb
--- /dev/null
+++ b/src/systemcmds/tests/test_dataman.c
@@ -0,0 +1,179 @@
+/****************************************************************************
+ * px4/sensors/test_dataman.c
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include <drivers/drv_led.h>
+#include <systemlib/systemlib.h>
+#include <drivers/drv_hrt.h>
+#include <semaphore.h>
+
+
+#include "tests.h"
+
+#include "dataman/dataman.h"
+
+static sem_t *sems;
+
+static int
+task_main(int argc, char *argv[])
+{
+ char buffer[DM_MAX_DATA_SIZE];
+ hrt_abstime wstart, wend, rstart, rend;
+
+ warnx("Starting dataman test task %s", argv[1]);
+ /* try to read an invalid item */
+ int my_id = atoi(argv[1]);
+ /* try to read an invalid item */
+ if (dm_read(DM_KEY_NUM_KEYS, 0, buffer, sizeof(buffer)) >= 0) {
+ warnx("%d read an invalid item failed", my_id);
+ goto fail;
+ }
+ /* try to read an invalid index */
+ if (dm_read(DM_KEY_SAFE_POINTS, DM_KEY_SAFE_POINTS_MAX, buffer, sizeof(buffer)) >= 0) {
+ warnx("%d read an invalid index failed", my_id);
+ goto fail;
+ }
+ srand(hrt_absolute_time() ^ my_id);
+ unsigned hit = 0, miss = 0;
+ wstart = hrt_absolute_time();
+ for (unsigned i = 0; i < 256; i++) {
+ memset(buffer, my_id, sizeof(buffer));
+ buffer[1] = i;
+ unsigned hash = i ^ my_id;
+ unsigned len = (hash & 63) + 2;
+ if (dm_write(DM_KEY_WAY_POINTS, hash, DM_PERSIST_IN_FLIGHT_RESET, buffer, len) != len) {
+ warnx("%d write failed, index %d, length %d", my_id, hash, len);
+ goto fail;
+ }
+ usleep(rand() & ((64 * 1024) - 1));
+ }
+ rstart = hrt_absolute_time();
+ wend = rstart;
+
+ for (unsigned i = 0; i < 256; i++) {
+ unsigned hash = i ^ my_id;
+ unsigned len2, len = (hash & 63) + 2;
+ if ((len2 = dm_read(DM_KEY_WAY_POINTS, hash, buffer, sizeof(buffer))) < 2) {
+ warnx("%d read failed length test, index %d", my_id, hash);
+ goto fail;
+ }
+ if (buffer[0] == my_id) {
+ hit++;
+ if (len2 != len) {
+ warnx("%d read failed length test, index %d, wanted %d, got %d", my_id, hash, len, len2);
+ goto fail;
+ }
+ if (buffer[1] != i) {
+ warnx("%d data verification failed, index %d, wanted %d, got %d", my_id, hash, my_id, buffer[1]);
+ goto fail;
+ }
+ }
+ else
+ miss++;
+ }
+ rend = hrt_absolute_time();
+ warnx("Test %d pass, hit %d, miss %d, io time read %llums. write %llums.",
+ my_id, hit, miss, (rend - rstart) / 256000, (wend - wstart) / 256000);
+ sem_post(sems + my_id);
+ return 0;
+fail:
+ warnx("Test %d fail, buffer %02x %02x %02x %02x %02x %02x",
+ my_id, buffer[0], buffer[1], buffer[2], buffer[3], buffer[4], buffer[5]);
+ sem_post(sems + my_id);
+ return -1;
+}
+
+int test_dataman(int argc, char *argv[])
+{
+ int i, num_tasks = 4;
+ char buffer[DM_MAX_DATA_SIZE];
+
+ if (argc > 1)
+ num_tasks = atoi(argv[1]);
+
+ sems = (sem_t *)malloc(num_tasks * sizeof(sem_t));
+ warnx("Running %d tasks", num_tasks);
+ for (i = 0; i < num_tasks; i++) {
+ int task;
+ char a[16];
+ sprintf(a, "%d", i);
+ const char *av[2];
+ av[0] = a;
+ av[1] = 0;
+ sem_init(sems + i, 1, 0);
+ /* start the task */
+ if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2048, task_main, av)) <= 0) {
+ warn("task start failed");
+ }
+ }
+ for (i = 0; i < num_tasks; i++) {
+ sem_wait(sems + i);
+ sem_destroy(sems + i);
+ }
+ free(sems);
+ dm_restart(DM_INIT_REASON_IN_FLIGHT);
+ for (i = 0; i < 256; i++) {
+ if (dm_read(DM_KEY_WAY_POINTS, i, buffer, sizeof(buffer)) != 0)
+ break;
+ }
+ if (i >= 256) {
+ warnx("Restart in-flight failed");
+ return -1;
+
+ }
+ dm_restart(DM_INIT_REASON_POWER_ON);
+ for (i = 0; i < 256; i++) {
+ if (dm_read(DM_KEY_WAY_POINTS, i, buffer, sizeof(buffer)) != 0) {
+ warnx("Restart power-on failed");
+ return -1;
+ }
+ }
+ return 0;
+}
diff --git a/src/systemcmds/tests/tests.h b/src/systemcmds/tests/tests.h
index c483108cf..4a5eaa0c5 100644
--- a/src/systemcmds/tests/tests.h
+++ b/src/systemcmds/tests/tests.h
@@ -101,6 +101,7 @@ extern int test_param(int argc, char *argv[]);
extern int test_bson(int argc, char *argv[]);
extern int test_file(int argc, char *argv[]);
extern int test_mixer(int argc, char *argv[]);
+extern int test_dataman(int argc, char *argv[]);
__END_DECLS
diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c
index 9eb9c632e..9b1cfb1fe 100644
--- a/src/systemcmds/tests/tests_main.c
+++ b/src/systemcmds/tests/tests_main.c
@@ -112,6 +112,7 @@ const struct {
{"file", test_file, 0},
{"mixer", test_mixer, OPT_NOJIGTEST | OPT_NOALLTEST},
{"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST},
+ {"dataman", test_dataman, OPT_NOALLTEST},
{NULL, NULL, 0}
};