forked from Archive/PX4-Autopilot
topics: move geofence status to its own topic
This commit is contained in:
parent
19d5383c56
commit
2a09473e5f
|
@ -81,6 +81,7 @@
|
||||||
#include <uORB/topics/system_power.h>
|
#include <uORB/topics/system_power.h>
|
||||||
#include <uORB/topics/mission.h>
|
#include <uORB/topics/mission.h>
|
||||||
#include <uORB/topics/mission_result.h>
|
#include <uORB/topics/mission_result.h>
|
||||||
|
#include <uORB/topics/geofence_result.h>
|
||||||
#include <uORB/topics/telemetry_status.h>
|
#include <uORB/topics/telemetry_status.h>
|
||||||
#include <uORB/topics/vtol_vehicle_status.h>
|
#include <uORB/topics/vtol_vehicle_status.h>
|
||||||
|
|
||||||
|
@ -926,6 +927,11 @@ int commander_thread_main(int argc, char *argv[])
|
||||||
struct mission_result_s mission_result;
|
struct mission_result_s mission_result;
|
||||||
memset(&mission_result, 0, sizeof(mission_result));
|
memset(&mission_result, 0, sizeof(mission_result));
|
||||||
|
|
||||||
|
/* Subscribe to geofence result topic */
|
||||||
|
int geofence_result_sub = orb_subscribe(ORB_ID(geofence_result));
|
||||||
|
struct geofence_result_s geofence_result;
|
||||||
|
memset(&geofence_result, 0, sizeof(geofence_result));
|
||||||
|
|
||||||
/* Subscribe to manual control data */
|
/* Subscribe to manual control data */
|
||||||
int sp_man_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
|
int sp_man_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
|
||||||
struct manual_control_setpoint_s sp_man;
|
struct manual_control_setpoint_s sp_man;
|
||||||
|
@ -1545,9 +1551,17 @@ int commander_thread_main(int argc, char *argv[])
|
||||||
|
|
||||||
if (updated) {
|
if (updated) {
|
||||||
orb_copy(ORB_ID(mission_result), mission_result_sub, &mission_result);
|
orb_copy(ORB_ID(mission_result), mission_result_sub, &mission_result);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* start geofence result check */
|
||||||
|
orb_check(geofence_result_sub, &updated);
|
||||||
|
|
||||||
|
if (updated) {
|
||||||
|
orb_copy(ORB_ID(geofence_result), geofence_result_sub, &geofence_result);
|
||||||
|
}
|
||||||
|
|
||||||
/* Check for geofence violation */
|
/* Check for geofence violation */
|
||||||
if (armed.armed && (mission_result.geofence_violated || mission_result.flight_termination)) {
|
if (armed.armed && (geofence_result.geofence_violated || mission_result.flight_termination)) {
|
||||||
//XXX: make this configurable to select different actions (e.g. navigation modes)
|
//XXX: make this configurable to select different actions (e.g. navigation modes)
|
||||||
/* this will only trigger if geofence is activated via param and a geofence file is present, also there is a circuit breaker to disable the actual flight termination in the px4io driver */
|
/* this will only trigger if geofence is activated via param and a geofence file is present, also there is a circuit breaker to disable the actual flight termination in the px4io driver */
|
||||||
armed.force_failsafe = true;
|
armed.force_failsafe = true;
|
||||||
|
@ -1564,7 +1578,6 @@ int commander_thread_main(int argc, char *argv[])
|
||||||
mavlink_log_critical(mavlink_fd, "GF violation: flight termination");
|
mavlink_log_critical(mavlink_fd, "GF violation: flight termination");
|
||||||
}
|
}
|
||||||
} // no reset is done here on purpose, on geofence violation we want to stay in flighttermination
|
} // no reset is done here on purpose, on geofence violation we want to stay in flighttermination
|
||||||
}
|
|
||||||
|
|
||||||
/* RC input check */
|
/* RC input check */
|
||||||
if (!status.rc_input_blocked && sp_man.timestamp != 0 &&
|
if (!status.rc_input_blocked && sp_man.timestamp != 0 &&
|
||||||
|
|
|
@ -54,6 +54,7 @@
|
||||||
#include <uORB/topics/vehicle_gps_position.h>
|
#include <uORB/topics/vehicle_gps_position.h>
|
||||||
#include <uORB/topics/parameter_update.h>
|
#include <uORB/topics/parameter_update.h>
|
||||||
#include <uORB/topics/mission_result.h>
|
#include <uORB/topics/mission_result.h>
|
||||||
|
#include <uORB/topics/geofence_result.h>
|
||||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||||
|
|
||||||
#include "navigator_mode.h"
|
#include "navigator_mode.h"
|
||||||
|
@ -111,6 +112,11 @@ public:
|
||||||
*/
|
*/
|
||||||
void publish_mission_result();
|
void publish_mission_result();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Publish the geofence result
|
||||||
|
*/
|
||||||
|
void publish_geofence_result();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Publish the attitude sp, only to be used in very special modes when position control is deactivated
|
* Publish the attitude sp, only to be used in very special modes when position control is deactivated
|
||||||
* Example: mode that is triggered on gps failure
|
* Example: mode that is triggered on gps failure
|
||||||
|
@ -134,6 +140,7 @@ public:
|
||||||
struct home_position_s* get_home_position() { return &_home_pos; }
|
struct home_position_s* get_home_position() { return &_home_pos; }
|
||||||
struct position_setpoint_triplet_s* get_position_setpoint_triplet() { return &_pos_sp_triplet; }
|
struct position_setpoint_triplet_s* get_position_setpoint_triplet() { return &_pos_sp_triplet; }
|
||||||
struct mission_result_s* get_mission_result() { return &_mission_result; }
|
struct mission_result_s* get_mission_result() { return &_mission_result; }
|
||||||
|
struct geofence_result_s* get_geofence_result() { return &_geofence_result; }
|
||||||
struct vehicle_attitude_setpoint_s* get_att_sp() { return &_att_sp; }
|
struct vehicle_attitude_setpoint_s* get_att_sp() { return &_att_sp; }
|
||||||
|
|
||||||
int get_onboard_mission_sub() { return _onboard_mission_sub; }
|
int get_onboard_mission_sub() { return _onboard_mission_sub; }
|
||||||
|
@ -164,6 +171,7 @@ private:
|
||||||
|
|
||||||
orb_advert_t _pos_sp_triplet_pub; /**< publish position setpoint triplet */
|
orb_advert_t _pos_sp_triplet_pub; /**< publish position setpoint triplet */
|
||||||
orb_advert_t _mission_result_pub;
|
orb_advert_t _mission_result_pub;
|
||||||
|
orb_advert_t _geofence_result_pub;
|
||||||
orb_advert_t _att_sp_pub; /**< publish att sp
|
orb_advert_t _att_sp_pub; /**< publish att sp
|
||||||
used only in very special failsafe modes
|
used only in very special failsafe modes
|
||||||
when pos control is deactivated */
|
when pos control is deactivated */
|
||||||
|
@ -179,6 +187,7 @@ private:
|
||||||
position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of position setpoints */
|
position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of position setpoints */
|
||||||
|
|
||||||
mission_result_s _mission_result;
|
mission_result_s _mission_result;
|
||||||
|
geofence_result_s _geofence_result;
|
||||||
vehicle_attitude_setpoint_s _att_sp;
|
vehicle_attitude_setpoint_s _att_sp;
|
||||||
|
|
||||||
bool _mission_item_valid; /**< flags if the current mission item is valid */
|
bool _mission_item_valid; /**< flags if the current mission item is valid */
|
||||||
|
|
|
@ -110,6 +110,7 @@ Navigator::Navigator() :
|
||||||
_param_update_sub(-1),
|
_param_update_sub(-1),
|
||||||
_pos_sp_triplet_pub(-1),
|
_pos_sp_triplet_pub(-1),
|
||||||
_mission_result_pub(-1),
|
_mission_result_pub(-1),
|
||||||
|
_geofence_result_pub(-1),
|
||||||
_att_sp_pub(-1),
|
_att_sp_pub(-1),
|
||||||
_vstatus{},
|
_vstatus{},
|
||||||
_control_mode{},
|
_control_mode{},
|
||||||
|
@ -398,8 +399,8 @@ Navigator::task_main()
|
||||||
have_geofence_position_data = false;
|
have_geofence_position_data = false;
|
||||||
if (!inside) {
|
if (!inside) {
|
||||||
/* inform other apps via the mission result */
|
/* inform other apps via the mission result */
|
||||||
_mission_result.geofence_violated = true;
|
_geofence_result.geofence_violated = true;
|
||||||
publish_mission_result();
|
publish_geofence_result();
|
||||||
|
|
||||||
/* Issue a warning about the geofence violation once */
|
/* Issue a warning about the geofence violation once */
|
||||||
if (!_geofence_violation_warning_sent) {
|
if (!_geofence_violation_warning_sent) {
|
||||||
|
@ -408,8 +409,8 @@ Navigator::task_main()
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
/* inform other apps via the mission result */
|
/* inform other apps via the mission result */
|
||||||
_mission_result.geofence_violated = false;
|
_geofence_result.geofence_violated = false;
|
||||||
publish_mission_result();
|
publish_geofence_result();
|
||||||
/* Reset the _geofence_violation_warning_sent field */
|
/* Reset the _geofence_violation_warning_sent field */
|
||||||
_geofence_violation_warning_sent = false;
|
_geofence_violation_warning_sent = false;
|
||||||
}
|
}
|
||||||
|
@ -641,6 +642,21 @@ Navigator::publish_mission_result()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Navigator::publish_geofence_result()
|
||||||
|
{
|
||||||
|
|
||||||
|
/* lazily publish the geofence result only once available */
|
||||||
|
if (_geofence_result_pub > 0) {
|
||||||
|
/* publish mission result */
|
||||||
|
orb_publish(ORB_ID(geofence_result), _geofence_result_pub, &_geofence_result);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
/* advertise and publish */
|
||||||
|
_geofence_result_pub = orb_advertise(ORB_ID(geofence_result), &_geofence_result);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Navigator::publish_att_sp()
|
Navigator::publish_att_sp()
|
||||||
{
|
{
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
*
|
*
|
||||||
* Copyright (C) 2012, 2013 PX4 Development Team. All rights reserved.
|
* Copyright (C) 2012-2014 PX4 Development Team. All rights reserved.
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
@ -148,6 +148,9 @@ ORB_DEFINE(onboard_mission, struct mission_s);
|
||||||
#include "topics/mission_result.h"
|
#include "topics/mission_result.h"
|
||||||
ORB_DEFINE(mission_result, struct mission_result_s);
|
ORB_DEFINE(mission_result, struct mission_result_s);
|
||||||
|
|
||||||
|
#include "topics/geofence_result.h"
|
||||||
|
ORB_DEFINE(geofence_result, struct geofence_result_s);
|
||||||
|
|
||||||
#include "topics/fence.h"
|
#include "topics/fence.h"
|
||||||
ORB_DEFINE(fence, unsigned);
|
ORB_DEFINE(fence, unsigned);
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,65 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2014 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file geofence_result.h
|
||||||
|
* Status of the plance concerning the geofence
|
||||||
|
*
|
||||||
|
* @author Ban Siesta <bansiesta@gmail.com>
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef TOPIC_GEOFENCE_RESULT_H
|
||||||
|
#define TOPIC_GEOFENCE_RESULT_H
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include "../uORB.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @addtogroup topics
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
struct geofence_result_s
|
||||||
|
{
|
||||||
|
bool geofence_violated; /**< true if the geofence is violated */
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* register this as object request broker structure */
|
||||||
|
ORB_DECLARE(geofence_result);
|
||||||
|
|
||||||
|
#endif
|
|
@ -1,9 +1,6 @@
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
*
|
*
|
||||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
* Copyright (C) 2012-2014 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>
|
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
@ -37,6 +34,11 @@
|
||||||
/**
|
/**
|
||||||
* @file mission_result.h
|
* @file mission_result.h
|
||||||
* Mission results that navigator needs to pass on to commander and mavlink.
|
* Mission results that navigator needs to pass on to commander and mavlink.
|
||||||
|
*
|
||||||
|
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||||
|
* @author Julian Oes <joes@student.ethz.ch>
|
||||||
|
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||||
|
* @author Ban Siesta <bansiesta@gmail.com>
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef TOPIC_MISSION_RESULT_H
|
#ifndef TOPIC_MISSION_RESULT_H
|
||||||
|
@ -58,7 +60,6 @@ struct mission_result_s
|
||||||
bool reached; /**< true if mission has been reached */
|
bool reached; /**< true if mission has been reached */
|
||||||
bool finished; /**< true if mission has been completed */
|
bool finished; /**< true if mission has been completed */
|
||||||
bool stay_in_failsafe; /**< true if the commander should not switch out of the failsafe mode*/
|
bool stay_in_failsafe; /**< true if the commander should not switch out of the failsafe mode*/
|
||||||
bool geofence_violated; /**< true if the geofence is violated */
|
|
||||||
bool flight_termination; /**< true if the navigator demands a flight termination from the commander app */
|
bool flight_termination; /**< true if the navigator demands a flight termination from the commander app */
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue