navigator/geofence: move more functions to geofence class (WIP)

This commit is contained in:
Thomas Gubler 2014-01-02 15:01:08 +01:00
parent dca6d97a52
commit 429a11a21d
5 changed files with 138 additions and 127 deletions

View File

@ -39,10 +39,14 @@
#include "geofence.h" #include "geofence.h"
#include <uORB/topics/vehicle_global_position.h> #include <uORB/topics/vehicle_global_position.h>
#include <string.h>
#include <dataman/dataman.h>
#include <systemlib/err.h>
#include <stdlib.h>
Geofence::Geofence() Geofence::Geofence() : _fence_pub(-1)
{ {
memset(&_fence, 0, sizeof(_fence));
} }
Geofence::~Geofence() Geofence::~Geofence()
@ -71,3 +75,92 @@ bool Geofence::inside(const struct vehicle_global_position_s *vehicle)
c = !c; c = !c;
return c; return c;
} }
bool
Geofence::load(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 (valid())
memcpy(&_fence, &temp_fence, sizeof(_fence));
else
warnx("Invalid fence file, ignored!");
return _fence.count != 0;
}
bool
Geofence::valid()
{
// 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;
}
void
Geofence::addPoint(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);
publishFence(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)
publishFence((unsigned)ix + 1);
return;
}
errx(1, "can't store fence point");
}
void
Geofence::publishFence(unsigned vertices)
{
if (_fence_pub == -1)
_fence_pub = orb_advertise(ORB_ID(fence), &vertices);
else
orb_publish(ORB_ID(fence), _fence_pub, &vertices);
}

View File

@ -45,6 +45,7 @@
class Geofence { class Geofence {
private: private:
struct fence_s _fence; struct fence_s _fence;
orb_advert_t _fence_pub; /**< publish fence topic */
public: public:
Geofence(); Geofence();
~Geofence(); ~Geofence();
@ -58,6 +59,21 @@ public:
* @return true: craft is inside fence, false:craft is outside fence * @return true: craft is inside fence, false:craft is outside fence
*/ */
bool inside(const struct vehicle_global_position_s *craft); bool inside(const struct vehicle_global_position_s *craft);
/**
* Load fence parameters.
*/
bool load(unsigned vertices);
bool valid();
/**
* Specify fence vertex position.
*/
void addPoint(int argc, char *argv[]);
void publishFence(unsigned vertices);
}; };

View File

@ -62,7 +62,7 @@ MissionFeasibilityChecker::MissionFeasibilityChecker() : _mavlink_fd(-1), _capab
} }
bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, const struct fence_s &fence) bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
{ {
/* Init if not done yet */ /* Init if not done yet */
init(); init();
@ -75,27 +75,27 @@ bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_
if (isRotarywing) if (isRotarywing)
return checkMissionFeasibleRotarywing(dm_current, nMissionItems, fence); return checkMissionFeasibleRotarywing(dm_current, nMissionItems, geofence);
else else
return checkMissionFeasibleFixedwing(dm_current, nMissionItems, fence); return checkMissionFeasibleFixedwing(dm_current, nMissionItems, geofence);
} }
bool MissionFeasibilityChecker::checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, const struct fence_s &fence) bool MissionFeasibilityChecker::checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
{ {
return checkGeofence(dm_current, nMissionItems, fence); return checkGeofence(dm_current, nMissionItems, geofence);
} }
bool MissionFeasibilityChecker::checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, const struct fence_s &fence) bool MissionFeasibilityChecker::checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
{ {
/* Update fixed wing navigation capabilites */ /* Update fixed wing navigation capabilites */
updateNavigationCapabilities(); updateNavigationCapabilities();
// warnx("_nav_caps.landing_slope_angle_rad %.4f, _nav_caps.landing_horizontal_slope_displacement %.4f", _nav_caps.landing_slope_angle_rad, _nav_caps.landing_horizontal_slope_displacement); // warnx("_nav_caps.landing_slope_angle_rad %.4f, _nav_caps.landing_horizontal_slope_displacement %.4f", _nav_caps.landing_slope_angle_rad, _nav_caps.landing_horizontal_slope_displacement);
return (checkFixedWingLanding(dm_current, nMissionItems) && checkGeofence(dm_current, nMissionItems, fence)); return (checkFixedWingLanding(dm_current, nMissionItems) && checkGeofence(dm_current, nMissionItems, geofence));
} }
bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMissionItems, const struct fence_s &fence) bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
{ {
//xxx: check geofence //xxx: check geofence
return true; return true;

View File

@ -43,6 +43,7 @@
#include <uORB/topics/mission.h> #include <uORB/topics/mission.h>
#include <uORB/topics/navigation_capabilities.h> #include <uORB/topics/navigation_capabilities.h>
#include <dataman/dataman.h> #include <dataman/dataman.h>
#include "geofence.h"
class MissionFeasibilityChecker class MissionFeasibilityChecker
@ -57,15 +58,15 @@ private:
void init(); void init();
/* Checks for all airframes */ /* Checks for all airframes */
bool checkGeofence(dm_item_t dm_current, size_t nMissionItems, const struct fence_s &fence); bool checkGeofence(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
/* Checks specific to fixedwing airframes */ /* Checks specific to fixedwing airframes */
bool checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, const struct fence_s &fence); bool checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
bool checkFixedWingLanding(dm_item_t dm_current, size_t nMissionItems); bool checkFixedWingLanding(dm_item_t dm_current, size_t nMissionItems);
void updateNavigationCapabilities(); void updateNavigationCapabilities();
/* Checks specific to rotarywing airframes */ /* Checks specific to rotarywing airframes */
bool checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, const struct fence_s &fence); bool checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
public: public:
MissionFeasibilityChecker(); MissionFeasibilityChecker();
@ -74,7 +75,7 @@ public:
/* /*
* Returns true if mission is feasible and false otherwise * Returns true if mission is feasible and false otherwise
*/ */
bool checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, const struct fence_s &fence); bool checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
}; };

View File

@ -120,14 +120,9 @@ public:
void status(); void status();
/** /**
* Load fence parameters. * Add point to geofence
*/ */
bool load_fence(unsigned vertices); void add_fence_point(int argc, char *argv[]);
/**
* Specify fence vertex position.
*/
void fence_point(int argc, char *argv[]);
private: private:
@ -145,7 +140,6 @@ private:
int _capabilities_sub; /**< notification of vehicle capabilities updates */ int _capabilities_sub; /**< notification of vehicle capabilities updates */
orb_advert_t _triplet_pub; /**< publish position setpoint triplet */ orb_advert_t _triplet_pub; /**< publish position setpoint triplet */
orb_advert_t _fence_pub; /**< publish fence topic */
orb_advert_t _mission_result_pub; /**< publish mission result topic */ orb_advert_t _mission_result_pub; /**< publish mission result topic */
orb_advert_t _control_mode_pub; /**< publish vehicle control mode topic */ orb_advert_t _control_mode_pub; /**< publish vehicle control mode topic */
@ -158,8 +152,7 @@ private:
perf_counter_t _loop_perf; /**< loop performance counter */ perf_counter_t _loop_perf; /**< loop performance counter */
Geofence geofence; Geofence _geofence;
struct fence_s _fence; /**< storage for fence vertices */
bool _fence_valid; /**< flag if fence is valid */ bool _fence_valid; /**< flag if fence is valid */
bool _inside_fence; /**< vehicle is inside fence */ bool _inside_fence; /**< vehicle is inside fence */
@ -252,12 +245,8 @@ private:
*/ */
void task_main() __attribute__((noreturn)); void task_main() __attribute__((noreturn));
void publish_fence(unsigned vertices);
void publish_safepoints(unsigned points); void publish_safepoints(unsigned points);
bool fence_valid(const struct fence_s &fence);
/** /**
* Functions that are triggered when a new state is entered. * Functions that are triggered when a new state is entered.
*/ */
@ -347,7 +336,6 @@ Navigator::Navigator() :
/* publications */ /* publications */
_triplet_pub(-1), _triplet_pub(-1),
_fence_pub(-1),
_mission_result_pub(-1), _mission_result_pub(-1),
_control_mode_pub(-1), _control_mode_pub(-1),
@ -365,8 +353,6 @@ Navigator::Navigator() :
_time_first_inside_orbit(0), _time_first_inside_orbit(0),
_set_nav_state_timestamp(0) _set_nav_state_timestamp(0)
{ {
memset(&_fence, 0, sizeof(_fence));
_parameter_handles.min_altitude = param_find("NAV_MIN_ALT"); _parameter_handles.min_altitude = param_find("NAV_MIN_ALT");
_parameter_handles.loiter_radius = param_find("NAV_LOITER_RAD"); _parameter_handles.loiter_radius = param_find("NAV_LOITER_RAD");
_parameter_handles.onboard_mission_enabled = param_find("NAV_ONB_MIS_EN"); _parameter_handles.onboard_mission_enabled = param_find("NAV_ONB_MIS_EN");
@ -458,7 +444,7 @@ Navigator::offboard_mission_update(bool isrotaryWing)
} else { } else {
dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1; dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
} }
missionFeasiblityChecker.checkMissionFeasible(isrotaryWing, dm_current, (size_t)offboard_mission.count, _fence); missionFeasiblityChecker.checkMissionFeasible(isrotaryWing, dm_current, (size_t)offboard_mission.count, _geofence);
_mission.set_offboard_dataman_id(offboard_mission.dataman_id); _mission.set_offboard_dataman_id(offboard_mission.dataman_id);
_mission.set_current_offboard_mission_index(offboard_mission.current_index); _mission.set_current_offboard_mission_index(offboard_mission.current_index);
@ -511,7 +497,7 @@ Navigator::task_main()
mavlink_log_info(_mavlink_fd, "[navigator] started"); mavlink_log_info(_mavlink_fd, "[navigator] started");
_fence_valid = load_fence(GEOFENCE_MAX_VERTICES); _fence_valid = _geofence.load(GEOFENCE_MAX_VERTICES);
/* /*
* do subscriptions * do subscriptions
@ -782,9 +768,9 @@ Navigator::status()
} }
if (_fence_valid) { if (_fence_valid) {
warnx("Geofence is valid"); warnx("Geofence is valid");
warnx("Vertex longitude latitude"); // warnx("Vertex longitude latitude");
for (unsigned i = 0; i < _fence.count; i++) // 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); // warnx("%6u %9.5f %8.5f", i, (double)_fence.vertices[i].lon, (double)_fence.vertices[i].lat);
} else { } else {
warnx("Geofence not set"); warnx("Geofence not set");
} }
@ -808,96 +794,6 @@ Navigator::status()
} }
} }
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");
}
StateTable::Tran const Navigator::myTable[NAV_STATE_MAX][MAX_EVENT] = { StateTable::Tran const Navigator::myTable[NAV_STATE_MAX][MAX_EVENT] = {
{ {
/* STATE_NONE */ /* STATE_NONE */
@ -1351,6 +1247,11 @@ bool Navigator::cmp_mission_item_equivalent(const struct mission_item_s a, const
} }
} }
void Navigator::add_fence_point(int argc, char *argv[])
{
_geofence.addPoint(argc, argv);
}
static void usage() static void usage()
{ {
@ -1395,7 +1296,7 @@ int navigator_main(int argc, char *argv[])
navigator::g_navigator->status(); navigator::g_navigator->status();
} else if (!strcmp(argv[1], "fence")) { } else if (!strcmp(argv[1], "fence")) {
navigator::g_navigator->fence_point(argc - 2, argv + 2); navigator::g_navigator->add_fence_point(argc - 2, argv + 2);
} else { } else {
usage(); usage();