/**************************************************************************** * * Copyright (c) 2017 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in * the documentation and/or other materials provided with the * distribution. * 3. Neither the name PX4 nor the names of its contributors may be * used to endorse or promote products derived from this software * without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * ****************************************************************************/ #pragma once /* Helper classes */ #include "Arming/PreFlightCheck/PreFlightCheck.hpp" #include "failure_detector/FailureDetector.hpp" #include "ManualControl.hpp" #include "state_machine_helper.h" #include "worker_thread.hpp" #include #include #include #include #include // publications #include #include #include #include #include #include #include #include #include // subscriptions #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include using math::constrain; using systemlib::Hysteresis; using namespace time_literals; class Commander : public ModuleBase, public ModuleParams { public: Commander(); /** @see ModuleBase */ static int task_spawn(int argc, char *argv[]); /** @see ModuleBase */ static Commander *instantiate(int argc, char *argv[]); /** @see ModuleBase */ static int custom_command(int argc, char *argv[]); /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); /** @see ModuleBase::run() */ void run() override; /** @see ModuleBase::print_status() */ int print_status() override; void enable_hil(); void get_circuit_breaker_params(); private: void answer_command(const vehicle_command_s &cmd, uint8_t result); transition_result_t arm(arm_disarm_reason_t calling_reason, bool run_preflight_checks = true); transition_result_t disarm(arm_disarm_reason_t calling_reason); transition_result_t try_mode_change(main_state_t desired_mode); void battery_status_check(); bool check_posvel_validity(const bool data_valid, const float data_accuracy, const float required_accuracy, const hrt_abstime &data_timestamp_us, hrt_abstime *last_fail_time_us, hrt_abstime *probation_time_us, bool *valid_state); void control_status_leds(bool changed, const uint8_t battery_warning); /** * Checks the status of all available data links and handles switching between different system telemetry states. */ void data_link_check(); void avoidance_check(); void esc_status_check(const esc_status_s &esc_status); void estimator_check(); bool handle_command(const vehicle_command_s &cmd); unsigned handle_command_motor_test(const vehicle_command_s &cmd); void mission_init(); void offboard_control_update(); void print_reject_mode(uint8_t main_state); void reset_posvel_validity(); bool set_home_position(); bool set_home_position_alt_only(); bool set_in_air_home_position(); bool isGPosGoodForInitializingHomePos(const vehicle_global_position_s &gpos) const; void fillLocalHomePos(home_position_s &home, const vehicle_local_position_s &lpos) const; void fillLocalHomePos(home_position_s &home, float x, float y, float z, float heading) const; void fillGlobalHomePos(home_position_s &home, const vehicle_global_position_s &gpos) const; void fillGlobalHomePos(home_position_s &home, double lat, double lon, float alt) const; void setHomePosValid(); void updateHomePositionYaw(float yaw); void update_control_mode(); void UpdateEstimateValidity(); // Set the main system state based on RC and override device inputs transition_result_t set_main_state(bool &changed); // Enable override (manual reversion mode) on the system transition_result_t set_main_state_override_on(bool &changed); // Set the system main state based on the current RC inputs transition_result_t set_main_state_rc(); bool shutdown_if_allowed(); bool stabilization_required(); DEFINE_PARAMETERS( (ParamInt) _param_nav_dll_act, (ParamInt) _param_com_dl_loss_t, (ParamInt) _param_com_hldl_loss_t, (ParamInt) _param_com_hldl_reg_t, (ParamInt) _param_nav_rcl_act, (ParamFloat) _param_com_rcl_act_t, (ParamFloat) _param_com_home_h_t, (ParamFloat) _param_com_home_v_t, (ParamBool) _param_com_home_in_air, (ParamFloat) _param_com_pos_fs_eph, (ParamFloat) _param_com_pos_fs_epv, /*Not realy used for now*/ (ParamFloat) _param_com_vel_fs_evh, (ParamInt) _param_com_posctl_navl, /* failsafe response to loss of navigation accuracy */ (ParamInt) _param_com_pos_fs_delay, (ParamInt) _param_com_pos_fs_prob, (ParamInt) _param_com_pos_fs_gain, (ParamInt) _param_com_low_bat_act, (ParamFloat) _param_com_disarm_land, (ParamFloat) _param_com_disarm_preflight, (ParamBool) _param_com_obs_avoid, (ParamInt) _param_com_flt_profile, // Offboard (ParamFloat) _param_com_of_loss_t, (ParamInt) _param_com_obl_act, (ParamInt) _param_com_obl_rc_act, (ParamInt) _param_com_prearm_mode, (ParamBool) _param_com_mot_test_en, (ParamFloat) _param_com_kill_disarm, (ParamFloat) _param_com_lkdown_tko, // Engine failure (ParamFloat) _param_ef_throttle_thres, (ParamFloat) _param_ef_current2throttle_thres, (ParamFloat) _param_ef_time_thres, (ParamBool) _param_arm_without_gps, (ParamBool) _param_arm_mission_required, (ParamBool) _param_arm_auth_required, (ParamBool) _param_escs_checks_required, (ParamBool) _param_com_rearm_grace, (ParamInt) _param_flight_uuid, (ParamInt) _param_takeoff_finished_action, (ParamInt) _param_rc_in_off, (ParamInt) _param_fltmode_1, (ParamInt) _param_fltmode_2, (ParamInt) _param_fltmode_3, (ParamInt) _param_fltmode_4, (ParamInt) _param_fltmode_5, (ParamInt) _param_fltmode_6, // Circuit breakers (ParamInt) _param_cbrk_supply_chk, (ParamInt) _param_cbrk_usb_chk, (ParamInt) _param_cbrk_airspd_chk, (ParamInt) _param_cbrk_enginefail, (ParamInt) _param_cbrk_flightterm, (ParamInt) _param_cbrk_velposerr, (ParamInt) _param_cbrk_vtolarming, // Geofrence (ParamInt) _param_geofence_action, // Mavlink (ParamInt) _param_mav_comp_id, (ParamInt) _param_mav_sys_id, (ParamInt) _param_mav_type, (ParamFloat) _param_cp_dist, (ParamFloat) _param_bat_low_thr, (ParamFloat) _param_bat_crit_thr ) enum class PrearmedMode { DISABLED = 0, SAFETY_BUTTON = 1, ALWAYS = 2 }; /* Decouple update interval and hysteresis counters, all depends on intervals */ static constexpr uint64_t COMMANDER_MONITORING_INTERVAL{10_ms}; static constexpr uint64_t HOTPLUG_SENS_TIMEOUT{8_s}; /**< wait for hotplug sensors to come online for upto 8 seconds */ static constexpr uint64_t INAIR_RESTART_HOLDOFF_INTERVAL{500_ms}; const int64_t POSVEL_PROBATION_MIN = 1_s; /**< minimum probation duration (usec) */ const int64_t POSVEL_PROBATION_MAX = 100_s; /**< maximum probation duration (usec) */ PreFlightCheck::arm_requirements_t _arm_requirements{}; hrt_abstime _valid_distance_sensor_time_us{0}; /**< Last time that distance sensor data arrived (usec) */ hrt_abstime _last_gpos_fail_time_us{0}; /**< Last time that the global position validity recovery check failed (usec) */ hrt_abstime _last_lpos_fail_time_us{0}; /**< Last time that the local position validity recovery check failed (usec) */ hrt_abstime _last_lvel_fail_time_us{0}; /**< Last time that the local velocity validity recovery check failed (usec) */ // Probation times for position and velocity validity checks to pass if failed hrt_abstime _gpos_probation_time_us = POSVEL_PROBATION_MIN; hrt_abstime _lpos_probation_time_us = POSVEL_PROBATION_MIN; hrt_abstime _lvel_probation_time_us = POSVEL_PROBATION_MIN; /* class variables used to check for navigation failure after takeoff */ hrt_abstime _time_last_innov_pass{0}; /**< last time velocity and position innovations passed */ hrt_abstime _time_last_innov_fail{0}; /**< last time velocity and position innovations failed */ bool _nav_test_passed{false}; /**< true if the post takeoff navigation test has passed */ bool _nav_test_failed{false}; /**< true if the post takeoff navigation test has failed */ bool _geofence_loiter_on{false}; bool _geofence_rtl_on{false}; bool _geofence_land_on{false}; bool _geofence_warning_action_on{false}; bool _geofence_violated_prev{false}; FailureDetector _failure_detector; bool _flight_termination_triggered{false}; bool _lockdown_triggered{false}; hrt_abstime _datalink_last_heartbeat_gcs{0}; hrt_abstime _datalink_last_heartbeat_avoidance_system{0}; hrt_abstime _datalink_last_heartbeat_onboard_controller{0}; bool _onboard_controller_lost{false}; bool _avoidance_system_lost{false}; hrt_abstime _high_latency_datalink_heartbeat{0}; hrt_abstime _high_latency_datalink_lost{0}; int _last_esc_online_flags{-1}; uint8_t _battery_warning{battery_status_s::BATTERY_WARNING_NONE}; float _battery_current{0.0f}; Hysteresis _auto_disarm_landed{false}; Hysteresis _auto_disarm_killed{false}; Hysteresis _offboard_available{false}; hrt_abstime _last_print_mode_reject_time{0}; ///< To remember when last notification was sent bool _last_condition_local_altitude_valid{false}; bool _last_condition_local_position_valid{false}; bool _last_condition_global_position_valid{false}; bool _last_overload{false}; unsigned int _leds_counter{0}; manual_control_switches_s _manual_control_switches{}; manual_control_switches_s _last_manual_control_switches{}; ManualControl _manual_control{this}; hrt_abstime _rc_signal_lost_timestamp{0}; ///< Time at which the RC reception was lost int32_t _flight_mode_slots[manual_control_switches_s::MODE_SLOT_NUM] {}; hrt_abstime _boot_timestamp{0}; hrt_abstime _last_disarmed_timestamp{0}; hrt_abstime _timestamp_engine_healthy{0}; ///< absolute time when engine was healty hrt_abstime _overload_start{0}; ///< time when CPU overload started uint32_t _counter{0}; uint8_t _heading_reset_counter{0}; bool _status_changed{true}; bool _arm_tune_played{false}; bool _was_armed{false}; bool _failsafe_old{false}; ///< check which state machines for changes, clear "changed" flag bool _have_taken_off_since_arming{false}; bool _should_set_home_on_takeoff{true}; bool _flight_termination_printed{false}; bool _system_power_usb_connected{false}; cpuload_s _cpuload{}; geofence_result_s _geofence_result{}; vehicle_land_detected_s _land_detector{}; safety_s _safety{}; vtol_vehicle_status_s _vtol_status{}; // commander publications actuator_armed_s _armed{}; commander_state_s _internal_state{}; vehicle_control_mode_s _vehicle_control_mode{}; vehicle_status_s _status{}; vehicle_status_flags_s _status_flags{}; WorkerThread _worker_thread; // Subscriptions uORB::Subscription _actuator_controls_sub{ORB_ID_VEHICLE_ATTITUDE_CONTROLS}; uORB::Subscription _cmd_sub {ORB_ID(vehicle_command)}; uORB::Subscription _cpuload_sub{ORB_ID(cpuload)}; uORB::Subscription _esc_status_sub{ORB_ID(esc_status)}; uORB::Subscription _estimator_selector_status_sub{ORB_ID(estimator_selector_status)}; uORB::Subscription _geofence_result_sub{ORB_ID(geofence_result)}; uORB::Subscription _iridiumsbd_status_sub{ORB_ID(iridiumsbd_status)}; uORB::Subscription _land_detector_sub{ORB_ID(vehicle_land_detected)}; uORB::Subscription _safety_sub{ORB_ID(safety)}; uORB::Subscription _manual_control_switches_sub{ORB_ID(manual_control_switches)}; uORB::Subscription _system_power_sub{ORB_ID(system_power)}; uORB::Subscription _vehicle_angular_velocity_sub{ORB_ID(vehicle_angular_velocity)}; uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; uORB::Subscription _vtol_vehicle_status_sub{ORB_ID(vtol_vehicle_status)}; uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::SubscriptionMultiArray _battery_status_subs{ORB_ID::battery_status}; uORB::SubscriptionMultiArray _distance_sensor_subs{ORB_ID::distance_sensor}; uORB::SubscriptionMultiArray _telemetry_status_subs{ORB_ID::telemetry_status}; #if defined(BOARD_HAS_POWER_CONTROL) uORB::Subscription _power_button_state_sub {ORB_ID(power_button_state)}; #endif // BOARD_HAS_POWER_CONTROL uORB::SubscriptionData _airspeed_sub{ORB_ID(airspeed)}; uORB::SubscriptionData _estimator_status_sub{ORB_ID(estimator_status)}; uORB::SubscriptionData _mission_result_sub{ORB_ID(mission_result)}; uORB::SubscriptionData _offboard_control_mode_sub{ORB_ID(offboard_control_mode)}; uORB::SubscriptionData _global_position_sub{ORB_ID(vehicle_global_position)}; uORB::SubscriptionData _local_position_sub{ORB_ID(vehicle_local_position)}; uORB::SubscriptionData _rtl_flight_time_sub{ORB_ID(rtl_flight_time)}; // Publications uORB::Publication _armed_pub{ORB_ID(actuator_armed)}; uORB::Publication _commander_state_pub{ORB_ID(commander_state)}; uORB::Publication _test_motor_pub{ORB_ID(test_motor)}; uORB::Publication _control_mode_pub{ORB_ID(vehicle_control_mode)}; uORB::Publication _vehicle_status_flags_pub{ORB_ID(vehicle_status_flags)}; uORB::Publication _status_pub{ORB_ID(vehicle_status)}; uORB::Publication _mission_pub{ORB_ID(mission)}; uORB::Publication _landing_gear_pub{ORB_ID(landing_gear)}; uORB::PublicationData _home_pub{ORB_ID(home_position)}; uORB::Publication _command_ack_pub{ORB_ID(vehicle_command_ack)}; orb_advert_t _mavlink_log_pub{nullptr}; };