PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <navigator.h>
Public Member Functions | |
Navigator () | |
~Navigator () override | |
Navigator (const Navigator &)=delete | |
Navigator | operator= (const Navigator &)=delete |
void | run () override |
int | print_status () override |
void | load_fence_from_file (const char *filename) |
Load fence from file. More... | |
void | publish_vehicle_cmd (vehicle_command_s *vcmd) |
void | fake_traffic (const char *callsign, float distance, float direction, float traffic_heading, float altitude_diff, float hor_velocity, float ver_velocity) |
Generate an artificial traffic indication. More... | |
void | check_traffic () |
Check nearby traffic for potential collisions. More... | |
void | set_can_loiter_at_sp (bool can_loiter) |
Setters. More... | |
void | set_position_setpoint_triplet_updated () |
void | set_mission_result_updated () |
struct home_position_s * | get_home_position () |
Getters. More... | |
struct mission_result_s * | get_mission_result () |
struct position_setpoint_triplet_s * | get_position_setpoint_triplet () |
struct position_setpoint_triplet_s * | get_reposition_triplet () |
struct position_setpoint_triplet_s * | get_takeoff_triplet () |
struct vehicle_global_position_s * | get_global_position () |
struct vehicle_land_detected_s * | get_land_detected () |
struct vehicle_local_position_s * | get_local_position () |
struct vehicle_status_s * | get_vstatus () |
PrecLand * | get_precland () |
allow others, e.g. More... | |
const vehicle_roi_s & | get_vroi () |
void | reset_vroi () |
bool | home_alt_valid () |
bool | home_position_valid () |
Geofence & | get_geofence () |
bool | get_can_loiter_at_sp () |
float | get_loiter_radius () |
float | get_default_acceptance_radius () |
Returns the default acceptance radius defined by the parameter. More... | |
float | get_acceptance_radius () |
Get the acceptance radius. More... | |
float | get_default_altitude_acceptance_radius () |
Get the default altitude acceptance radius (i.e. More... | |
float | get_altitude_acceptance_radius () |
Get the altitude acceptance radius. More... | |
float | get_cruising_speed () |
Get the cruising speed. More... | |
void | set_cruising_speed (float speed=-1.0f) |
Set the cruising speed. More... | |
void | reset_cruising_speed () |
Reset cruising speed to default values. More... | |
void | reset_triplets () |
Set triplets to invalid. More... | |
float | get_cruising_throttle () |
Get the target throttle. More... | |
void | set_cruising_throttle (float throttle=-1.0f) |
Set the target throttle. More... | |
float | get_acceptance_radius (float mission_item_radius) |
Get the acceptance radius given the mission item preset radius. More... | |
float | get_yaw_acceptance (float mission_item_yaw) |
Get the yaw acceptance given the current mission item. More... | |
orb_advert_t * | get_mavlink_log_pub () |
void | increment_mission_instance_count () |
void | set_mission_failure (const char *reason) |
bool | is_planned_mission () const |
bool | on_mission_landing () |
bool | start_mission_landing () |
bool | get_mission_start_land_available () |
int | get_mission_landing_index () |
double | get_mission_landing_lat () |
double | get_mission_landing_lon () |
float | get_mission_landing_alt () |
bool | mission_landing_required () |
int | rtl_type () |
bool | in_rtl_state () const |
bool | abort_landing () |
float | get_loiter_min_alt () const |
float | get_takeoff_min_alt () const |
bool | get_takeoff_required () const |
float | get_yaw_timeout () const |
float | get_yaw_threshold () const |
float | get_vtol_back_trans_deceleration () const |
float | get_vtol_reverse_delay () const |
bool | force_vtol () |
Static Public Member Functions | |
static int | task_spawn (int argc, char *argv[]) |
static Navigator * | instantiate (int argc, char *argv[]) |
static int | custom_command (int argc, char *argv[]) |
static int | print_usage (const char *reason=nullptr) |
Private Member Functions | |
DEFINE_PARAMETERS ((ParamFloat< px4::params::NAV_LOITER_RAD >) _param_nav_loiter_rad,(ParamFloat< px4::params::NAV_ACC_RAD >) _param_nav_acc_rad,(ParamFloat< px4::params::NAV_FW_ALT_RAD >) _param_nav_fw_alt_rad,(ParamFloat< px4::params::NAV_FW_ALTL_RAD >) _param_nav_fw_altl_rad,(ParamFloat< px4::params::NAV_MC_ALT_RAD >) _param_nav_mc_alt_rad,(ParamInt< px4::params::NAV_FORCE_VT >) _param_nav_force_vt,(ParamInt< px4::params::NAV_TRAFF_AVOID >) _param_nav_traff_avoid,(ParamFloat< px4::params::MIS_LTRMIN_ALT >) _param_mis_ltrmin_alt,(ParamFloat< px4::params::MIS_TAKEOFF_ALT >) _param_mis_takeoff_alt,(ParamBool< px4::params::MIS_TAKEOFF_REQ >) _param_mis_takeoff_req,(ParamFloat< px4::params::MIS_YAW_TMT >) _param_mis_yaw_tmt,(ParamFloat< px4::params::MIS_YAW_ERR >) _param_mis_yaw_err) int _local_pos_sub | |
void | params_update () |
void | publish_position_setpoint_triplet () |
Publish a new position setpoint triplet for position controllers. More... | |
void | publish_mission_result () |
Publish the mission result so commander and mavlink know what is going on. More... | |
void | publish_vehicle_command_ack (const vehicle_command_s &cmd, uint8_t result) |
Definition at line 89 of file navigator.h.
Navigator::Navigator | ( | ) |
Definition at line 77 of file navigator_main.cpp.
References _dataLinkLoss, _engineFailure, _follow_target, _gpsFailure, _handle_back_trans_dec_mss, _handle_reverse_delay, _land, _loiter, _mission, _navigation_mode_array, _precland, _rcLoss, _rtl, _takeoff, _vehicle_status_sub, ORB_ID, orb_subscribe(), param_find(), and reset_triplets().
Referenced by instantiate().
|
override |
Definition at line 115 of file navigator_main.cpp.
References _vehicle_status_sub, and orb_unsubscribe().
|
delete |
bool Navigator::abort_landing | ( | ) |
Definition at line 1041 of file navigator_main.cpp.
References _pos_ctrl_landing_status_sub, _pos_sp_triplet, position_controller_landing_status_s::abort_landing, uORB::Subscription::copy(), position_setpoint_triplet_s::current, position_setpoint_triplet_s::timestamp, position_setpoint_s::type, uORB::Subscription::updated(), and position_setpoint_s::valid.
Referenced by in_rtl_state(), and Mission::on_active().
void Navigator::check_traffic | ( | ) |
Check nearby traffic for potential collisions.
Definition at line 934 of file navigator_main.cpp.
References _mavlink_log_pub, _rtl, _traffic_sub, vehicle_global_position_s::alt, vehicle_command_s::command, uORB::Subscription::copy(), math::degrees(), crosstrack_error_s::distance, get_distance_to_line(), get_distance_to_point_global_wgs84(), get_global_position(), vehicle_global_position_s::lat, vehicle_global_position_s::lon, mavlink_log_critical, crosstrack_error_s::past_end, publish_vehicle_cmd(), RTL::set_return_alt_min(), uORB::Subscription::updated(), and waypoint_from_heading_and_distance().
Referenced by run().
|
static |
Definition at line 1072 of file navigator_main.cpp.
References f(), GEOFENCE_FILENAME, is_running(), and print_usage().
|
inlineprivate |
_param_nav_loiter_rad | loiter radius for fixedwing |
_param_nav_acc_rad | acceptance for takeoff |
_param_nav_fw_alt_rad | acceptance radius for fixedwing altitude |
_param_nav_fw_altl_rad | acceptance radius for fixedwing altitude before landing |
_param_nav_mc_alt_rad | acceptance radius for multicopter altitude |
_param_nav_force_vt | acceptance radius for multicopter altitude |
_param_nav_traff_avoid | avoiding other aircraft is enabled |
Definition at line 297 of file navigator.h.
void Navigator::fake_traffic | ( | const char * | callsign, |
float | distance, | ||
float | direction, | ||
float | traffic_heading, | ||
float | altitude_diff, | ||
float | hor_velocity, | ||
float | ver_velocity | ||
) |
Generate an artificial traffic indication.
Creates a fake traffic measurement with supplied parameters.
distance | Horizontal distance to this vehicle |
direction | Direction in earth frame from this vehicle in radians |
traffic_heading | Travel direction of the traffic in earth frame in radians |
altitude_diff | Altitude difference, positive is up |
hor_velocity | Horizontal velocity of traffic, in m/s |
ver_velocity | Vertical velocity of traffic, in m/s |
Definition at line 898 of file navigator_main.cpp.
References vehicle_global_position_s::alt, get_global_position(), hrt_absolute_time(), ORB_ID, transponder_report_s::timestamp, and waypoint_from_heading_and_distance().
bool Navigator::force_vtol | ( | ) |
Definition at line 1065 of file navigator_main.cpp.
References _vstatus, vehicle_status_s::in_transition_to_fw, vehicle_status_s::is_vtol, vehicle_status_s::vehicle_type, and VEHICLE_TYPE_FIXED_WING.
Referenced by get_vtol_reverse_delay(), MissionBlock::set_land_item(), and Mission::set_mission_items().
float Navigator::get_acceptance_radius | ( | ) |
Get the acceptance radius.
Definition at line 749 of file navigator_main.cpp.
Referenced by Mission::altitude_sp_foh_update(), Mission::do_abort_landing(), Mission::do_need_move_to_land(), Mission::do_need_move_to_takeoff(), get_loiter_radius(), Mission::heading_sp_update(), MissionBlock::is_mission_item_reached(), MissionBlock::MissionBlock(), run(), set_cruising_throttle(), DataLinkLoss::set_dll_item(), EngineFailure::set_ef_item(), FollowTarget::set_follow_target_item(), MissionBlock::set_idle_item(), MissionBlock::set_land_item(), MissionBlock::set_loiter_item(), RCLoss::set_rcl_item(), and RTL::set_rtl_item().
float Navigator::get_acceptance_radius | ( | float | mission_item_radius | ) |
Get the acceptance radius given the mission item preset radius.
mission_item_radius | the radius to use in case the controller-derived radius is smaller |
Definition at line 854 of file navigator_main.cpp.
References _pos_sp_triplet, _position_controller_status_sub, position_controller_status_s::acceptance_radius, uORB::SubscriptionData< T >::get(), position_controller_status_s::timestamp, and position_setpoint_triplet_s::timestamp.
float Navigator::get_altitude_acceptance_radius | ( | ) |
Get the altitude acceptance radius.
Definition at line 778 of file navigator_main.cpp.
References get_default_altitude_acceptance_radius(), get_position_setpoint_triplet(), get_vstatus(), position_setpoint_triplet_s::next, position_setpoint_s::type, position_setpoint_s::valid, and VEHICLE_TYPE_FIXED_WING.
Referenced by Mission::do_need_vertical_takeoff(), get_loiter_radius(), and MissionBlock::is_mission_item_reached().
|
inline |
Definition at line 170 of file navigator.h.
References _can_loiter_at_sp.
Referenced by RCLoss::on_inactive(), DataLinkLoss::on_inactive(), GpsFailure::on_inactive(), Mission::on_inactive(), and MissionBlock::set_loiter_item().
float Navigator::get_cruising_speed | ( | ) |
Get the cruising speed.
Definition at line 793 of file navigator_main.cpp.
References _mission_cruising_speed_fw, _mission_cruising_speed_mc, _vstatus, f(), is_planned_mission(), and vehicle_status_s::vehicle_type.
Referenced by Mission::cruising_speed_sp_update(), get_loiter_radius(), MissionBlock::mission_item_to_position_setpoint(), and run().
float Navigator::get_cruising_throttle | ( | ) |
Get the target throttle.
Definition at line 842 of file navigator_main.cpp.
References _mission_throttle, and FLT_EPSILON.
Referenced by get_loiter_radius(), MissionBlock::mission_item_to_position_setpoint(), and run().
float Navigator::get_default_acceptance_radius | ( | ) |
Returns the default acceptance radius defined by the parameter.
Definition at line 743 of file navigator_main.cpp.
Referenced by MissionFeasibilityChecker::checkTakeoff(), get_loiter_radius(), and MissionBlock::mission_item_to_position_setpoint().
float Navigator::get_default_altitude_acceptance_radius | ( | ) |
Get the default altitude acceptance radius (i.e.
from parameters)
Definition at line 755 of file navigator_main.cpp.
References _pos_sp_triplet, _position_controller_status_sub, position_controller_status_s::altitude_acceptance, uORB::SubscriptionData< T >::get(), get_vstatus(), position_controller_status_s::timestamp, position_setpoint_triplet_s::timestamp, and VEHICLE_TYPE_FIXED_WING.
Referenced by get_altitude_acceptance_radius(), get_loiter_radius(), and MissionBlock::is_mission_item_reached().
|
inline |
Definition at line 168 of file navigator.h.
References _geofence.
Referenced by MissionFeasibilityChecker::checkGeofence().
|
inline |
Definition at line 156 of file navigator.h.
References _global_pos.
Referenced by Mission::altitude_sp_foh_update(), RTL::calculate_return_alt_from_cone_half_angle(), Mission::calculate_takeoff_altitude(), check_traffic(), Mission::copy_position_if_valid(), Mission::do_abort_landing(), Mission::do_need_move_to_land(), Mission::do_need_move_to_takeoff(), Mission::do_need_vertical_takeoff(), fake_traffic(), RTL::find_RTL_destination(), Mission::generate_waypoint_from_heading(), Mission::heading_sp_update(), Mission::index_closest_mission_item(), MissionBlock::is_mission_item_reached(), MissionBlock::mission_item_to_position_setpoint(), PrecLand::on_activation(), RTL::on_activation(), Land::on_active(), FollowTarget::on_active(), Loiter::reposition(), run(), PrecLand::run_state_descend_above_target(), PrecLand::run_state_horizontal_approach(), PrecLand::run_state_search(), PrecLand::run_state_start(), Mission::set_align_mission_item(), EngineFailure::set_ef_item(), MissionBlock::set_loiter_item(), Mission::set_mission_items(), RCLoss::set_rcl_item(), RTL::set_rtl_item(), MissionBlock::set_takeoff_item(), Takeoff::set_takeoff_position(), MissionBlock::set_vtol_transition_item(), PrecLand::switch_to_state_fallback(), and PrecLand::switch_to_state_horizontal_approach().
|
inline |
Getters.
Definition at line 151 of file navigator.h.
References _home_pos.
Referenced by Mission::calculate_takeoff_altitude(), Geofence::checkAll(), MissionFeasibilityChecker::checkDistanceToFirstWaypoint(), MissionFeasibilityChecker::checkMissionFeasible(), RTL::find_RTL_destination(), MissionBlock::get_absolute_altitude_for_item(), Mission::index_closest_mission_item(), MissionBlock::is_mission_item_reached(), MissionBlock::issue_command(), MissionBlock::mission_apply_limitation(), MissionBlock::mission_item_to_position_setpoint(), EngineFailure::set_ef_item(), FollowTarget::set_follow_target_item(), MissionBlock::set_idle_item(), MissionBlock::set_land_item(), MissionBlock::set_loiter_item(), and Mission::set_mission_items().
|
inline |
Definition at line 157 of file navigator.h.
References _land_detected.
Referenced by Mission::calculate_takeoff_altitude(), MissionFeasibilityChecker::checkMissionItemValidity(), MissionFeasibilityChecker::checkTakeoff(), Mission::do_need_vertical_takeoff(), MissionBlock::is_mission_item_reached(), MissionBlock::mission_apply_limitation(), MissionBlock::mission_item_to_position_setpoint(), RTL::on_activation(), Land::on_active(), PrecLand::on_active(), Mission::on_active(), Mission::on_inactive(), run(), Mission::set_execution_mode(), FollowTarget::set_follow_target_item(), MissionBlock::set_loiter_item(), Loiter::set_loiter_position(), Mission::set_mission_items(), and Mission::update_mission().
|
inline |
Definition at line 158 of file navigator.h.
References _local_pos.
Referenced by PrecLand::check_state_conditions(), MissionBlock::is_mission_item_reached(), PrecLand::on_activation(), run(), MissionBlock::set_land_item(), RTL::set_rtl_item(), PrecLand::slewrate(), and PrecLand::switch_to_state_search().
|
inline |
Definition at line 285 of file navigator.h.
Referenced by Mission::do_abort_landing(), MissionBlock::mission_item_to_position_setpoint(), and Loiter::set_loiter_position().
|
inline |
Definition at line 171 of file navigator.h.
References f(), get_acceptance_radius(), get_altitude_acceptance_radius(), get_cruising_speed(), get_cruising_throttle(), get_default_acceptance_radius(), get_default_altitude_acceptance_radius(), reset_cruising_speed(), reset_triplets(), and set_cruising_speed().
Referenced by Mission::do_abort_landing(), MissionBlock::is_mission_item_reached(), MissionBlock::mission_item_to_position_setpoint(), MissionBlock::MissionBlock(), run(), DataLinkLoss::set_dll_item(), EngineFailure::set_ef_item(), FollowTarget::set_follow_target_item(), MissionBlock::set_idle_item(), MissionBlock::set_land_item(), MissionBlock::set_loiter_item(), RCLoss::set_rcl_item(), RTL::set_rtl_item(), and MissionBlock::set_takeoff_item().
|
inline |
Definition at line 261 of file navigator.h.
References _mavlink_log_pub.
Referenced by DataLinkLoss::advance_dll(), EngineFailure::advance_ef(), GpsFailure::advance_gpsf(), RCLoss::advance_rcl(), Geofence::checkAll(), MissionFeasibilityChecker::checkDistancesBetweenWaypoints(), MissionFeasibilityChecker::checkDistanceToFirstWaypoint(), MissionFeasibilityChecker::checkFixedWingLanding(), MissionFeasibilityChecker::checkGeofence(), MissionFeasibilityChecker::checkHomePositionAltitude(), MissionFeasibilityChecker::checkMissionFeasible(), MissionFeasibilityChecker::checkMissionItemValidity(), MissionFeasibilityChecker::checkTakeoff(), Mission::do_abort_landing(), RTL::find_RTL_destination(), Geofence::loadFromFile(), RTL::on_activation(), Mission::read_mission_item(), Mission::reset_mission(), run(), Mission::save_mission_state(), Mission::set_mission_items(), RTL::set_rtl_item(), and Takeoff::set_takeoff_position().
|
inline |
Definition at line 275 of file navigator.h.
References _mission, and Mission::get_landing_alt().
Referenced by RTL::find_RTL_destination().
|
inline |
Definition at line 272 of file navigator.h.
References _mission, and Mission::get_land_start_index().
|
inline |
Definition at line 273 of file navigator.h.
References _mission, and Mission::get_landing_lat().
Referenced by RTL::find_RTL_destination().
|
inline |
Definition at line 274 of file navigator.h.
References _mission, and Mission::get_landing_lon().
Referenced by RTL::find_RTL_destination().
|
inline |
Definition at line 152 of file navigator.h.
References _mission_result.
Referenced by DataLinkLoss::advance_dll(), RCLoss::advance_rcl(), Mission::check_mission_valid(), MissionFeasibilityChecker::checkDistancesBetweenWaypoints(), MissionFeasibilityChecker::checkDistanceToFirstWaypoint(), MissionFeasibilityChecker::checkHomePositionAltitude(), Mission::landing(), Land::on_activation(), Land::on_active(), Takeoff::on_active(), Mission::on_inactive(), Mission::report_do_jump_mission_changed(), NavigatorMode::run(), Mission::set_current_mission_index(), Mission::set_current_mission_item(), DataLinkLoss::set_dll_item(), Mission::set_execution_mode(), GpsFailure::set_gpsf_item(), Mission::set_mission_item_reached(), Mission::set_mission_items(), RCLoss::set_rcl_item(), Takeoff::set_takeoff_position(), and Mission::update_mission().
|
inline |
Definition at line 271 of file navigator.h.
References _mission, and Mission::get_land_start_available().
Referenced by RTL::find_RTL_destination().
|
inline |
Definition at line 153 of file navigator.h.
References _pos_sp_triplet.
Referenced by Mission::altitude_sp_foh_update(), Mission::cruising_speed_sp_update(), Mission::do_abort_landing(), get_altitude_acceptance_radius(), Mission::heading_sp_update(), MissionBlock::is_mission_item_reached(), Land::on_activation(), NavigatorMode::on_activation(), PrecLand::on_activation(), Land::on_active(), Takeoff::on_active(), Loiter::reposition(), run(), PrecLand::run_state_descend_above_target(), PrecLand::run_state_horizontal_approach(), PrecLand::run_state_search(), PrecLand::run_state_start(), Mission::set_align_mission_item(), Mission::set_current_mission_index(), DataLinkLoss::set_dll_item(), EngineFailure::set_ef_item(), Mission::set_execution_mode(), GpsFailure::set_gpsf_item(), MissionBlock::set_loiter_item(), Loiter::set_loiter_position(), Mission::set_mission_items(), RCLoss::set_rcl_item(), RTL::set_rtl_item(), Takeoff::set_takeoff_position(), PrecLand::slewrate(), PrecLand::switch_to_state_fallback(), PrecLand::switch_to_state_search(), PrecLand::switch_to_state_start(), and FollowTarget::update_position_sp().
|
inline |
allow others, e.g.
Mission, to use the precision land block
Definition at line 160 of file navigator.h.
References _precland.
Referenced by Mission::on_active(), and Mission::set_mission_items().
|
inline |
Definition at line 154 of file navigator.h.
References _reposition_triplet.
Referenced by Loiter::on_activation(), Loiter::on_active(), Loiter::reposition(), and run().
|
inline |
Definition at line 286 of file navigator.h.
Referenced by Mission::calculate_takeoff_altitude(), Mission::set_mission_items(), and Takeoff::set_takeoff_position().
|
inline |
Definition at line 287 of file navigator.h.
Referenced by MissionFeasibilityChecker::checkTakeoff().
|
inline |
Definition at line 155 of file navigator.h.
References _takeoff_triplet.
Referenced by Takeoff::on_active(), run(), and Takeoff::set_takeoff_position().
|
inline |
Definition at line 162 of file navigator.h.
References _vroi.
Referenced by Mission::heading_sp_update(), and Mission::on_active().
|
inline |
Definition at line 159 of file navigator.h.
References _vstatus.
Referenced by DataLinkLoss::advance_dll(), RTL::advance_rtl(), Mission::altitude_sp_foh_update(), MissionFeasibilityChecker::checkMissionFeasible(), Mission::do_need_move_to_land(), Mission::do_need_move_to_takeoff(), Mission::do_need_vertical_takeoff(), get_altitude_acceptance_radius(), get_default_altitude_acceptance_radius(), MissionBlock::get_time_inside(), Mission::index_closest_mission_item(), MissionBlock::is_mission_item_reached(), MissionBlock::mission_item_to_position_setpoint(), Mission::need_to_reset_mission(), Land::on_active(), Loiter::on_active(), GpsFailure::on_active(), Mission::on_active(), Loiter::reposition(), Mission::set_execution_mode(), Loiter::set_loiter_position(), Mission::set_mission_items(), and RTL::set_rtl_item().
|
inline |
Definition at line 291 of file navigator.h.
References _param_back_trans_dec_mss.
Referenced by MissionBlock::is_mission_item_reached().
|
inline |
Definition at line 292 of file navigator.h.
References _param_reverse_delay, and force_vtol().
Referenced by MissionBlock::is_mission_item_reached().
float Navigator::get_yaw_acceptance | ( | float | mission_item_yaw | ) |
Get the yaw acceptance given the current mission item.
mission_item_yaw | the yaw to use in case the controller-derived radius is finite |
Definition at line 873 of file navigator_main.cpp.
References _pos_sp_triplet, _position_controller_status_sub, uORB::SubscriptionData< T >::get(), position_controller_status_s::timestamp, position_setpoint_triplet_s::timestamp, and position_controller_status_s::yaw_acceptance.
Referenced by MissionBlock::is_mission_item_reached(), and set_cruising_throttle().
|
inline |
Definition at line 289 of file navigator.h.
References math::radians().
Referenced by MissionBlock::is_mission_item_reached().
|
inline |
Definition at line 288 of file navigator.h.
Referenced by MissionBlock::is_mission_item_reached().
|
inline |
Definition at line 165 of file navigator.h.
References _home_pos, home_position_s::timestamp, and home_position_s::valid_alt.
Referenced by MissionFeasibilityChecker::checkMissionFeasible().
|
inline |
Definition at line 166 of file navigator.h.
References _home_pos, home_position_s::timestamp, home_position_s::valid_alt, and home_position_s::valid_hpos.
Referenced by Mission::check_mission_valid(), Geofence::checkAll(), MissionFeasibilityChecker::checkMissionFeasible(), Mission::on_inactive(), run(), and Takeoff::set_takeoff_position().
|
inline |
Definition at line 280 of file navigator.h.
References _vstatus, abort_landing(), and vehicle_status_s::nav_state.
|
inline |
Definition at line 263 of file navigator.h.
References _mission_result, mission_result_s::instance_count, and set_mission_failure().
Referenced by Mission::check_mission_valid().
|
static |
Definition at line 714 of file navigator_main.cpp.
References ll40ls::instance, and Navigator().
|
inline |
Definition at line 268 of file navigator.h.
References _mission, and _navigation_mode.
Referenced by Mission::altitude_sp_foh_update(), get_cruising_speed(), and Mission::set_current_mission_index().
void Navigator::load_fence_from_file | ( | const char * | filename | ) |
Load fence from file.
Definition at line 889 of file navigator_main.cpp.
References _geofence, and Geofence::loadFromFile().
|
inline |
Definition at line 278 of file navigator.h.
References _rtl, RTL::RTL_LAND, and RTL::rtl_type().
Referenced by Mission::check_mission_valid().
|
inline |
Definition at line 269 of file navigator.h.
References _mission, and Mission::landing().
Referenced by RTL::on_activation(), and run().
|
private |
Definition at line 122 of file navigator_main.cpp.
References _handle_back_trans_dec_mss, _handle_reverse_delay, _param_back_trans_dec_mss, _param_reverse_delay, param_get(), and PARAM_INVALID.
Referenced by run().
|
override |
Definition at line 726 of file navigator_main.cpp.
References _geofence, and Geofence::printStatus().
|
static |
Definition at line 1170 of file navigator_main.cpp.
Referenced by custom_command().
|
private |
Publish the mission result so commander and mavlink know what is going on.
Definition at line 1099 of file navigator_main.cpp.
References _mission_result, _mission_result_pub, _mission_result_updated, hrt_absolute_time(), mission_result_s::item_changed_index, mission_result_s::item_do_jump_changed, mission_result_s::item_do_jump_remaining, uORB::Publication< T >::publish(), and mission_result_s::timestamp.
Referenced by run().
|
private |
Publish a new position setpoint triplet for position controllers.
Definition at line 735 of file navigator_main.cpp.
References _pos_sp_triplet, _pos_sp_triplet_pub, _pos_sp_triplet_updated, hrt_absolute_time(), uORB::Publication< T >::publish(), and position_setpoint_triplet_s::timestamp.
Referenced by run().
void Navigator::publish_vehicle_cmd | ( | vehicle_command_s * | vcmd | ) |
Definition at line 1125 of file navigator_main.cpp.
References _vehicle_cmd_pub, _vstatus, vehicle_command_s::command, vehicle_status_s::component_id, vehicle_command_s::confirmation, vehicle_command_s::from_external, hrt_absolute_time(), NAV_CMD_IMAGE_START_CAPTURE, NAV_CMD_IMAGE_STOP_CAPTURE, NAV_CMD_VIDEO_START_CAPTURE, NAV_CMD_VIDEO_STOP_CAPTURE, uORB::PublicationQueued< T >::publish(), vehicle_command_s::source_component, vehicle_command_s::source_system, vehicle_status_s::system_id, vehicle_command_s::target_component, vehicle_command_s::target_system, and vehicle_command_s::timestamp.
Referenced by check_traffic(), Mission::do_abort_landing(), MissionBlock::issue_command(), Mission::on_activation(), Mission::on_inactivation(), run(), and MissionBlock::set_land_item().
|
private |
Definition at line 1153 of file navigator_main.cpp.
References _vehicle_cmd_ack_pub, vehicle_command_ack_s::command, vehicle_command_s::command, vehicle_command_ack_s::from_external, hrt_absolute_time(), uORB::PublicationQueued< T >::publish(), vehicle_command_ack_s::result, vehicle_command_ack_s::result_param1, vehicle_command_ack_s::result_param2, vehicle_command_s::source_component, vehicle_command_s::source_system, vehicle_command_ack_s::target_component, vehicle_command_ack_s::target_system, and vehicle_command_ack_s::timestamp.
Referenced by run().
void Navigator::reset_cruising_speed | ( | ) |
Reset cruising speed to default values.
For VTOL: resets both cruising speeds.
Definition at line 826 of file navigator_main.cpp.
References _mission_cruising_speed_fw, and _mission_cruising_speed_mc.
Referenced by get_loiter_radius(), Mission::on_active(), and Mission::on_inactive().
void Navigator::reset_triplets | ( | ) |
Set triplets to invalid.
Definition at line 833 of file navigator_main.cpp.
References _pos_sp_triplet, _pos_sp_triplet_updated, position_setpoint_triplet_s::current, position_setpoint_triplet_s::next, position_setpoint_triplet_s::previous, and position_setpoint_s::valid.
Referenced by get_loiter_radius(), Navigator(), Mission::on_active(), and run().
|
inline |
Definition at line 163 of file navigator.h.
References _vroi.
Referenced by Mission::update_mission().
|
inline |
Definition at line 279 of file navigator.h.
References _rtl, and RTL::rtl_type().
Referenced by run().
|
override |
Definition at line 136 of file navigator_main.cpp.
References _can_loiter_at_sp, _dataLinkLoss, _engineFailure, _follow_target, _geofence, _geofence_result, _geofence_result_pub, _geofence_violation_warning_sent, _global_pos, _global_pos_sub, _gps_pos, _gps_pos_sub, _gpsFailure, _home_pos, _home_pos_sub, _land, _land_detected, _land_detected_sub, _local_pos, _loiter, _loop_perf, _mavlink_log_pub, _mission, _mission_result, _mission_result_updated, _navigation_mode, _navigation_mode_array, _parameter_update_sub, _pos_sp_triplet, _pos_sp_triplet_published_invalid_once, _pos_sp_triplet_updated, _position_controller_status_sub, _precland, _previous_nav_state, _rcLoss, _rtl, _takeoff, _vehicle_command_sub, _vehicle_roi_pub, _vehicle_status_sub, _vroi, _vstatus, position_setpoint_s::acceptance_radius, vehicle_global_position_s::alt, vehicle_roi_s::alt, position_setpoint_s::alt, Geofence::check(), check_traffic(), vehicle_command_s::command, uORB::Subscription::copy(), position_setpoint_s::cruising_speed, position_setpoint_s::cruising_throttle, position_setpoint_triplet_s::current, FLT_EPSILON, geofence_result_s::geofence_action, GEOFENCE_CHECK_INTERVAL, GEOFENCE_FILENAME, geofence_result_s::geofence_violated, get_acceptance_radius(), get_cruising_speed(), get_cruising_throttle(), get_global_position(), get_land_detected(), Mission::get_land_start_available(), Mission::get_land_start_index(), get_local_position(), get_loiter_radius(), get_mavlink_log_pub(), Mission::get_mission_changed(), Mission::get_mission_finished(), Mission::get_mission_waypoints_changed(), get_position_setpoint_triplet(), get_reposition_triplet(), get_takeoff_triplet(), Geofence::getGeofenceAction(), Geofence::getSource(), Geofence::GF_SOURCE_GLOBALPOS, Geofence::GF_SOURCE_GPS, home_position_valid(), geofence_result_s::home_required, hrt_absolute_time(), hrt_abstime, hrt_elapsed_time(), Geofence::isHomeRequired(), Mission::land_start(), vehicle_land_detected_s::landed, vehicle_global_position_s::lat, vehicle_roi_s::lat, position_setpoint_s::lat, Geofence::loadFromFile(), position_setpoint_s::loiter_direction, position_setpoint_s::loiter_radius, vehicle_global_position_s::lon, vehicle_roi_s::lon, position_setpoint_s::lon, mavlink_and_console_log_info, mavlink_log_critical, vehicle_roi_s::mode, vehicle_status_s::nav_state, NAVIGATOR_MODE_ARRAY_SIZE, position_setpoint_triplet_s::next, on_mission_landing(), orb_copy(), ORB_ID, orb_set_interval(), vehicle_command_s::param1, params_update(), perf_begin(), perf_end(), vehicle_roi_s::pitch_offset, position_setpoint_triplet_s::previous, uORB::Publication< T >::publish(), publish_mission_result(), publish_position_setpoint_triplet(), publish_vehicle_cmd(), publish_vehicle_command_ack(), px4_poll(), Required, reset_triplets(), vehicle_roi_s::roll_offset, RTL::RTL_CLOSEST, RTL::RTL_LAND, RTL::RTL_MISSION, rtl_type(), NavigatorMode::run(), Mission::set_closest_item_as_current(), set_cruising_speed(), set_cruising_throttle(), Mission::set_current_mission_index(), Mission::set_execution_mode(), PrecLand::set_mode(), start_mission_landing(), geofence_result_s::timestamp, vehicle_roi_s::timestamp, position_setpoint_s::timestamp, position_setpoint_s::type, uORB::Subscription::update(), uORB::SubscriptionData< T >::update(), uORB::Subscription::updated(), mission_result_s::valid, position_setpoint_s::valid, vehicle_global_position_s::yaw, vehicle_local_position_s::yaw, position_setpoint_s::yaw, vehicle_roi_s::yaw_offset, and position_setpoint_s::yaw_valid.
|
inline |
Setters.
Definition at line 144 of file navigator.h.
References _can_loiter_at_sp.
Referenced by Land::on_activation(), Mission::on_active(), Loiter::reposition(), DataLinkLoss::set_dll_item(), EngineFailure::set_ef_item(), Loiter::set_loiter_position(), Mission::set_mission_items(), RCLoss::set_rcl_item(), RTL::set_rtl_item(), and Takeoff::set_takeoff_position().
void Navigator::set_cruising_speed | ( | float | speed = -1.0f | ) |
Set the cruising speed.
Passing a negative value or leaving the parameter away will reset the cruising speed to its default value.
For VTOL: sets cruising speed for current mode only (multirotor or fixed-wing).
Definition at line 815 of file navigator_main.cpp.
References _mission_cruising_speed_fw, _mission_cruising_speed_mc, _vstatus, and vehicle_status_s::vehicle_type.
Referenced by get_loiter_radius(), Mission::on_inactive(), and run().
|
inline |
Set the target throttle.
Definition at line 240 of file navigator.h.
References _mission_throttle, get_acceptance_radius(), and get_yaw_acceptance().
Referenced by run().
void Navigator::set_mission_failure | ( | const char * | reason | ) |
Definition at line 1115 of file navigator_main.cpp.
References _mavlink_log_pub, _mission_result, mission_result_s::failure, mavlink_log_critical, and set_mission_result_updated().
Referenced by increment_mission_instance_count(), and MissionBlock::is_mission_item_reached().
|
inline |
Definition at line 146 of file navigator.h.
References _mission_result_updated.
Referenced by DataLinkLoss::advance_dll(), RCLoss::advance_rcl(), Mission::check_mission_valid(), Land::on_activation(), Land::on_active(), Takeoff::on_active(), Mission::report_do_jump_mission_changed(), NavigatorMode::run(), Mission::set_current_mission_item(), DataLinkLoss::set_dll_item(), GpsFailure::set_gpsf_item(), set_mission_failure(), Mission::set_mission_item_reached(), Mission::set_mission_items(), RCLoss::set_rcl_item(), and Takeoff::set_takeoff_position().
|
inline |
Definition at line 145 of file navigator.h.
References _pos_sp_triplet_updated.
Referenced by Mission::altitude_sp_foh_update(), Mission::cruising_speed_sp_update(), Mission::do_abort_landing(), Mission::heading_sp_update(), MissionBlock::is_mission_item_reached(), Land::on_activation(), Land::on_active(), Takeoff::on_active(), Loiter::reposition(), PrecLand::run_state_descend_above_target(), PrecLand::run_state_horizontal_approach(), PrecLand::run_state_search(), DataLinkLoss::set_dll_item(), EngineFailure::set_ef_item(), Mission::set_execution_mode(), GpsFailure::set_gpsf_item(), Loiter::set_loiter_position(), Mission::set_mission_items(), RCLoss::set_rcl_item(), RTL::set_rtl_item(), Takeoff::set_takeoff_position(), PrecLand::switch_to_state_fallback(), PrecLand::switch_to_state_search(), PrecLand::switch_to_state_start(), and FollowTarget::update_position_sp().
|
inline |
Definition at line 270 of file navigator.h.
References _mission, and Mission::land_start().
Referenced by run(), and RTL::set_rtl_item().
|
static |
Definition at line 697 of file navigator_main.cpp.
|
private |
flags if current position SP can be used to loiter
Definition at line 365 of file navigator.h.
Referenced by get_can_loiter_at_sp(), run(), and set_can_loiter_at_sp().
|
private |
class that handles the OBC datalink loss mode
Definition at line 378 of file navigator.h.
Referenced by Navigator(), and run().
|
private |
class that handles the engine failure mode (FW only!)
Definition at line 379 of file navigator.h.
Referenced by Navigator(), and run().
|
private |
Definition at line 381 of file navigator.h.
Referenced by Navigator(), and run().
|
private |
class that handles the geofence
Definition at line 362 of file navigator.h.
Referenced by get_geofence(), load_fence_from_file(), print_status(), and run().
|
private |
Definition at line 354 of file navigator.h.
Referenced by run().
|
private |
Definition at line 332 of file navigator.h.
Referenced by run().
|
private |
|
private |
global vehicle position
Definition at line 345 of file navigator.h.
Referenced by get_global_position(), and run().
|
private |
|
private |
|
private |
|
private |
class that handles the OBC gpsfailure loss mode
Definition at line 380 of file navigator.h.
Referenced by Navigator(), and run().
|
private |
Definition at line 385 of file navigator.h.
Referenced by Navigator(), and params_update().
|
private |
Definition at line 386 of file navigator.h.
Referenced by Navigator(), and params_update().
|
private |
home position for RTL
Definition at line 343 of file navigator.h.
Referenced by get_home_position(), home_alt_valid(), home_position_valid(), and run().
|
private |
|
private |
class for handling land commands
Definition at line 374 of file navigator.h.
Referenced by Navigator(), and run().
|
private |
vehicle land_detected
Definition at line 347 of file navigator.h.
Referenced by get_land_detected(), and run().
|
private |
|
private |
local vehicle position
Definition at line 348 of file navigator.h.
Referenced by get_local_position(), and run().
|
private |
class that handles loiter
Definition at line 372 of file navigator.h.
Referenced by Navigator(), and run().
|
private |
|
private |
the uORB advert to send messages over mavlink
Definition at line 337 of file navigator.h.
Referenced by check_traffic(), get_mavlink_log_pub(), run(), and set_mission_failure().
|
private |
class that handles the missions
Definition at line 371 of file navigator.h.
Referenced by get_mission_landing_alt(), get_mission_landing_index(), get_mission_landing_lat(), get_mission_landing_lon(), get_mission_start_land_available(), is_planned_mission(), Navigator(), on_mission_landing(), run(), and start_mission_landing().
|
private |
Definition at line 391 of file navigator.h.
Referenced by get_cruising_speed(), reset_cruising_speed(), and set_cruising_speed().
|
private |
Definition at line 390 of file navigator.h.
Referenced by get_cruising_speed(), reset_cruising_speed(), and set_cruising_speed().
|
private |
Definition at line 344 of file navigator.h.
Referenced by get_mission_result(), increment_mission_instance_count(), publish_mission_result(), run(), and set_mission_failure().
|
private |
Definition at line 333 of file navigator.h.
Referenced by publish_mission_result().
|
private |
flags if mission result has seen an update
Definition at line 368 of file navigator.h.
Referenced by publish_mission_result(), run(), and set_mission_result_updated().
|
private |
Definition at line 392 of file navigator.h.
Referenced by get_cruising_throttle(), and set_cruising_throttle().
|
private |
abstract pointer to current navigation mode class
Definition at line 370 of file navigator.h.
Referenced by is_planned_mission(), and run().
|
private |
array of navigation modes
Definition at line 383 of file navigator.h.
Referenced by Navigator(), and run().
|
private |
Definition at line 387 of file navigator.h.
Referenced by get_vtol_back_trans_deceleration(), and params_update().
|
private |
Definition at line 388 of file navigator.h.
Referenced by get_vtol_reverse_delay(), and params_update().
|
private |
|
private |
position controller landing status subscription
Definition at line 326 of file navigator.h.
Referenced by abort_landing().
|
private |
triplet of position setpoints
Definition at line 355 of file navigator.h.
Referenced by abort_landing(), get_acceptance_radius(), get_default_altitude_acceptance_radius(), get_position_setpoint_triplet(), get_yaw_acceptance(), publish_position_setpoint_triplet(), reset_triplets(), and run().
|
private |
Definition at line 334 of file navigator.h.
Referenced by publish_position_setpoint_triplet().
|
private |
flags if position SP triplet has been published once to UORB
Definition at line 367 of file navigator.h.
Referenced by run().
|
private |
flags if position SP triplet needs to be published
Definition at line 366 of file navigator.h.
Referenced by publish_position_setpoint_triplet(), reset_triplets(), run(), and set_position_setpoint_triplet_updated().
|
private |
Definition at line 330 of file navigator.h.
Referenced by get_acceptance_radius(), get_default_altitude_acceptance_radius(), get_yaw_acceptance(), and run().
|
private |
class for handling precision land commands
Definition at line 375 of file navigator.h.
Referenced by get_precland(), Navigator(), and run().
|
private |
nav_state of the previous iteration
Definition at line 351 of file navigator.h.
Referenced by run().
|
private |
class that handles RTL according to OBC rules (rc loss mode)
Definition at line 377 of file navigator.h.
Referenced by Navigator(), and run().
|
private |
triplet for non-mission direct position command
Definition at line 356 of file navigator.h.
Referenced by get_reposition_triplet().
|
private |
class that handles RTL
Definition at line 376 of file navigator.h.
Referenced by check_traffic(), mission_landing_required(), Navigator(), rtl_type(), and run().
|
private |
class for handling takeoff commands
Definition at line 373 of file navigator.h.
Referenced by Navigator(), and run().
|
private |
triplet for non-mission direct takeoff command
Definition at line 357 of file navigator.h.
Referenced by get_takeoff_triplet().
|
private |
|
private |
Definition at line 339 of file navigator.h.
Referenced by publish_vehicle_command_ack().
|
private |
Definition at line 340 of file navigator.h.
Referenced by publish_vehicle_cmd().
|
private |
vehicle commands (onboard and offboard)
Definition at line 328 of file navigator.h.
Referenced by run().
|
private |
Definition at line 335 of file navigator.h.
Referenced by run().
|
private |
local position subscription
local position subscription
Definition at line 319 of file navigator.h.
Referenced by Navigator(), run(), and ~Navigator().
|
private |
vehicle ROI
Definition at line 358 of file navigator.h.
Referenced by get_vroi(), reset_vroi(), and run().
|
private |
vehicle status
Definition at line 349 of file navigator.h.
Referenced by force_vtol(), get_cruising_speed(), get_vstatus(), in_rtl_state(), publish_vehicle_cmd(), run(), and set_cruising_speed().