2020-10-22 10:34:08 -04:00
/****************************************************************************
*
* 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 <commander/px4_custom_mode.h>
# include <drivers/drv_hrt.h>
# include <lib/controllib/blocks.hpp>
# include <lib/flight_tasks/FlightTasks.hpp>
# include <lib/hysteresis/hysteresis.h>
# include <lib/mathlib/mathlib.h>
# include <lib/matrix/matrix/math.hpp>
# include <lib/perf/perf_counter.h>
# include <lib/systemlib/mavlink_log.h>
# include <lib/weather_vane/WeatherVane.hpp>
# include <px4_platform_common/px4_config.h>
# include <px4_platform_common/defines.h>
# include <px4_platform_common/module.h>
# include <px4_platform_common/module_params.h>
# include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
# include <px4_platform_common/posix.h>
# include <px4_platform_common/tasks.h>
# include <uORB/Publication.hpp>
# include <uORB/Subscription.hpp>
# include <uORB/SubscriptionCallback.hpp>
# include <uORB/topics/home_position.h>
# include <uORB/topics/landing_gear.h>
# include <uORB/topics/parameter_update.h>
# include <uORB/topics/vehicle_attitude_setpoint.h>
# include <uORB/topics/vehicle_control_mode.h>
# include <uORB/topics/vehicle_land_detected.h>
# include <uORB/topics/vehicle_local_position.h>
# include <uORB/topics/vehicle_local_position_setpoint.h>
# include <uORB/topics/vehicle_status.h>
# include <uORB/topics/vehicle_trajectory_waypoint.h>
# include <uORB/topics/hover_thrust_estimate.h>
# include "PositionControl/PositionControl.hpp"
# include "Takeoff/Takeoff.hpp"
# include <float.h>
class MulticopterPositionControl : public ModuleBase < MulticopterPositionControl > , public control : : SuperBlock ,
public ModuleParams , public px4 : : WorkItem
{
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 ;
Takeoff _takeoff ; /**< state machine and ramp to bring the vehicle off the ground without jumps */
uORB : : Publication < vehicle_attitude_setpoint_s > _vehicle_attitude_setpoint_pub ;
orb_advert_t _mavlink_log_pub { nullptr } ;
uORB : : Publication < vehicle_local_position_setpoint_s > _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 : : Subscription _control_mode_sub { ORB_ID ( vehicle_control_mode ) } ; /**< vehicle control mode subscription */
uORB : : Subscription _parameter_update_sub { ORB_ID ( parameter_update ) } ; /**< notification of parameter updates */
uORB : : Subscription _hover_thrust_estimate_sub { ORB_ID ( hover_thrust_estimate ) } ;
2020-10-24 10:30:12 +02:00
uORB : : Subscription _trajectory_setpoint_sub { ORB_ID ( trajectory_setpoint ) } ;
uORB : : Subscription _vehicle_constraints_sub { ORB_ID ( vehicle_constraints ) } ;
2020-10-22 10:34:08 -04:00
hrt_abstime _time_stamp_last_loop { 0 } ; /**< time stamp of last loop iteration */
int _task_failure_count { 0 } ; /**< counter for task failures */
/**< vehicle-land-detection: initialze to landed */
vehicle_land_detected_s _vehicle_land_detected = {
. timestamp = 0 ,
. alt_max = - 1.0f ,
. freefall = false ,
. ground_contact = true ,
. maybe_landed = true ,
. landed = true ,
} ;
vehicle_control_mode_s _control_mode { } ; /**< vehicle control mode */
vehicle_local_position_s _local_pos { } ; /**< vehicle local position */
home_position_s _home_pos { } ; /**< home position */
2020-12-11 12:11:35 -05:00
2020-10-22 10:34:08 -04:00
int8_t _old_landing_gear_position { landing_gear_s : : GEAR_KEEP } ;
DEFINE_PARAMETERS (
// Position Control
( ParamFloat < px4 : : params : : MPC_XY_P > ) _param_mpc_xy_p ,
( ParamFloat < px4 : : params : : MPC_Z_P > ) _param_mpc_z_p ,
( ParamFloat < px4 : : params : : MPC_XY_VEL_P_ACC > ) _param_mpc_xy_vel_p_acc ,
( ParamFloat < px4 : : params : : MPC_XY_VEL_I_ACC > ) _param_mpc_xy_vel_i_acc ,
( ParamFloat < px4 : : params : : MPC_XY_VEL_D_ACC > ) _param_mpc_xy_vel_d_acc ,
( ParamFloat < px4 : : params : : MPC_Z_VEL_P_ACC > ) _param_mpc_z_vel_p_acc ,
( ParamFloat < px4 : : params : : MPC_Z_VEL_I_ACC > ) _param_mpc_z_vel_i_acc ,
( ParamFloat < px4 : : params : : MPC_Z_VEL_D_ACC > ) _param_mpc_z_vel_d_acc ,
( ParamFloat < px4 : : params : : MPC_XY_VEL_MAX > ) _param_mpc_xy_vel_max ,
( ParamFloat < px4 : : params : : MPC_Z_VEL_MAX_UP > ) _param_mpc_z_vel_max_up ,
( ParamFloat < px4 : : params : : MPC_Z_VEL_MAX_DN > ) _param_mpc_z_vel_max_dn ,
( ParamFloat < px4 : : params : : MPC_TILTMAX_AIR > ) _param_mpc_tiltmax_air ,
( ParamFloat < px4 : : params : : MPC_THR_HOVER > ) _param_mpc_thr_hover ,
( ParamBool < px4 : : params : : MPC_USE_HTE > ) _param_mpc_use_hte ,
// Takeoff / Land
( ParamFloat < px4 : : params : : MPC_TKO_SPEED > ) _param_mpc_tko_speed ,
( ParamFloat < px4 : : params : : MPC_LAND_SPEED > ) _param_mpc_land_speed ,
( ParamFloat < px4 : : params : : MPC_VEL_MANUAL > ) _param_mpc_vel_manual ,
( ParamFloat < px4 : : params : : MPC_XY_CRUISE > ) _param_mpc_xy_cruise ,
( ParamFloat < px4 : : params : : MPC_LAND_ALT2 > ) _param_mpc_land_alt2 , /**< downwards speed limited below this altitude */
( ParamInt < px4 : : params : : MPC_POS_MODE > ) _param_mpc_pos_mode ,
( ParamInt < px4 : : params : : MPC_ALT_MODE > ) _param_mpc_alt_mode ,
( ParamFloat < px4 : : params : : MPC_TILTMAX_LND > ) _param_mpc_tiltmax_lnd , /**< maximum tilt for landing and smooth takeoff */
( ParamFloat < px4 : : params : : MPC_THR_MIN > ) _param_mpc_thr_min ,
( ParamFloat < px4 : : params : : MPC_THR_MAX > ) _param_mpc_thr_max
) ;
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 */
PositionControl _control ; /**< class for core PID position control */
PositionControlStates _states { } ; /**< structure containing vehicle state information for position control */
hrt_abstime _last_warn = 0 ; /**< timer when the last warn message was sent out */
bool _in_failsafe = false ; /**< true if failsafe was entered within current cycle */
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 ;
/** If Flighttask fails, keep 0.2 seconds the current setpoint before going into failsafe land */
static constexpr uint64_t LOITER_TIME_BEFORE_DESCEND = 200 _ms ;
/** During smooth-takeoff, below ALTITUDE_THRESHOLD the yaw-control is turned off ant 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
systemlib : : Hysteresis _failsafe_land_hysteresis { false } ; /**< becomes true if task did not update correctly for LOITER_TIME_BEFORE_DESCEND */
perf_counter_t _cycle_perf ;
/**
* Update our local parameter cache .
* Parameter update can be forced when argument is true .
* @ param force forces parameter update .
*/
int parameters_update ( bool force ) ;
/**
* Check for changes in subscribed topics .
*/
void poll_subscriptions ( ) ;
/**
* Check for validity of positon / velocity states .
* @ param vel_sp_z velocity setpoint in z - direction
*/
void set_vehicle_states ( const float & vel_sp_z ) ;
/**
* Adjust the setpoint during landing .
* Thrust is adjusted to support the land - detector during detection .
* @ param setpoint gets adjusted based on land - detector state
*/
void limit_thrust_during_landing ( vehicle_attitude_setpoint_s & setpoint ) ;
/**
* Failsafe .
* If flighttask fails for whatever reason , then do failsafe . This could
* occur if the commander fails to switch to a mode in case of invalid states or
* setpoints . The failsafe will occur after LOITER_TIME_BEFORE_DESCEND . If force is set
* to true , the failsafe will be initiated immediately .
*/
void failsafe ( const hrt_abstime & now , vehicle_local_position_setpoint_s & setpoint , const PositionControlStates & states ,
2020-10-24 14:35:27 +02:00
bool warn ) ;
2020-10-22 10:34:08 -04:00
/**
* Reset setpoints to NAN
*/
void reset_setpoint_to_nan ( vehicle_local_position_setpoint_s & setpoint ) ;
} ;