/**************************************************************************** * * Copyright (c) 2013-2020 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. * ****************************************************************************/ /** * Multicopter position controller. */ #pragma once #include "PositionControl/PositionControl.hpp" #include "Takeoff/Takeoff.hpp" #include "GotoControl/GotoControl.hpp" #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 namespace time_literals; class MulticopterPositionControl : public ModuleBase, public control::SuperBlock, public ModuleParams, public px4::ScheduledWorkItem { public: MulticopterPositionControl(bool vtol = false); ~MulticopterPositionControl() override; /** @see ModuleBase */ static int task_spawn(int argc, char *argv[]); /** @see ModuleBase */ static int custom_command(int argc, char *argv[]); /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); bool init(); private: void Run() override; TakeoffHandling _takeoff; /**< state machine and ramp to bring the vehicle off the ground without jumps */ orb_advert_t _mavlink_log_pub{nullptr}; uORB::PublicationData _takeoff_status_pub{ORB_ID(takeoff_status)}; uORB::Publication _vehicle_attitude_setpoint_pub{ORB_ID(vehicle_attitude_setpoint)}; uORB::Publication _local_pos_sp_pub{ORB_ID(vehicle_local_position_setpoint)}; /**< vehicle local position setpoint publication */ uORB::SubscriptionCallbackWorkItem _local_pos_sub{this, ORB_ID(vehicle_local_position)}; /**< vehicle local position */ uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::Subscription _hover_thrust_estimate_sub{ORB_ID(hover_thrust_estimate)}; uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; uORB::Subscription _vehicle_constraints_sub{ORB_ID(vehicle_constraints)}; uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; uORB::Subscription _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)}; hrt_abstime _time_stamp_last_loop{0}; /**< time stamp of last loop iteration */ hrt_abstime _time_position_control_enabled{0}; trajectory_setpoint_s _setpoint{PositionControl::empty_trajectory_setpoint}; vehicle_control_mode_s _vehicle_control_mode{}; vehicle_constraints_s _vehicle_constraints { .timestamp = 0, .speed_up = NAN, .speed_down = NAN, .want_takeoff = false, }; vehicle_land_detected_s _vehicle_land_detected { .timestamp = 0, .freefall = false, .ground_contact = true, .maybe_landed = true, .landed = true, }; DEFINE_PARAMETERS( // Position Control (ParamFloat) _param_mpc_xy_p, (ParamFloat) _param_mpc_z_p, (ParamFloat) _param_mpc_xy_vel_p_acc, (ParamFloat) _param_mpc_xy_vel_i_acc, (ParamFloat) _param_mpc_xy_vel_d_acc, (ParamFloat) _param_mpc_z_vel_p_acc, (ParamFloat) _param_mpc_z_vel_i_acc, (ParamFloat) _param_mpc_z_vel_d_acc, (ParamFloat) _param_mpc_xy_vel_max, (ParamFloat) _param_mpc_z_v_auto_up, (ParamFloat) _param_mpc_z_vel_max_up, (ParamFloat) _param_mpc_z_v_auto_dn, (ParamFloat) _param_mpc_z_vel_max_dn, (ParamFloat) _param_mpc_tiltmax_air, (ParamFloat) _param_mpc_thr_hover, (ParamBool) _param_mpc_use_hte, // Takeoff / Land (ParamFloat) _param_com_spoolup_time, /**< time to let motors spool up after arming */ (ParamBool) _param_com_throw_en, /**< throw launch enabled */ (ParamFloat) _param_mpc_tko_ramp_t, /**< time constant for smooth takeoff ramp */ (ParamFloat) _param_mpc_tko_speed, (ParamFloat) _param_mpc_land_speed, (ParamFloat) _param_mpc_vel_manual, (ParamFloat) _param_mpc_vel_man_back, (ParamFloat) _param_mpc_vel_man_side, (ParamFloat) _param_mpc_xy_cruise, (ParamFloat) _param_mpc_land_alt2, /**< downwards speed limited below this altitude */ (ParamInt) _param_mpc_pos_mode, (ParamInt) _param_mpc_alt_mode, (ParamFloat) _param_mpc_tiltmax_lnd, /**< maximum tilt for landing and smooth takeoff */ (ParamFloat) _param_mpc_thr_min, (ParamFloat) _param_mpc_thr_max, (ParamFloat) _param_mpc_thr_xy_marg, (ParamFloat) _param_sys_vehicle_resp, (ParamFloat) _param_mpc_acc_hor, (ParamFloat) _param_mpc_acc_down_max, (ParamFloat) _param_mpc_acc_up_max, (ParamFloat) _param_mpc_acc_hor_max, (ParamFloat) _param_mpc_jerk_auto, (ParamFloat) _param_mpc_jerk_max, (ParamFloat) _param_mpc_man_y_max, (ParamFloat) _param_mpc_man_y_tau, (ParamFloat) _param_mpc_xy_vel_all, (ParamFloat) _param_mpc_z_vel_all, (ParamFloat) _param_mpc_xy_err_max, (ParamFloat) _param_mpc_yawrauto_max, (ParamFloat) _param_mpc_yawrauto_acc ); control::BlockDerivative _vel_x_deriv; /**< velocity derivative in x */ control::BlockDerivative _vel_y_deriv; /**< velocity derivative in y */ control::BlockDerivative _vel_z_deriv; /**< velocity derivative in z */ GotoControl _goto_control; ///< class for handling smooth goto position setpoints PositionControl _control; ///< class for core PID position control hrt_abstime _last_warn{0}; /**< timer when the last warn message was sent out */ bool _hover_thrust_initialized{false}; /** Timeout in us for trajectory data to get considered invalid */ static constexpr uint64_t TRAJECTORY_STREAM_TIMEOUT_US = 500_ms; /** During smooth-takeoff, below ALTITUDE_THRESHOLD the yaw-control is turned off and tilt is limited */ static constexpr float ALTITUDE_THRESHOLD = 0.3f; static constexpr float MAX_SAFE_TILT_DEG = 89.f; // Numerical issues above this value due to tanf SlewRate _tilt_limit_slew_rate; uint8_t _vxy_reset_counter{0}; uint8_t _vz_reset_counter{0}; uint8_t _xy_reset_counter{0}; uint8_t _z_reset_counter{0}; uint8_t _heading_reset_counter{0}; perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle time")}; /** * Update our local parameter cache. * Parameter update can be forced when argument is true. * @param force forces parameter update. */ void parameters_update(bool force); /** * Check for validity of positon/velocity states. */ PositionControlStates set_vehicle_states(const vehicle_local_position_s &local_pos); /** * Generate setpoint to bridge no executable setpoint being available. * Used to handle transitions where no proper setpoint was generated yet and when the received setpoint is invalid. * This should only happen briefly when transitioning and never during mode operation or by design. */ trajectory_setpoint_s generateFailsafeSetpoint(const hrt_abstime &now, const PositionControlStates &states, bool warn); /** * @brief adjust existing (or older) setpoint with any EKF reset deltas and update the local counters * * @param[in] vehicle_local_position struct containing EKF reset deltas and counters * @param[out] setpoint trajectory setpoint struct to be adjusted */ void adjustSetpointForEKFResets(const vehicle_local_position_s &vehicle_local_position, trajectory_setpoint_s &setpoint); };