|
PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <FlightTaskAutoMapper2.hpp>
Public Member Functions | |
| FlightTaskAutoMapper2 ()=default | |
| virtual | ~FlightTaskAutoMapper2 ()=default |
| bool | activate (vehicle_local_position_setpoint_s last_setpoint) override |
| Call once on the event where you switch to the task. More... | |
| bool | update () override |
| To be called regularly in the control loop cycle to execute the task. More... | |
Public Member Functions inherited from FlightTaskAuto | |
| FlightTaskAuto () | |
| virtual | ~FlightTaskAuto ()=default |
| bool | updateInitialize () override |
| Call before activate() or update() to initialize time and input data. More... | |
| bool | updateFinalize () override |
| Call after update() to constrain the generated setpoints in order to comply with the constraints of the current mode. More... | |
| void | setYawHandler (WeatherVane *ext_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 FlightTask | |
| FlightTask () | |
| virtual | ~FlightTask ()=default |
| virtual void | reActivate () |
| Call this to reset an active Flight Task. More... | |
| virtual bool | applyCommandParameters (const vehicle_command_s &command) |
| To be called to adopt parameters from an arrived vehicle command. 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 | |
| virtual void | _generateSetpoints ()=0 |
| Generate velocity and position setpoint for following line. More... | |
| void | _prepareIdleSetpoints () |
| void | _prepareLandSetpoints () |
| void | _prepareVelocitySetpoints () |
| void | _prepareTakeoffSetpoints () |
| void | _preparePositionSetpoints () |
| void | _updateAltitudeAboveGround () |
| Computes altitude above ground based on sensors available. More... | |
| void | updateParams () override |
| See ModuleParam class. More... | |
| DEFINE_PARAMETERS_CUSTOM_PARENT (FlightTaskAuto,(ParamFloat< px4::params::MPC_LAND_SPEED >) _param_mpc_land_speed,(ParamFloat< px4::params::MPC_TILTMAX_LND >) _param_mpc_tiltmax_lnd,(ParamInt< px4::params::MPC_LAND_RC_HELP >) _param_mpc_land_rc_help,(ParamFloat< px4::params::MPC_LAND_ALT1 >) _param_mpc_land_alt1,(ParamFloat< px4::params::MPC_LAND_ALT2 >) _param_mpc_land_alt2,(ParamFloat< px4::params::MPC_TKO_SPEED >) _param_mpc_tko_speed) | |
Protected Member Functions inherited from FlightTaskAuto | |
| void | _setDefaultConstraints () override |
| Set constraints to default values. More... | |
| matrix::Vector2f | _getTargetVelocityXY () |
| only used for follow-me and only here because of legacy reason. More... | |
| void | _updateInternalWaypoints () |
| Depending on state of vehicle, the internal waypoints might differ from target (for instance if offtrack). More... | |
| bool | _compute_heading_from_2D_vector (float &heading, matrix::Vector2f v) |
| Computes and sets heading a 2D vector. More... | |
| DEFINE_PARAMETERS_CUSTOM_PARENT (FlightTask,(ParamFloat< px4::params::MPC_XY_CRUISE >) _param_mpc_xy_cruise,(ParamFloat< px4::params::MPC_CRUISE_90 >) _param_mpc_cruise_90,(ParamFloat< px4::params::NAV_MC_ALT_RAD >) _param_nav_mc_alt_rad,(ParamInt< px4::params::MPC_YAW_MODE >) _param_mpc_yaw_mode,(ParamInt< px4::params::COM_OBS_AVOID >) _param_com_obs_avoid,(ParamFloat< px4::params::MPC_YAWRAUTO_MAX >) _param_mpc_yawrauto_max,(ParamFloat< px4::params::MIS_YAW_ERR >) _param_mis_yaw_err,(ParamBool< px4::params::WV_EN >) _param_wv_en) | |
Protected Member Functions inherited from FlightTask | |
| void | _resetSetpoints () |
| Reset all setpoints to NAN. More... | |
| void | _evaluateVehicleLocalPosition () |
| Check and update local position. More... | |
| virtual bool | _checkTakeoff () |
| Determine when to trigger a takeoff (ignored in flight) 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 () |
| virtual void | _ekfResetHandlerHeading (float delta_psi) |
Protected Attributes | |
| float | _alt_above_ground {0.0f} |
| If home provided, then it is altitude above home, otherwise it is altitude above local position reference. More... | |
Protected Attributes inherited from FlightTaskAuto | |
| matrix::Vector3f | _prev_prev_wp {} |
| Pre-previous waypoint (local frame). More... | |
| matrix::Vector3f | _prev_wp {} |
| Previous waypoint (local frame). More... | |
| matrix::Vector3f | _target {} |
| Target waypoint (local frame). More... | |
| matrix::Vector3f | _next_wp {} |
| The next waypoint after target (local frame). More... | |
| float | _mc_cruise_speed {0.0f} |
| Requested cruise speed. More... | |
| WaypointType | _type {WaypointType::idle} |
| Type of current target triplet. More... | |
| uORB::SubscriptionData< home_position_s > | _sub_home_position {ORB_ID(home_position)} |
| uORB::SubscriptionData< manual_control_setpoint_s > | _sub_manual_control_setpoint {ORB_ID(manual_control_setpoint)} |
| uORB::SubscriptionData< vehicle_status_s > | _sub_vehicle_status {ORB_ID(vehicle_status)} |
| State | _current_state {State::none} |
| float | _target_acceptance_radius {0.0f} |
| Acceptances radius of the target. More... | |
| int | _mission_gear {landing_gear_s::GEAR_KEEP} |
| float | _yaw_sp_prev {NAN} |
| bool | _yaw_sp_aligned {false} |
| ObstacleAvoidance | _obstacle_avoidance |
| class adjusting setpoints according to external avoidance module's input 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... | |
Private Member Functions | |
| void | _reset () |
| Resets member variables to current vehicle state. More... | |
| bool | _highEnoughForLandingGear () |
| Checks if gears can be lowered. More... | |
| float | _getLandSpeed () |
| Returns landing descent speed. More... | |
Private Attributes | |
| WaypointType | _type_previous {WaypointType::idle} |
| Previous type of current target triplet. 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 45 of file FlightTaskAutoMapper2.hpp.
|
default |
|
virtualdefault |
|
protectedpure virtual |
Generate velocity and position setpoint for following line.
Implemented in FlightTaskAutoLineSmoothVel.
|
private |
Returns landing descent speed.
Definition at line 199 of file FlightTaskAutoMapper2.cpp.
References f().
|
private |
Checks if gears can be lowered.
Definition at line 193 of file FlightTaskAutoMapper2.cpp.
|
protected |
Definition at line 122 of file FlightTaskAutoMapper2.cpp.
|
protected |
Definition at line 130 of file FlightTaskAutoMapper2.cpp.
References math::radians().
|
protected |
Definition at line 163 of file FlightTaskAutoMapper2.cpp.
|
protected |
Definition at line 143 of file FlightTaskAutoMapper2.cpp.
|
protected |
Definition at line 154 of file FlightTaskAutoMapper2.cpp.
|
private |
Resets member variables to current vehicle state.
Definition at line 115 of file FlightTaskAutoMapper2.cpp.
|
protected |
Computes altitude above ground based on sensors available.
Definition at line 170 of file FlightTaskAutoMapper2.cpp.
|
overridevirtual |
Call once on the event where you switch to the task.
| state | of the previous task |
Reimplemented from FlightTaskAuto.
Definition at line 43 of file FlightTaskAutoMapper2.cpp.
References FlightTaskAuto::activate().
Referenced by FlightTaskAutoLineSmoothVel::activate().
|
protected |
|
overridevirtual |
To be called regularly in the control loop cycle to execute the task.
Implements FlightTask.
Definition at line 50 of file FlightTaskAutoMapper2.cpp.
References idle, land, loiter, position, takeoff, and velocity.
|
overrideprotected |
See ModuleParam class.
Definition at line 185 of file FlightTaskAutoMapper2.cpp.
References math::max().
|
protected |
If home provided, then it is altitude above home, otherwise it is altitude above local position reference.
Definition at line 66 of file FlightTaskAutoMapper2.hpp.
|
private |
Previous type of current target triplet.
Definition at line 82 of file FlightTaskAutoMapper2.hpp.