PX4 Firmware
PX4 Autopilot Software http://px4.io
Navigator Class Reference

#include <navigator.h>

Inheritance diagram for Navigator:
Collaboration diagram for Navigator:

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_sget_home_position ()
 Getters. More...
 
struct mission_result_sget_mission_result ()
 
struct position_setpoint_triplet_sget_position_setpoint_triplet ()
 
struct position_setpoint_triplet_sget_reposition_triplet ()
 
struct position_setpoint_triplet_sget_takeoff_triplet ()
 
struct vehicle_global_position_sget_global_position ()
 
struct vehicle_land_detected_sget_land_detected ()
 
struct vehicle_local_position_sget_local_position ()
 
struct vehicle_status_sget_vstatus ()
 
PrecLandget_precland ()
 allow others, e.g. More...
 
const vehicle_roi_sget_vroi ()
 
void reset_vroi ()
 
bool home_alt_valid ()
 
bool home_position_valid ()
 
Geofenceget_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_tget_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 Navigatorinstantiate (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)
 

Private Attributes

int _vehicle_status_sub {-1}
 local position subscription More...
 
uORB::Subscription _global_pos_sub {ORB_ID(vehicle_global_position)}
 global position subscription More...
 
uORB::Subscription _gps_pos_sub {ORB_ID(vehicle_gps_position)}
 gps position subscription More...
 
uORB::Subscription _home_pos_sub {ORB_ID(home_position)}
 home position subscription More...
 
uORB::Subscription _land_detected_sub {ORB_ID(vehicle_land_detected)}
 vehicle land detected subscription More...
 
uORB::Subscription _parameter_update_sub {ORB_ID(parameter_update)}
 param update subscription More...
 
uORB::Subscription _pos_ctrl_landing_status_sub {ORB_ID(position_controller_landing_status)}
 position controller landing status subscription More...
 
uORB::Subscription _traffic_sub {ORB_ID(transponder_report)}
 traffic subscription More...
 
uORB::Subscription _vehicle_command_sub {ORB_ID(vehicle_command)}
 vehicle commands (onboard and offboard) More...
 
uORB::SubscriptionData< position_controller_status_s_position_controller_status_sub {ORB_ID(position_controller_status)}
 
uORB::Publication< geofence_result_s_geofence_result_pub {ORB_ID(geofence_result)}
 
uORB::Publication< mission_result_s_mission_result_pub {ORB_ID(mission_result)}
 
uORB::Publication< position_setpoint_triplet_s_pos_sp_triplet_pub {ORB_ID(position_setpoint_triplet)}
 
uORB::Publication< vehicle_roi_s_vehicle_roi_pub {ORB_ID(vehicle_roi)}
 
orb_advert_t _mavlink_log_pub {nullptr}
 the uORB advert to send messages over mavlink More...
 
uORB::PublicationQueued< vehicle_command_ack_s_vehicle_cmd_ack_pub {ORB_ID(vehicle_command_ack)}
 
uORB::PublicationQueued< vehicle_command_s_vehicle_cmd_pub {ORB_ID(vehicle_command)}
 
home_position_s _home_pos {}
 home position for RTL More...
 
mission_result_s _mission_result {}
 
vehicle_global_position_s _global_pos {}
 global vehicle position More...
 
vehicle_gps_position_s _gps_pos {}
 gps position More...
 
vehicle_land_detected_s _land_detected {}
 vehicle land_detected More...
 
vehicle_local_position_s _local_pos {}
 local vehicle position More...
 
vehicle_status_s _vstatus {}
 vehicle status More...
 
uint8_t _previous_nav_state {}
 nav_state of the previous iteration More...
 
geofence_result_s _geofence_result {}
 
position_setpoint_triplet_s _pos_sp_triplet {}
 triplet of position setpoints More...
 
position_setpoint_triplet_s _reposition_triplet {}
 triplet for non-mission direct position command More...
 
position_setpoint_triplet_s _takeoff_triplet {}
 triplet for non-mission direct takeoff command More...
 
vehicle_roi_s _vroi {}
 vehicle ROI More...
 
perf_counter_t _loop_perf
 loop performance counter More...
 
Geofence _geofence
 class that handles the geofence More...
 
bool _geofence_violation_warning_sent {false}
 prevents spaming to mavlink More...
 
bool _can_loiter_at_sp {false}
 flags if current position SP can be used to loiter More...
 
bool _pos_sp_triplet_updated {false}
 flags if position SP triplet needs to be published More...
 
bool _pos_sp_triplet_published_invalid_once {false}
 flags if position SP triplet has been published once to UORB More...
 
bool _mission_result_updated {false}
 flags if mission result has seen an update More...
 
NavigatorMode_navigation_mode {nullptr}
 abstract pointer to current navigation mode class More...
 
Mission _mission
 class that handles the missions More...
 
Loiter _loiter
 class that handles loiter More...
 
Takeoff _takeoff
 class for handling takeoff commands More...
 
Land _land
 class for handling land commands More...
 
PrecLand _precland
 class for handling precision land commands More...
 
RTL _rtl
 class that handles RTL More...
 
RCLoss _rcLoss
 class that handles RTL according to OBC rules (rc loss mode) More...
 
DataLinkLoss _dataLinkLoss
 class that handles the OBC datalink loss mode More...
 
EngineFailure _engineFailure
 class that handles the engine failure mode (FW only!) More...
 
GpsFailure _gpsFailure
 class that handles the OBC gpsfailure loss mode More...
 
FollowTarget _follow_target
 
NavigatorMode_navigation_mode_array [NAVIGATOR_MODE_ARRAY_SIZE]
 array of navigation modes More...
 
param_t _handle_back_trans_dec_mss {PARAM_INVALID}
 
param_t _handle_reverse_delay {PARAM_INVALID}
 
float _param_back_trans_dec_mss {0.f}
 
float _param_reverse_delay {0.f}
 
float _mission_cruising_speed_mc {-1.0f}
 
float _mission_cruising_speed_fw {-1.0f}
 
float _mission_throttle {-1.0f}
 

Detailed Description

Definition at line 89 of file navigator.h.

Constructor & Destructor Documentation

◆ Navigator() [1/2]

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ ~Navigator()

Navigator::~Navigator ( )
override

Definition at line 115 of file navigator_main.cpp.

References _vehicle_status_sub, and orb_unsubscribe().

Here is the call graph for this function:

◆ Navigator() [2/2]

Navigator::Navigator ( const Navigator )
delete

Member Function Documentation

◆ abort_landing()

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ check_traffic()

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ custom_command()

int Navigator::custom_command ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 1072 of file navigator_main.cpp.

References f(), GEOFENCE_FILENAME, is_running(), and print_usage().

Here is the call graph for this function:

◆ DEFINE_PARAMETERS()

Navigator::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 
)
inlineprivate
Parameters
_param_nav_loiter_radloiter radius for fixedwing
_param_nav_acc_radacceptance for takeoff
_param_nav_fw_alt_radacceptance radius for fixedwing altitude
_param_nav_fw_altl_radacceptance radius for fixedwing altitude before landing
_param_nav_mc_alt_radacceptance radius for multicopter altitude
_param_nav_force_vtacceptance radius for multicopter altitude
_param_nav_traff_avoidavoiding other aircraft is enabled

Definition at line 297 of file navigator.h.

◆ fake_traffic()

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.

Parameters
distanceHorizontal distance to this vehicle
directionDirection in earth frame from this vehicle in radians
traffic_headingTravel direction of the traffic in earth frame in radians
altitude_diffAltitude difference, positive is up
hor_velocityHorizontal velocity of traffic, in m/s
ver_velocityVertical 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().

Here is the call graph for this function:

◆ force_vtol()

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().

Here is the caller graph for this function:

◆ get_acceptance_radius() [1/2]

float Navigator::get_acceptance_radius ( )

◆ get_acceptance_radius() [2/2]

float Navigator::get_acceptance_radius ( float  mission_item_radius)

Get the acceptance radius given the mission item preset radius.

Parameters
mission_item_radiusthe radius to use in case the controller-derived radius is smaller
Returns
the distance at which the next waypoint should be used

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.

Here is the call graph for this function:

◆ get_altitude_acceptance_radius()

float Navigator::get_altitude_acceptance_radius ( )

Get the altitude acceptance radius.

Returns
the distance from the target altitude before considering the waypoint reached

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_can_loiter_at_sp()

bool Navigator::get_can_loiter_at_sp ( )
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().

Here is the caller graph for this function:

◆ get_cruising_speed()

float Navigator::get_cruising_speed ( )

Get the cruising speed.

Returns
the desired cruising speed for this mission

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_cruising_throttle()

float Navigator::get_cruising_throttle ( )

Get the target throttle.

Returns
the desired throttle for this mission

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().

Here is the caller graph for this function:

◆ get_default_acceptance_radius()

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().

Here is the caller graph for this function:

◆ get_default_altitude_acceptance_radius()

float Navigator::get_default_altitude_acceptance_radius ( )

Get the default altitude acceptance radius (i.e.

from parameters)

Returns
the distance from the target altitude before considering the waypoint reached

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_geofence()

Geofence& Navigator::get_geofence ( )
inline

Definition at line 168 of file navigator.h.

References _geofence.

Referenced by MissionFeasibilityChecker::checkGeofence().

Here is the caller graph for this function:

◆ get_global_position()

struct vehicle_global_position_s* Navigator::get_global_position ( )
inline

◆ get_home_position()

◆ get_land_detected()

◆ get_local_position()

struct vehicle_local_position_s* Navigator::get_local_position ( )
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().

Here is the caller graph for this function:

◆ get_loiter_min_alt()

float Navigator::get_loiter_min_alt ( ) const
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().

Here is the caller graph for this function:

◆ get_loiter_radius()

float Navigator::get_loiter_radius ( )
inline

◆ get_mavlink_log_pub()

◆ get_mission_landing_alt()

float Navigator::get_mission_landing_alt ( )
inline

Definition at line 275 of file navigator.h.

References _mission, and Mission::get_landing_alt().

Referenced by RTL::find_RTL_destination().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_mission_landing_index()

int Navigator::get_mission_landing_index ( )
inline

Definition at line 272 of file navigator.h.

References _mission, and Mission::get_land_start_index().

Here is the call graph for this function:

◆ get_mission_landing_lat()

double Navigator::get_mission_landing_lat ( )
inline

Definition at line 273 of file navigator.h.

References _mission, and Mission::get_landing_lat().

Referenced by RTL::find_RTL_destination().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_mission_landing_lon()

double Navigator::get_mission_landing_lon ( )
inline

Definition at line 274 of file navigator.h.

References _mission, and Mission::get_landing_lon().

Referenced by RTL::find_RTL_destination().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_mission_result()

◆ get_mission_start_land_available()

bool Navigator::get_mission_start_land_available ( )
inline

Definition at line 271 of file navigator.h.

References _mission, and Mission::get_land_start_available().

Referenced by RTL::find_RTL_destination().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_position_setpoint_triplet()

◆ get_precland()

PrecLand* Navigator::get_precland ( )
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().

Here is the caller graph for this function:

◆ get_reposition_triplet()

struct position_setpoint_triplet_s* Navigator::get_reposition_triplet ( )
inline

Definition at line 154 of file navigator.h.

References _reposition_triplet.

Referenced by Loiter::on_activation(), Loiter::on_active(), Loiter::reposition(), and run().

Here is the caller graph for this function:

◆ get_takeoff_min_alt()

float Navigator::get_takeoff_min_alt ( ) const
inline

Definition at line 286 of file navigator.h.

Referenced by Mission::calculate_takeoff_altitude(), Mission::set_mission_items(), and Takeoff::set_takeoff_position().

Here is the caller graph for this function:

◆ get_takeoff_required()

bool Navigator::get_takeoff_required ( ) const
inline

Definition at line 287 of file navigator.h.

Referenced by MissionFeasibilityChecker::checkTakeoff().

Here is the caller graph for this function:

◆ get_takeoff_triplet()

struct position_setpoint_triplet_s* Navigator::get_takeoff_triplet ( )
inline

Definition at line 155 of file navigator.h.

References _takeoff_triplet.

Referenced by Takeoff::on_active(), run(), and Takeoff::set_takeoff_position().

Here is the caller graph for this function:

◆ get_vroi()

const vehicle_roi_s& Navigator::get_vroi ( )
inline

Definition at line 162 of file navigator.h.

References _vroi.

Referenced by Mission::heading_sp_update(), and Mission::on_active().

Here is the caller graph for this function:

◆ get_vstatus()

◆ get_vtol_back_trans_deceleration()

float Navigator::get_vtol_back_trans_deceleration ( ) const
inline

Definition at line 291 of file navigator.h.

References _param_back_trans_dec_mss.

Referenced by MissionBlock::is_mission_item_reached().

Here is the caller graph for this function:

◆ get_vtol_reverse_delay()

float Navigator::get_vtol_reverse_delay ( ) const
inline

Definition at line 292 of file navigator.h.

References _param_reverse_delay, and force_vtol().

Referenced by MissionBlock::is_mission_item_reached().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_yaw_acceptance()

float Navigator::get_yaw_acceptance ( float  mission_item_yaw)

Get the yaw acceptance given the current mission item.

Parameters
mission_item_yawthe yaw to use in case the controller-derived radius is finite
Returns
the yaw at which the next waypoint should be used or NaN if the yaw at a waypoint should be ignored

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_yaw_threshold()

float Navigator::get_yaw_threshold ( ) const
inline

Definition at line 289 of file navigator.h.

References math::radians().

Referenced by MissionBlock::is_mission_item_reached().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_yaw_timeout()

float Navigator::get_yaw_timeout ( ) const
inline

Definition at line 288 of file navigator.h.

Referenced by MissionBlock::is_mission_item_reached().

Here is the caller graph for this function:

◆ home_alt_valid()

bool Navigator::home_alt_valid ( )
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().

Here is the caller graph for this function:

◆ home_position_valid()

bool Navigator::home_position_valid ( )
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().

Here is the caller graph for this function:

◆ in_rtl_state()

bool Navigator::in_rtl_state ( ) const
inline

Definition at line 280 of file navigator.h.

References _vstatus, abort_landing(), and vehicle_status_s::nav_state.

Here is the call graph for this function:

◆ increment_mission_instance_count()

void Navigator::increment_mission_instance_count ( )
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ instantiate()

Navigator * Navigator::instantiate ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 714 of file navigator_main.cpp.

References ll40ls::instance, and Navigator().

Here is the call graph for this function:

◆ is_planned_mission()

bool Navigator::is_planned_mission ( ) const
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().

Here is the caller graph for this function:

◆ load_fence_from_file()

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().

Here is the call graph for this function:

◆ mission_landing_required()

bool Navigator::mission_landing_required ( )
inline

Definition at line 278 of file navigator.h.

References _rtl, RTL::RTL_LAND, and RTL::rtl_type().

Referenced by Mission::check_mission_valid().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ on_mission_landing()

bool Navigator::on_mission_landing ( )
inline

Definition at line 269 of file navigator.h.

References _mission, and Mission::landing().

Referenced by RTL::on_activation(), and run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ operator=()

Navigator Navigator::operator= ( const Navigator )
delete

◆ params_update()

void Navigator::params_update ( )
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_status()

int Navigator::print_status ( )
override
See also
ModuleBase::print_status()

Definition at line 726 of file navigator_main.cpp.

References _geofence, and Geofence::printStatus().

Here is the call graph for this function:

◆ print_usage()

int Navigator::print_usage ( const char *  reason = nullptr)
static
See also
ModuleBase

Definition at line 1170 of file navigator_main.cpp.

Referenced by custom_command().

Here is the caller graph for this function:

◆ publish_mission_result()

void Navigator::publish_mission_result ( )
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ publish_position_setpoint_triplet()

void Navigator::publish_position_setpoint_triplet ( )
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ publish_vehicle_cmd()

◆ publish_vehicle_command_ack()

void Navigator::publish_vehicle_command_ack ( const vehicle_command_s cmd,
uint8_t  result 
)
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ reset_cruising_speed()

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().

Here is the caller graph for this function:

◆ reset_triplets()

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().

Here is the caller graph for this function:

◆ reset_vroi()

void Navigator::reset_vroi ( )
inline

Definition at line 163 of file navigator.h.

References _vroi.

Referenced by Mission::update_mission().

Here is the caller graph for this function:

◆ rtl_type()

int Navigator::rtl_type ( )
inline

Definition at line 279 of file navigator.h.

References _rtl, and RTL::rtl_type().

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ run()

void Navigator::run ( )
override
See also
ModuleBase::run()

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.

◆ set_can_loiter_at_sp()

void Navigator::set_can_loiter_at_sp ( bool  can_loiter)
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().

Here is the caller graph for this function:

◆ set_cruising_speed()

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().

Here is the caller graph for this function:

◆ set_cruising_throttle()

void Navigator::set_cruising_throttle ( float  throttle = -1.0f)
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_mission_failure()

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_mission_result_updated()

◆ set_position_setpoint_triplet_updated()

◆ start_mission_landing()

bool Navigator::start_mission_landing ( )
inline

Definition at line 270 of file navigator.h.

References _mission, and Mission::land_start().

Referenced by run(), and RTL::set_rtl_item().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ task_spawn()

int Navigator::task_spawn ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 697 of file navigator_main.cpp.

Member Data Documentation

◆ _can_loiter_at_sp

bool Navigator::_can_loiter_at_sp {false}
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().

◆ _dataLinkLoss

DataLinkLoss Navigator::_dataLinkLoss
private

class that handles the OBC datalink loss mode

Definition at line 378 of file navigator.h.

Referenced by Navigator(), and run().

◆ _engineFailure

EngineFailure Navigator::_engineFailure
private

class that handles the engine failure mode (FW only!)

Definition at line 379 of file navigator.h.

Referenced by Navigator(), and run().

◆ _follow_target

FollowTarget Navigator::_follow_target
private

Definition at line 381 of file navigator.h.

Referenced by Navigator(), and run().

◆ _geofence

Geofence Navigator::_geofence
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().

◆ _geofence_result

geofence_result_s Navigator::_geofence_result {}
private

Definition at line 354 of file navigator.h.

Referenced by run().

◆ _geofence_result_pub

uORB::Publication<geofence_result_s> Navigator::_geofence_result_pub {ORB_ID(geofence_result)}
private

Definition at line 332 of file navigator.h.

Referenced by run().

◆ _geofence_violation_warning_sent

bool Navigator::_geofence_violation_warning_sent {false}
private

prevents spaming to mavlink

Definition at line 363 of file navigator.h.

Referenced by run().

◆ _global_pos

vehicle_global_position_s Navigator::_global_pos {}
private

global vehicle position

Definition at line 345 of file navigator.h.

Referenced by get_global_position(), and run().

◆ _global_pos_sub

uORB::Subscription Navigator::_global_pos_sub {ORB_ID(vehicle_global_position)}
private

global position subscription

Definition at line 321 of file navigator.h.

Referenced by run().

◆ _gps_pos

vehicle_gps_position_s Navigator::_gps_pos {}
private

gps position

Definition at line 346 of file navigator.h.

Referenced by run().

◆ _gps_pos_sub

uORB::Subscription Navigator::_gps_pos_sub {ORB_ID(vehicle_gps_position)}
private

gps position subscription

Definition at line 322 of file navigator.h.

Referenced by run().

◆ _gpsFailure

GpsFailure Navigator::_gpsFailure
private

class that handles the OBC gpsfailure loss mode

Definition at line 380 of file navigator.h.

Referenced by Navigator(), and run().

◆ _handle_back_trans_dec_mss

param_t Navigator::_handle_back_trans_dec_mss {PARAM_INVALID}
private

Definition at line 385 of file navigator.h.

Referenced by Navigator(), and params_update().

◆ _handle_reverse_delay

param_t Navigator::_handle_reverse_delay {PARAM_INVALID}
private

Definition at line 386 of file navigator.h.

Referenced by Navigator(), and params_update().

◆ _home_pos

home_position_s Navigator::_home_pos {}
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().

◆ _home_pos_sub

uORB::Subscription Navigator::_home_pos_sub {ORB_ID(home_position)}
private

home position subscription

Definition at line 323 of file navigator.h.

Referenced by run().

◆ _land

Land Navigator::_land
private

class for handling land commands

Definition at line 374 of file navigator.h.

Referenced by Navigator(), and run().

◆ _land_detected

vehicle_land_detected_s Navigator::_land_detected {}
private

vehicle land_detected

Definition at line 347 of file navigator.h.

Referenced by get_land_detected(), and run().

◆ _land_detected_sub

uORB::Subscription Navigator::_land_detected_sub {ORB_ID(vehicle_land_detected)}
private

vehicle land detected subscription

Definition at line 324 of file navigator.h.

Referenced by run().

◆ _local_pos

vehicle_local_position_s Navigator::_local_pos {}
private

local vehicle position

Definition at line 348 of file navigator.h.

Referenced by get_local_position(), and run().

◆ _loiter

Loiter Navigator::_loiter
private

class that handles loiter

Definition at line 372 of file navigator.h.

Referenced by Navigator(), and run().

◆ _loop_perf

perf_counter_t Navigator::_loop_perf
private

loop performance counter

Definition at line 360 of file navigator.h.

Referenced by run().

◆ _mavlink_log_pub

orb_advert_t Navigator::_mavlink_log_pub {nullptr}
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().

◆ _mission

◆ _mission_cruising_speed_fw

float Navigator::_mission_cruising_speed_fw {-1.0f}
private

Definition at line 391 of file navigator.h.

Referenced by get_cruising_speed(), reset_cruising_speed(), and set_cruising_speed().

◆ _mission_cruising_speed_mc

float Navigator::_mission_cruising_speed_mc {-1.0f}
private

Definition at line 390 of file navigator.h.

Referenced by get_cruising_speed(), reset_cruising_speed(), and set_cruising_speed().

◆ _mission_result

mission_result_s Navigator::_mission_result {}
private

◆ _mission_result_pub

uORB::Publication<mission_result_s> Navigator::_mission_result_pub {ORB_ID(mission_result)}
private

Definition at line 333 of file navigator.h.

Referenced by publish_mission_result().

◆ _mission_result_updated

bool Navigator::_mission_result_updated {false}
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().

◆ _mission_throttle

float Navigator::_mission_throttle {-1.0f}
private

Definition at line 392 of file navigator.h.

Referenced by get_cruising_throttle(), and set_cruising_throttle().

◆ _navigation_mode

NavigatorMode* Navigator::_navigation_mode {nullptr}
private

abstract pointer to current navigation mode class

Definition at line 370 of file navigator.h.

Referenced by is_planned_mission(), and run().

◆ _navigation_mode_array

NavigatorMode* Navigator::_navigation_mode_array[NAVIGATOR_MODE_ARRAY_SIZE]
private

array of navigation modes

Definition at line 383 of file navigator.h.

Referenced by Navigator(), and run().

◆ _param_back_trans_dec_mss

float Navigator::_param_back_trans_dec_mss {0.f}
private

Definition at line 387 of file navigator.h.

Referenced by get_vtol_back_trans_deceleration(), and params_update().

◆ _param_reverse_delay

float Navigator::_param_reverse_delay {0.f}
private

Definition at line 388 of file navigator.h.

Referenced by get_vtol_reverse_delay(), and params_update().

◆ _parameter_update_sub

uORB::Subscription Navigator::_parameter_update_sub {ORB_ID(parameter_update)}
private

param update subscription

Definition at line 325 of file navigator.h.

Referenced by run().

◆ _pos_ctrl_landing_status_sub

uORB::Subscription Navigator::_pos_ctrl_landing_status_sub {ORB_ID(position_controller_landing_status)}
private

position controller landing status subscription

Definition at line 326 of file navigator.h.

Referenced by abort_landing().

◆ _pos_sp_triplet

◆ _pos_sp_triplet_pub

uORB::Publication<position_setpoint_triplet_s> Navigator::_pos_sp_triplet_pub {ORB_ID(position_setpoint_triplet)}
private

Definition at line 334 of file navigator.h.

Referenced by publish_position_setpoint_triplet().

◆ _pos_sp_triplet_published_invalid_once

bool Navigator::_pos_sp_triplet_published_invalid_once {false}
private

flags if position SP triplet has been published once to UORB

Definition at line 367 of file navigator.h.

Referenced by run().

◆ _pos_sp_triplet_updated

bool Navigator::_pos_sp_triplet_updated {false}
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().

◆ _position_controller_status_sub

uORB::SubscriptionData<position_controller_status_s> Navigator::_position_controller_status_sub {ORB_ID(position_controller_status)}
private

◆ _precland

PrecLand Navigator::_precland
private

class for handling precision land commands

Definition at line 375 of file navigator.h.

Referenced by get_precland(), Navigator(), and run().

◆ _previous_nav_state

uint8_t Navigator::_previous_nav_state {}
private

nav_state of the previous iteration

Definition at line 351 of file navigator.h.

Referenced by run().

◆ _rcLoss

RCLoss Navigator::_rcLoss
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().

◆ _reposition_triplet

position_setpoint_triplet_s Navigator::_reposition_triplet {}
private

triplet for non-mission direct position command

Definition at line 356 of file navigator.h.

Referenced by get_reposition_triplet().

◆ _rtl

RTL Navigator::_rtl
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().

◆ _takeoff

Takeoff Navigator::_takeoff
private

class for handling takeoff commands

Definition at line 373 of file navigator.h.

Referenced by Navigator(), and run().

◆ _takeoff_triplet

position_setpoint_triplet_s Navigator::_takeoff_triplet {}
private

triplet for non-mission direct takeoff command

Definition at line 357 of file navigator.h.

Referenced by get_takeoff_triplet().

◆ _traffic_sub

uORB::Subscription Navigator::_traffic_sub {ORB_ID(transponder_report)}
private

traffic subscription

Definition at line 327 of file navigator.h.

Referenced by check_traffic().

◆ _vehicle_cmd_ack_pub

uORB::PublicationQueued<vehicle_command_ack_s> Navigator::_vehicle_cmd_ack_pub {ORB_ID(vehicle_command_ack)}
private

Definition at line 339 of file navigator.h.

Referenced by publish_vehicle_command_ack().

◆ _vehicle_cmd_pub

uORB::PublicationQueued<vehicle_command_s> Navigator::_vehicle_cmd_pub {ORB_ID(vehicle_command)}
private

Definition at line 340 of file navigator.h.

Referenced by publish_vehicle_cmd().

◆ _vehicle_command_sub

uORB::Subscription Navigator::_vehicle_command_sub {ORB_ID(vehicle_command)}
private

vehicle commands (onboard and offboard)

Definition at line 328 of file navigator.h.

Referenced by run().

◆ _vehicle_roi_pub

uORB::Publication<vehicle_roi_s> Navigator::_vehicle_roi_pub {ORB_ID(vehicle_roi)}
private

Definition at line 335 of file navigator.h.

Referenced by run().

◆ _vehicle_status_sub

int Navigator::_vehicle_status_sub {-1}
private

local position subscription

local position subscription

Definition at line 319 of file navigator.h.

Referenced by Navigator(), run(), and ~Navigator().

◆ _vroi

vehicle_roi_s Navigator::_vroi {}
private

vehicle ROI

Definition at line 358 of file navigator.h.

Referenced by get_vroi(), reset_vroi(), and run().

◆ _vstatus

vehicle_status_s Navigator::_vstatus {}
private

The documentation for this class was generated from the following files: