|
PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <FlightTaskManualPosition.hpp>
Public Member Functions | |
| FlightTaskManualPosition () | |
| virtual | ~FlightTaskManualPosition ()=default |
| bool | activate (vehicle_local_position_setpoint_s last_setpoint) override |
| Call once on the event where you switch to the task. More... | |
| bool | updateInitialize () override |
| Call before activate() or update() to initialize time and input data. More... | |
| void | setYawHandler (WeatherVane *yaw_handler) override |
| Sets an external yaw handler which can be used to implement a different yaw control strategy. More... | |
Public Member Functions inherited from FlightTaskManualAltitude | |
| FlightTaskManualAltitude ()=default | |
| virtual | ~FlightTaskManualAltitude ()=default |
| bool | update () override |
| To be called regularly in the control loop cycle to execute the task. More... | |
Public Member Functions inherited from FlightTaskManual | |
| FlightTaskManual ()=default | |
| virtual | ~FlightTaskManual ()=default |
| bool | applyCommandParameters (const vehicle_command_s &command) override |
| To be called to adopt parameters from an arrived vehicle command. More... | |
Public Member Functions inherited from FlightTask | |
| FlightTask () | |
| virtual | ~FlightTask ()=default |
| virtual void | reActivate () |
| Call this to reset an active Flight Task. More... | |
| virtual bool | updateFinalize () |
| Call after update() to constrain the generated setpoints in order to comply with the constraints of the current mode. More... | |
| const vehicle_local_position_setpoint_s | getPositionSetpoint () |
| Get the output data. More... | |
| const vehicle_constraints_s & | getConstraints () |
| Get vehicle constraints. More... | |
| const landing_gear_s & | getGear () |
| Get landing gear position. More... | |
| const vehicle_trajectory_waypoint_s & | getAvoidanceWaypoint () |
| Get avoidance desired waypoint. More... | |
| void | handleParameterUpdate () |
| Call this whenever a parameter update notification is received (parameter_update uORB message) More... | |
| void | updateVelocityControllerIO (const matrix::Vector3f &vel_sp, const matrix::Vector3f &thrust_sp) |
Protected Member Functions | |
| void | _updateXYlock () |
| applies position lock based on stick and velocity More... | |
| void | _updateSetpoints () override |
| updates all setpoints More... | |
| void | _scaleSticks () override |
| scales sticks to velocity in z More... | |
Protected Member Functions inherited from FlightTaskManualAltitude | |
| void | _updateHeadingSetpoints () |
| sets yaw or yaw speed More... | |
| void | _ekfResetHandlerHeading (float delta_psi) override |
| adjust heading setpoint in case of EKF reset event More... | |
| bool | _checkTakeoff () override |
| Determine when to trigger a takeoff (ignored in flight) More... | |
| void | _rotateIntoHeadingFrame (matrix::Vector2f &vec) |
| rotates vector into local frame More... | |
| void | _updateAltitudeLock () |
| Check and sets for position lock. More... | |
| DEFINE_PARAMETERS_CUSTOM_PARENT(FlightTaskManual,(ParamFloat< px4::params::MPC_HOLD_MAX_Z >) _param_mpc_hold_max_z,(ParamInt< px4::params::MPC_ALT_MODE >) _param_mpc_alt_mode,(ParamFloat< px4::params::MPC_HOLD_MAX_XY >) _param_mpc_hold_max_xy,(ParamFloat< px4::params::MPC_Z_P >) _param_mpc_z_p,(ParamFloat< px4::params::MPC_MAN_Y_MAX >) _param_mpc_man_y_max,(ParamFloat< px4::params::MPC_MAN_Y_TAU >) _param_mpc_man_y_tau,(ParamFloat< px4::params::MPC_MAN_TILT_MAX >) _param_mpc_man_tilt_max,(ParamFloat< px4::params::MPC_LAND_ALT1 >) _param_mpc_land_alt1,(ParamFloat< px4::params::MPC_LAND_ALT2 >) _param_mpc_land_alt2,(ParamFloat< px4::params::MPC_LAND_SPEED >) _param_mpc_land_speed,(ParamFloat< px4::params::MPC_TKO_SPEED >) _param_mpc_tko_speed) private void | _unlockYaw () |
| void | _lockYaw () |
| float | _applyYawspeedFilter (float yawspeed_target) |
| Filter between stick input and yaw setpoint. More... | |
| void | _terrainFollowing (bool apply_brake, bool stopped) |
| Terrain following. More... | |
| void | _respectMinAltitude () |
| Minimum Altitude during range sensor operation. More... | |
| void | _respectMaxAltitude () |
| void | _respectGroundSlowdown () |
| Sets downwards velocity constraint based on the distance to ground. More... | |
Protected Member Functions inherited from FlightTaskManual | |
| float | stickDeadzone () const |
Protected Member Functions inherited from FlightTask | |
| void | _resetSetpoints () |
| Reset all setpoints to NAN. More... | |
| void | _evaluateVehicleLocalPosition () |
| Check and update local position. More... | |
| virtual void | _setDefaultConstraints () |
| Set constraints to default values. More... | |
| void | _initEkfResetCounters () |
| Monitor the EKF reset counters and call the appropriate handling functions in case of a reset event. More... | |
| void | _checkEkfResetCounters () |
| virtual void | _ekfResetHandlerPositionXY () |
| virtual void | _ekfResetHandlerVelocityXY () |
| virtual void | _ekfResetHandlerPositionZ () |
| virtual void | _ekfResetHandlerVelocityZ () |
Protected Attributes | |
| DEFINE_PARAMETERS_CUSTOM_PARENT(FlightTaskManualAltitude,(ParamFloat< px4::params::MPC_VEL_MANUAL >) _param_mpc_vel_manual,(ParamFloat< px4::params::MPC_ACC_HOR_MAX >) _param_mpc_acc_hor_max,(ParamFloat< px4::params::MPC_HOLD_MAX_XY >) _param_mpc_hold_max_xy,(ParamFloat< px4::params::MPC_ACC_HOR_ESTM >) _param_mpc_acc_hor_estm) private uint8_t | _reset_counter {0} |
| counter for estimator resets in xy-direction More... | |
| WeatherVane * | _weathervane_yaw_handler |
| external weathervane library, used to implement a yaw control law that turns the vehicle nose into the wind More... | |
| CollisionPrevention | _collision_prevention |
| collision avoidance setpoint amendment More... | |
Protected Attributes inherited from FlightTaskManualAltitude | |
| uORB::SubscriptionData< home_position_s > | _sub_home_position {ORB_ID(home_position)} |
| float | _yawspeed_filter_state {} |
| state of low-pass filter in rad/s More... | |
| uint8_t | _reset_counter = 0 |
| counter for estimator resets in z-direction More... | |
| float | _max_speed_up = 10.0f |
| float | _min_speed_down = 1.0f |
| bool | _terrain_follow {false} |
| true when the vehicle is following the terrain height More... | |
| bool | _terrain_hold {false} |
| true when vehicle is controlling height above a static ground position More... | |
| float | _dist_to_ground_lock = NAN |
| Distance to ground during terrain following. More... | |
Protected Attributes inherited from FlightTaskManual | |
| bool | _sticks_data_required = true |
| let inherited task-class define if it depends on stick data More... | |
| matrix::Vector< float, 4 > | _sticks |
| unmodified manual stick inputs More... | |
| matrix::Vector< float, 4 > | _sticks_expo |
| modified manual sticks using expo function More... | |
| int | _gear_switch_old = manual_control_setpoint_s::SWITCH_POS_NONE |
| old switch state More... | |
Protected Attributes inherited from FlightTask | |
| uORB::SubscriptionData< vehicle_local_position_s > | _sub_vehicle_local_position {ORB_ID(vehicle_local_position)} |
| uORB::SubscriptionData< vehicle_attitude_s > | _sub_attitude {ORB_ID(vehicle_attitude)} |
| float | _time = 0 |
| passed time in seconds since the task was activated More... | |
| float | _deltatime = 0 |
| passed time in seconds since the task was last updated More... | |
| hrt_abstime | _time_stamp_activate = 0 |
| time stamp when task was activated More... | |
| hrt_abstime | _time_stamp_current = 0 |
| time stamp at the beginning of the current task update More... | |
| hrt_abstime | _time_stamp_last = 0 |
| time stamp when task was last updated More... | |
| matrix::Vector3f | _position |
| current vehicle position More... | |
| matrix::Vector3f | _velocity |
| current vehicle velocity More... | |
| float | _yaw = 0.f |
| current vehicle yaw heading More... | |
| float | _dist_to_bottom = 0.0f |
| current height above ground level More... | |
| matrix::Vector3f | _position_setpoint |
| Setpoints which the position controller has to execute. More... | |
| matrix::Vector3f | _velocity_setpoint |
| matrix::Vector3f | _acceleration_setpoint |
| matrix::Vector3f | _jerk_setpoint |
| matrix::Vector3f | _thrust_setpoint |
| float | _yaw_setpoint |
| float | _yawspeed_setpoint |
| matrix::Vector3f | _velocity_setpoint_feedback |
| matrix::Vector3f | _thrust_setpoint_feedback |
| struct { | |
| uint8_t xy = 0 | |
| uint8_t vxy = 0 | |
| uint8_t z = 0 | |
| uint8_t vz = 0 | |
| uint8_t quat = 0 | |
| } | _reset_counters |
| vehicle_constraints_s | _constraints {} |
| Vehicle constraints. More... | |
| landing_gear_s | _gear {} |
| vehicle_trajectory_waypoint_s | _desired_waypoint {} |
| Desired waypoints. More... | |
Additional Inherited Members | |
Static Public Attributes inherited from FlightTask | |
| static const vehicle_local_position_setpoint_s | empty_setpoint = {0, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, {NAN, NAN, NAN}, {NAN, NAN, NAN}, {NAN, NAN, NAN}, {}} |
| Empty setpoint. More... | |
| static const vehicle_constraints_s | empty_constraints = {0, NAN, NAN, NAN, NAN, NAN, NAN, NAN, false, {}} |
| Empty constraints. More... | |
| static const landing_gear_s | empty_landing_gear_default_keep = {0, landing_gear_s::GEAR_KEEP, {}} |
| default landing gear state More... | |
Static Protected Attributes inherited from FlightTask | |
| static constexpr uint64_t | _timeout = 500000 |
| maximal time in us before a loop or data times out More... | |
Definition at line 46 of file FlightTaskManualPosition.hpp.
| FlightTaskManualPosition::FlightTaskManualPosition | ( | ) |
Definition at line 44 of file FlightTaskManualPosition.cpp.
|
virtualdefault |
|
overrideprotectedvirtual |
scales sticks to velocity in z
Reimplemented from FlightTaskManualAltitude.
Definition at line 81 of file FlightTaskManualPosition.cpp.
References _collision_prevention, FlightTask::_constraints, FlightTask::_deltatime, FlightTask::_position, FlightTaskManualAltitude::_rotateIntoHeadingFrame(), FlightTaskManualAltitude::_scaleSticks(), FlightTaskManual::_sticks_expo, FlightTask::_sub_vehicle_local_position, FlightTask::_velocity, FlightTask::_velocity_setpoint, math::constrain(), f(), FLT_EPSILON, uORB::SubscriptionData< T >::get(), CollisionPrevention::is_active(), matrix::Vector< Type, M >::length(), CollisionPrevention::modifySetpoint(), matrix::Vector< Type, M >::normalized(), vehicle_constraints_s::speed_xy, and vehicle_local_position_s::vxy_max.
Referenced by setYawHandler().
|
overrideprotectedvirtual |
updates all setpoints
Reimplemented from FlightTaskManualAltitude.
Reimplemented in FlightTaskManualPositionSmoothVel, and FlightTaskManualPositionSmooth.
Definition at line 159 of file FlightTaskManualPosition.cpp.
References FlightTask::_thrust_setpoint, FlightTaskManualAltitude::_updateSetpoints(), _updateXYlock(), _weathervane_yaw_handler, FlightTask::_yaw_setpoint, FlightTask::_yawspeed_setpoint, WeatherVane::get_weathervane_yawrate(), WeatherVane::is_active(), and matrix::Matrix< Type, M, N >::setAll().
Referenced by FlightTaskManualPositionSmooth::_updateSetpoints(), FlightTaskManualPositionSmoothVel::_updateSetpoints(), and setYawHandler().
|
protected |
applies position lock based on stick and velocity
Definition at line 132 of file FlightTaskManualPosition.cpp.
References FlightTask::_position, FlightTask::_position_setpoint, _reset_counter, FlightTask::_sub_vehicle_local_position, FlightTask::_velocity, FlightTask::_velocity_setpoint, FLT_EPSILON, uORB::SubscriptionData< T >::get(), and vehicle_local_position_s::xy_reset_counter.
Referenced by FlightTaskManualPositionSmooth::_updateSetpoints(), _updateSetpoints(), and setYawHandler().
|
overridevirtual |
Call once on the event where you switch to the task.
| state | of the previous task |
Reimplemented from FlightTaskManualAltitude.
Reimplemented in FlightTaskManualPositionSmoothVel, and FlightTaskSport.
Definition at line 59 of file FlightTaskManualPosition.cpp.
References FlightTask::_constraints, FlightTask::_position, FlightTask::_position_setpoint, FlightTask::_velocity_setpoint, FlightTaskManualAltitude::activate(), math::radians(), vehicle_constraints_s::speed_xy, and vehicle_constraints_s::tilt.
Referenced by FlightTaskSport::activate(), and FlightTaskManualPositionSmoothVel::activate().
|
inlineoverridevirtual |
Sets an external yaw handler which can be used to implement a different yaw control strategy.
Reimplemented from FlightTask.
Definition at line 58 of file FlightTaskManualPosition.hpp.
References _scaleSticks(), _updateSetpoints(), _updateXYlock(), and _weathervane_yaw_handler.
|
overridevirtual |
Call before activate() or update() to initialize time and input data.
Reimplemented from FlightTaskManualAltitude.
Definition at line 49 of file FlightTaskManualPosition.cpp.
References FlightTask::_position, FlightTask::_velocity, and FlightTaskManualAltitude::updateInitialize().
|
protected |
collision avoidance setpoint amendment
Definition at line 79 of file FlightTaskManualPosition.hpp.
Referenced by _scaleSticks().
|
protected |
counter for estimator resets in xy-direction
Definition at line 74 of file FlightTaskManualPosition.hpp.
Referenced by _updateXYlock().
|
protected |
external weathervane library, used to implement a yaw control law that turns the vehicle nose into the wind
Definition at line 76 of file FlightTaskManualPosition.hpp.
Referenced by _updateSetpoints(), and setYawHandler().