mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 09:28:58 +00:00
generic position controller status/feedback message
This commit is contained in:
@@ -46,26 +46,24 @@
|
||||
#include "navigator.h"
|
||||
|
||||
#include <cfloat>
|
||||
#include <sys/ioctl.h>
|
||||
#include <sys/stat.h>
|
||||
#include <sys/types.h>
|
||||
|
||||
#include <dataman/dataman.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <lib/ecl/geo/geo.h>
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <lib/mathlib/mathlib.h>
|
||||
#include <px4_config.h>
|
||||
#include <px4_defines.h>
|
||||
#include <px4_posix.h>
|
||||
#include <px4_tasks.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
#include <uORB/topics/fw_pos_ctrl_status.h>
|
||||
#include <uORB/topics/home_position.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
#include <uORB/topics/position_controller_landing_status.h>
|
||||
#include <uORB/topics/transponder_report.h>
|
||||
#include <uORB/topics/vehicle_command.h>
|
||||
#include <uORB/topics/vehicle_command_ack.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/transponder_report.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
/**
|
||||
@@ -77,6 +75,8 @@ extern "C" __EXPORT int navigator_main(int argc, char *argv[]);
|
||||
|
||||
#define GEOFENCE_CHECK_INTERVAL 200000
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
namespace navigator
|
||||
{
|
||||
Navigator *g_navigator;
|
||||
@@ -141,17 +141,6 @@ Navigator::home_position_update(bool force)
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Navigator::fw_pos_ctrl_status_update(bool force)
|
||||
{
|
||||
bool updated = false;
|
||||
orb_check(_fw_pos_ctrl_status_sub, &updated);
|
||||
|
||||
if (updated || force) {
|
||||
orb_copy(ORB_ID(fw_pos_ctrl_status), _fw_pos_ctrl_status_sub, &_fw_pos_ctrl_status);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Navigator::vehicle_status_update()
|
||||
{
|
||||
@@ -193,7 +182,7 @@ Navigator::run()
|
||||
_global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
|
||||
_local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
|
||||
_gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
|
||||
_fw_pos_ctrl_status_sub = orb_subscribe(ORB_ID(fw_pos_ctrl_status));
|
||||
_pos_ctrl_landing_status_sub = orb_subscribe(ORB_ID(position_controller_landing_status));
|
||||
_vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
|
||||
_land_detected_sub = orb_subscribe(ORB_ID(vehicle_land_detected));
|
||||
_home_pos_sub = orb_subscribe(ORB_ID(home_position));
|
||||
@@ -209,7 +198,6 @@ Navigator::run()
|
||||
local_position_update();
|
||||
gps_position_update();
|
||||
home_position_update(true);
|
||||
fw_pos_ctrl_status_update(true);
|
||||
params_update();
|
||||
|
||||
/* wakeup source(s) */
|
||||
@@ -293,11 +281,7 @@ Navigator::run()
|
||||
}
|
||||
|
||||
/* navigation capabilities updated */
|
||||
orb_check(_fw_pos_ctrl_status_sub, &updated);
|
||||
|
||||
if (updated) {
|
||||
fw_pos_ctrl_status_update();
|
||||
}
|
||||
_position_controller_status_sub.update();
|
||||
|
||||
/* home position updated */
|
||||
orb_check(_home_pos_sub, &updated);
|
||||
@@ -762,14 +746,11 @@ Navigator::run()
|
||||
}
|
||||
|
||||
if (_pos_sp_triplet_updated) {
|
||||
_pos_sp_triplet.timestamp = hrt_absolute_time();
|
||||
publish_position_setpoint_triplet();
|
||||
_pos_sp_triplet_updated = false;
|
||||
}
|
||||
|
||||
if (_mission_result_updated) {
|
||||
publish_mission_result();
|
||||
_mission_result_updated = false;
|
||||
}
|
||||
|
||||
perf_end(_loop_perf);
|
||||
@@ -778,7 +759,7 @@ Navigator::run()
|
||||
orb_unsubscribe(_global_pos_sub);
|
||||
orb_unsubscribe(_local_pos_sub);
|
||||
orb_unsubscribe(_gps_pos_sub);
|
||||
orb_unsubscribe(_fw_pos_ctrl_status_sub);
|
||||
orb_unsubscribe(_pos_ctrl_landing_status_sub);
|
||||
orb_unsubscribe(_vstatus_sub);
|
||||
orb_unsubscribe(_land_detected_sub);
|
||||
orb_unsubscribe(_home_pos_sub);
|
||||
@@ -827,11 +808,13 @@ Navigator::print_status()
|
||||
void
|
||||
Navigator::publish_position_setpoint_triplet()
|
||||
{
|
||||
/* do not publish an empty triplet */
|
||||
// do not publish an invalid setpoint
|
||||
if (!_pos_sp_triplet.current.valid) {
|
||||
return;
|
||||
}
|
||||
|
||||
_pos_sp_triplet.timestamp = hrt_absolute_time();
|
||||
|
||||
/* lazily publish the position setpoint triplet only once available */
|
||||
if (_pos_sp_triplet_pub != nullptr) {
|
||||
orb_publish(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_pub, &_pos_sp_triplet);
|
||||
@@ -839,6 +822,8 @@ Navigator::publish_position_setpoint_triplet()
|
||||
} else {
|
||||
_pos_sp_triplet_pub = orb_advertise(ORB_ID(position_setpoint_triplet), &_pos_sp_triplet);
|
||||
}
|
||||
|
||||
_pos_sp_triplet_updated = false;
|
||||
}
|
||||
|
||||
float
|
||||
@@ -949,10 +934,11 @@ Navigator::get_acceptance_radius(float mission_item_radius)
|
||||
// when in fixed wing mode
|
||||
// this might need locking against a commanded transition
|
||||
// so that a stale _vstatus doesn't trigger an accepted mission item.
|
||||
if (!_vstatus.is_rotary_wing && !_vstatus.in_transition_mode) {
|
||||
if ((hrt_elapsed_time(&_fw_pos_ctrl_status.timestamp) < 5000000) && (_fw_pos_ctrl_status.turn_distance > radius)) {
|
||||
radius = _fw_pos_ctrl_status.turn_distance;
|
||||
}
|
||||
|
||||
const position_controller_status_s &pos_ctrl_status = _position_controller_status_sub.get();
|
||||
|
||||
if ((pos_ctrl_status.timestamp > _pos_sp_triplet.timestamp) && pos_ctrl_status.acceptance_radius > radius) {
|
||||
radius = pos_ctrl_status.acceptance_radius;
|
||||
}
|
||||
|
||||
return radius;
|
||||
@@ -1114,15 +1100,24 @@ void Navigator::check_traffic()
|
||||
bool
|
||||
Navigator::abort_landing()
|
||||
{
|
||||
// only abort if currently landing and position controller status updated
|
||||
bool should_abort = false;
|
||||
|
||||
if (!_vstatus.is_rotary_wing && !_vstatus.in_transition_mode) {
|
||||
if (hrt_elapsed_time(&_fw_pos_ctrl_status.timestamp) < 1000000) {
|
||||
if (_pos_sp_triplet.current.valid
|
||||
&& _pos_sp_triplet.current.type == position_setpoint_s::SETPOINT_TYPE_LAND) {
|
||||
|
||||
if (get_position_setpoint_triplet()->current.valid
|
||||
&& get_position_setpoint_triplet()->current.type == position_setpoint_s::SETPOINT_TYPE_LAND) {
|
||||
bool updated = false;
|
||||
|
||||
should_abort = _fw_pos_ctrl_status.abort_landing;
|
||||
orb_check(_pos_ctrl_landing_status_sub, &updated);
|
||||
|
||||
if (updated) {
|
||||
position_controller_landing_status_s landing_status = {};
|
||||
|
||||
// landing status from position controller must be newer than navigator's last position setpoint
|
||||
if (orb_copy(ORB_ID(position_controller_landing_status), _pos_ctrl_landing_status_sub, &landing_status) == PX4_OK) {
|
||||
if (landing_status.timestamp > _pos_sp_triplet.timestamp) {
|
||||
should_abort = landing_status.abort_landing;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1214,6 +1209,8 @@ Navigator::publish_mission_result()
|
||||
_mission_result.item_do_jump_changed = false;
|
||||
_mission_result.item_changed_index = 0;
|
||||
_mission_result.item_do_jump_remaining = 0;
|
||||
|
||||
_mission_result_updated = false;
|
||||
}
|
||||
|
||||
void
|
||||
|
||||
Reference in New Issue
Block a user