|
PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <Takeoff.hpp>
Public Member Functions | |
| Takeoff ()=default | |
| ~Takeoff ()=default | |
| void | setTakeoffRampTime (const float seconds) |
| void | setSpoolupTime (const float seconds) |
| void | generateInitialRampValue (const float hover_thrust, const float velocity_p_gain) |
| Calculate a vertical velocity to initialize the takeoff ramp that when passed to the velocity controller results in a zero throttle setpoint. More... | |
| void | updateTakeoffState (const bool armed, const bool landed, const bool want_takeoff, const float takeoff_desired_vz, const bool skip_takeoff, const hrt_abstime &now_us) |
| Update the state for the takeoff. More... | |
| float | updateRamp (const float dt, const float takeoff_desired_vz) |
| Update and return the velocity constraint ramp value during takeoff. More... | |
| TakeoffState | getTakeoffState () |
| Takeoff (Navigator *navigator) | |
| ~Takeoff ()=default | |
| void | on_activation () override |
| This function is called one time when mode becomes active, pos_sp_triplet must be initialized here. More... | |
| void | on_active () override |
| This function is called while the mode is active. More... | |
Public Member Functions inherited from MissionBlock | |
| MissionBlock (Navigator *navigator) | |
| Constructor. More... | |
| virtual | ~MissionBlock ()=default |
| MissionBlock (const MissionBlock &)=delete | |
| MissionBlock & | operator= (const MissionBlock &)=delete |
Public Member Functions inherited from NavigatorMode | |
| NavigatorMode (Navigator *navigator) | |
| virtual | ~NavigatorMode ()=default |
| NavigatorMode (const NavigatorMode &)=delete | |
| NavigatorMode | operator= (const NavigatorMode &)=delete |
| void | run (bool active) |
| virtual void | on_inactive () |
| This function is called while the mode is inactive. More... | |
| virtual void | on_inactivation () |
| This function is called one time when mode becomes inactive. More... | |
Private Member Functions | |
| void | set_takeoff_position () |
Private Attributes | |
| TakeoffState | _takeoff_state = TakeoffState::disarmed |
| float | _takeoff_ramp_time = 0.f |
| float | _takeoff_ramp_vz_init = 0.f |
| float | _takeoff_ramp_vz = 0.f |
| systemlib::Hysteresis | _spoolup_time_hysteresis {false} |
| becomes true MPC_SPOOLUP_TIME seconds after the vehicle was armed More... | |
Additional Inherited Members | |
Static Public Member Functions inherited from MissionBlock | |
| static bool | item_contains_position (const mission_item_s &item) |
Protected Member Functions inherited from MissionBlock | |
| bool | is_mission_item_reached () |
| Check if mission item has been reached. More... | |
| void | reset_mission_item_reached () |
| Reset all reached flags. More... | |
| bool | mission_item_to_position_setpoint (const mission_item_s &item, position_setpoint_s *sp) |
| Convert a mission item to a position setpoint. More... | |
| void | set_loiter_item (struct mission_item_s *item, float min_clearance=-1.0f) |
| Set a loiter mission item, if possible reuse the position setpoint, otherwise take the current position. More... | |
| void | set_takeoff_item (struct mission_item_s *item, float abs_altitude, float min_pitch=0.0f) |
| Set a takeoff mission item. More... | |
| void | set_land_item (struct mission_item_s *item, bool at_current_location) |
| Set a land mission item. More... | |
| void | set_idle_item (struct mission_item_s *item) |
| Set idle mission item. More... | |
| void | set_vtol_transition_item (struct mission_item_s *item, const uint8_t new_mode) |
| Set vtol transition item. More... | |
| void | mission_apply_limitation (mission_item_s &item) |
| General function used to adjust the mission item based on vehicle specific limitations. More... | |
| void | issue_command (const mission_item_s &item) |
| float | get_time_inside (const mission_item_s &item) const |
| float | get_absolute_altitude_for_item (const mission_item_s &mission_item) const |
Protected Attributes inherited from MissionBlock | |
| mission_item_s | _mission_item {} |
| bool | _waypoint_position_reached {false} |
| bool | _waypoint_yaw_reached {false} |
| bool | _waypoint_position_reached_previously {false} |
| hrt_abstime | _time_first_inside_orbit {0} |
| hrt_abstime | _action_start {0} |
| hrt_abstime | _time_wp_reached {0} |
| uORB::Publication< actuator_controls_s > | _actuator_pub {ORB_ID(actuator_controls_2)} |
Protected Attributes inherited from NavigatorMode | |
| Navigator * | _navigator {nullptr} |
Definition at line 55 of file Takeoff.hpp.
|
default |
|
default |
| Takeoff::Takeoff | ( | Navigator * | navigator | ) |
Definition at line 44 of file takeoff.cpp.
|
default |
| void Takeoff::generateInitialRampValue | ( | const float | hover_thrust, |
| const float | velocity_p_gain | ||
| ) |
Calculate a vertical velocity to initialize the takeoff ramp that when passed to the velocity controller results in a zero throttle setpoint.
| hover_thrust | normalized thrsut value with which the vehicle hovers |
| velocity_p_gain | proportional gain of the velocity controller to calculate the thrust |
Definition at line 41 of file Takeoff.cpp.
References _takeoff_ramp_vz_init, f(), and math::max().
Referenced by MulticopterPositionControl::parameters_update().
|
inline |
Definition at line 91 of file Takeoff.hpp.
Referenced by MulticopterPositionControl::Run(), and TEST().
|
overridevirtual |
This function is called one time when mode becomes active, pos_sp_triplet must be initialized here.
Reimplemented from NavigatorMode.
Definition at line 50 of file takeoff.cpp.
References set_takeoff_position().
|
overridevirtual |
This function is called while the mode is active.
Reimplemented from NavigatorMode.
Definition at line 56 of file takeoff.cpp.
References MissionBlock::_mission_item, NavigatorMode::_navigator, position_setpoint_triplet_s::current, mission_result_s::finished, Navigator::get_mission_result(), Navigator::get_position_setpoint_triplet(), Navigator::get_takeoff_triplet(), MissionBlock::is_mission_item_reached(), MissionBlock::mission_apply_limitation(), MissionBlock::mission_item_to_position_setpoint(), MissionBlock::set_loiter_item(), Navigator::set_mission_result_updated(), Navigator::set_position_setpoint_triplet_updated(), set_takeoff_position(), and position_setpoint_s::valid.
|
private |
Definition at line 78 of file takeoff.cpp.
References MissionBlock::_mission_item, NavigatorMode::_navigator, vehicle_global_position_s::alt, position_setpoint_s::alt, position_setpoint_triplet_s::current, f(), mission_result_s::finished, Navigator::get_global_position(), Navigator::get_mavlink_log_pub(), Navigator::get_mission_result(), Navigator::get_position_setpoint_triplet(), Navigator::get_takeoff_min_alt(), Navigator::get_takeoff_triplet(), Navigator::home_position_valid(), position_setpoint_s::lat, position_setpoint_s::lon, mavlink_log_critical, mavlink_log_info, MissionBlock::mission_apply_limitation(), MissionBlock::mission_item_to_position_setpoint(), position_setpoint_triplet_s::next, position_setpoint_triplet_s::previous, MissionBlock::reset_mission_item_reached(), Navigator::set_can_loiter_at_sp(), Navigator::set_mission_result_updated(), Navigator::set_position_setpoint_triplet_updated(), MissionBlock::set_takeoff_item(), position_setpoint_s::valid, position_setpoint_s::yaw, and position_setpoint_s::yaw_valid.
Referenced by on_activation(), and on_active().
|
inline |
Definition at line 63 of file Takeoff.hpp.
References armed, dt, and hrt_abstime.
Referenced by MulticopterPositionControl::parameters_update().
|
inline |
Definition at line 62 of file Takeoff.hpp.
Referenced by MulticopterPositionControl::parameters_update().
| float Takeoff::updateRamp | ( | const float | dt, |
| const float | takeoff_desired_vz | ||
| ) |
Update and return the velocity constraint ramp value during takeoff.
By ramping up _takeoff_ramp_vz during the takeoff and using it to constain the maximum climb rate a smooth takeoff behavior is achieved. Returns zero on the ground and takeoff_desired_vz in flight.
| dt | time in seconds since the last call/loop iteration |
| takeoff_desired_vz | end value for the velocity ramp |
Definition at line 111 of file Takeoff.cpp.
References _takeoff_ramp_time, _takeoff_ramp_vz, _takeoff_ramp_vz_init, _takeoff_state, and rampup.
Referenced by MulticopterPositionControl::Run().
| void Takeoff::updateTakeoffState | ( | const bool | armed, |
| const bool | landed, | ||
| const bool | want_takeoff, | ||
| const float | takeoff_desired_vz, | ||
| const bool | skip_takeoff, | ||
| const hrt_abstime & | now_us | ||
| ) |
Update the state for the takeoff.
| setpoint | a vehicle_local_position_setpoint_s structure |
Definition at line 47 of file Takeoff.cpp.
References _spoolup_time_hysteresis, _takeoff_ramp_vz, _takeoff_ramp_vz_init, _takeoff_state, disarmed, flight, systemlib::Hysteresis::get_state(), rampup, ready_for_takeoff, systemlib::Hysteresis::set_state_and_update(), and spoolup.
Referenced by MulticopterPositionControl::Run().
|
private |
becomes true MPC_SPOOLUP_TIME seconds after the vehicle was armed
Definition at line 100 of file Takeoff.hpp.
Referenced by updateTakeoffState().
|
private |
Definition at line 96 of file Takeoff.hpp.
Referenced by updateRamp().
|
private |
Definition at line 98 of file Takeoff.hpp.
Referenced by updateRamp(), and updateTakeoffState().
|
private |
Definition at line 97 of file Takeoff.hpp.
Referenced by generateInitialRampValue(), updateRamp(), and updateTakeoffState().
|
private |
Definition at line 94 of file Takeoff.hpp.
Referenced by updateRamp(), and updateTakeoffState().