PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Public Member Functions | |
MulticopterPositionControl () | |
~MulticopterPositionControl () override | |
void | Run () override |
bool | init () |
int | print_status () override |
Public Member Functions inherited from control::SuperBlock | |
SuperBlock (SuperBlock *parent, const char *name) | |
~SuperBlock ()=default | |
SuperBlock (const SuperBlock &)=delete | |
SuperBlock & | operator= (const SuperBlock &)=delete |
SuperBlock (SuperBlock &&)=delete | |
SuperBlock & | operator= (SuperBlock &&)=delete |
void | setDt (float dt) override |
void | updateParams () override |
Public Member Functions inherited from control::Block | |
Block (SuperBlock *parent, const char *name) | |
virtual | ~Block ()=default |
Block (const Block &)=delete | |
Block & | operator= (const Block &)=delete |
Block (Block &&)=delete | |
Block & | operator= (Block &&)=delete |
void | getName (char *name, size_t n) |
float | getDt () |
Public Member Functions inherited from ListNode< Block *> | |
void | setSibling (Block * sibling) |
const Block * | getSibling () const |
Static Public Member Functions | |
static int | task_spawn (int argc, char *argv[]) |
static int | custom_command (int argc, char *argv[]) |
static int | print_usage (const char *reason=nullptr) |
Private Member Functions | |
DEFINE_PARAMETERS ((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 >) _param_mpc_xy_vel_p,(ParamFloat< px4::params::MPC_XY_VEL_I >) _param_mpc_xy_vel_i,(ParamFloat< px4::params::MPC_XY_VEL_D >) _param_mpc_xy_vel_d,(ParamFloat< px4::params::MPC_Z_VEL_P >) _param_mpc_z_vel_p,(ParamFloat< px4::params::MPC_Z_VEL_I >) _param_mpc_z_vel_i,(ParamFloat< px4::params::MPC_Z_VEL_D >) _param_mpc_z_vel_d,(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,(ParamFloat< px4::params::MPC_SPOOLUP_TIME >) _param_mpc_spoolup_time,(ParamFloat< px4::params::MPC_TKO_RAMP_T >) _param_mpc_tko_ramp_t,(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,(ParamInt< px4::params::MPC_POS_MODE >) _param_mpc_pos_mode,(ParamInt< px4::params::MPC_AUTO_MODE >) _param_mpc_auto_mode,(ParamInt< px4::params::MPC_ALT_MODE >) _param_mpc_alt_mode,(ParamFloat< px4::params::MPC_TILTMAX_LND >) _param_mpc_tiltmax_lnd,(ParamFloat< px4::params::MPC_THR_MIN >) _param_mpc_thr_min,(ParamFloat< px4::params::MPC_THR_MAX >) _param_mpc_thr_max) | |
int | parameters_update (bool force) |
Update our local parameter cache. More... | |
void | poll_subscriptions () |
Check for changes in subscribed topics. More... | |
void | set_vehicle_states (const float &vel_sp_z) |
Check for validity of positon/velocity states. More... | |
void | limit_altitude (vehicle_local_position_setpoint_s &setpoint) |
Limit altitude based on land-detector. More... | |
void | warn_rate_limited (const char *str) |
Prints a warning message at a lowered rate. More... | |
void | publish_attitude () |
Publish attitude. More... | |
void | limit_thrust_during_landing (vehicle_attitude_setpoint_s &setpoint) |
Adjust the setpoint during landing. More... | |
void | start_flight_task () |
Start flightasks based on navigation state. More... | |
void | failsafe (vehicle_local_position_setpoint_s &setpoint, const PositionControlStates &states, const bool force, const bool warn) |
Failsafe. More... | |
void | reset_setpoint_to_nan (vehicle_local_position_setpoint_s &setpoint) |
Reset setpoints to NAN. More... | |
void | check_failure (bool task_failure, uint8_t nav_state) |
check if task should be switched because of failsafe More... | |
void | send_vehicle_cmd_do (uint8_t nav_state) |
send vehicle command to inform commander about failsafe More... | |
Private Attributes | |
Takeoff | _takeoff |
state machine and ramp to bring the vehicle off the ground without jumps More... | |
orb_id_t | _attitude_setpoint_id {nullptr} |
orb metadata to publish attitude setpoint dependent if VTOL or not More... | |
orb_advert_t | _vehicle_attitude_setpoint_pub {nullptr} |
attitude setpoint publication handle More... | |
uORB::PublicationQueued< vehicle_command_s > | _pub_vehicle_command {ORB_ID(vehicle_command)} |
vehicle command publication More... | |
orb_advert_t | _mavlink_log_pub {nullptr} |
uORB::Publication< landing_gear_s > | _landing_gear_pub {ORB_ID(landing_gear)} |
uORB::Publication< vehicle_local_position_setpoint_s > | _local_pos_sp_pub {ORB_ID(vehicle_local_position_setpoint)} |
vehicle local position setpoint publication More... | |
uORB::Publication< vehicle_local_position_setpoint_s > | _traj_sp_pub {ORB_ID(trajectory_setpoint)} |
trajectory setpoints publication More... | |
uORB::SubscriptionCallbackWorkItem | _local_pos_sub {this, ORB_ID(vehicle_local_position)} |
vehicle local position More... | |
uORB::Subscription | _vehicle_status_sub {ORB_ID(vehicle_status)} |
vehicle status subscription More... | |
uORB::Subscription | _vehicle_land_detected_sub {ORB_ID(vehicle_land_detected)} |
vehicle land detected subscription More... | |
uORB::Subscription | _control_mode_sub {ORB_ID(vehicle_control_mode)} |
vehicle control mode subscription More... | |
uORB::Subscription | _parameter_update_sub {ORB_ID(parameter_update)} |
notification of parameter updates More... | |
uORB::Subscription | _att_sub {ORB_ID(vehicle_attitude)} |
vehicle attitude More... | |
uORB::Subscription | _home_pos_sub {ORB_ID(home_position)} |
home position More... | |
hrt_abstime | _time_stamp_last_loop {0} |
time stamp of last loop iteration More... | |
int | _task_failure_count {0} |
counter for task failures More... | |
vehicle_status_s | _vehicle_status {} |
vehicle status More... | |
vehicle_land_detected_s | _vehicle_land_detected |
vehicle_control_mode_s | _control_mode {} |
vehicle control mode More... | |
vehicle_local_position_s | _local_pos {} |
vehicle local position More... | |
home_position_s | _home_pos {} |
home position More... | |
landing_gear_s | _landing_gear {} |
int8_t | _old_landing_gear_position {landing_gear_s::GEAR_KEEP} |
control::BlockDerivative | _vel_x_deriv |
velocity derivative in x More... | |
control::BlockDerivative | _vel_y_deriv |
velocity derivative in y More... | |
control::BlockDerivative | _vel_z_deriv |
velocity derivative in z More... | |
FlightTasks | _flight_tasks |
class generating position controller setpoints depending on vehicle task More... | |
PositionControl | _control |
class for core PID position control More... | |
PositionControlStates | _states {} |
structure containing vehicle state information for position control More... | |
hrt_abstime | _last_warn = 0 |
timer when the last warn message was sent out More... | |
bool | _in_failsafe = false |
true if failsafe was entered within current cycle More... | |
systemlib::Hysteresis | _failsafe_land_hysteresis {false} |
becomes true if task did not update correctly for LOITER_TIME_BEFORE_DESCEND More... | |
WeatherVane * | _wv_controller {nullptr} |
Vector3f | _wv_dcm_z_sp_prev {0, 0, 1} |
perf_counter_t | _cycle_perf |
Static Private Attributes | |
static constexpr uint64_t | TRAJECTORY_STREAM_TIMEOUT_US = 500_ms |
Timeout in us for trajectory data to get considered invalid. More... | |
static constexpr int | NUM_FAILURE_TRIES = 10 |
number of tries before switching to a failsafe flight task More... | |
static constexpr uint64_t | LOITER_TIME_BEFORE_DESCEND = 200_ms |
If Flighttask fails, keep 0.2 seconds the current setpoint before going into failsafe land. More... | |
static constexpr float | ALTITUDE_THRESHOLD = 0.3f |
During smooth-takeoff, below ALTITUDE_THRESHOLD the yaw-control is turned off ant tilt is limited. More... | |
Additional Inherited Members | |
Protected Member Functions inherited from control::SuperBlock | |
List< Block * > & | getChildren () |
void | updateChildParams () |
Protected Member Functions inherited from control::Block | |
virtual void | updateParamsSubclass () |
SuperBlock * | getParent () |
List< BlockParamBase * > & | getParams () |
Protected Attributes inherited from control::SuperBlock | |
List< Block * > | _children |
Protected Attributes inherited from control::Block | |
const char * | _name |
SuperBlock * | _parent |
float | _dt {0.0f} |
List< BlockParamBase * > | _params |
Protected Attributes inherited from ListNode< Block *> | |
Block * | _list_node_sibling |
Definition at line 82 of file mc_pos_control_main.cpp.
MulticopterPositionControl::MulticopterPositionControl | ( | ) |
Definition at line 283 of file mc_pos_control_main.cpp.
References _failsafe_land_hysteresis, LOITER_TIME_BEFORE_DESCEND, parameters_update(), and systemlib::Hysteresis::set_hysteresis_time_from().
Referenced by task_spawn().
|
override |
Definition at line 299 of file mc_pos_control_main.cpp.
References _cycle_perf, _wv_controller, and perf_free().
|
private |
check if task should be switched because of failsafe
Definition at line 1028 of file mc_pos_control_main.cpp.
References _task_failure_count, NUM_FAILURE_TRIES, and send_vehicle_cmd_do().
Referenced by start_flight_task().
|
static |
Definition at line 1103 of file mc_pos_control_main.cpp.
References print_usage().
|
private |
_param_mpc_spoolup_time | time to let motors spool up after arming |
_param_mpc_tko_ramp_t | time constant for smooth takeoff ramp |
_param_mpc_land_alt2 | downwards speed limited below this altitude |
_param_mpc_tiltmax_lnd | maximum tilt for landing and smooth takeoff |
|
private |
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.
Definition at line 969 of file mc_pos_control_main.cpp.
References _failsafe_land_hysteresis, _in_failsafe, _states, systemlib::Hysteresis::get_state(), hrt_absolute_time(), reset_setpoint_to_nan(), systemlib::Hysteresis::set_state_and_update(), vehicle_local_position_setpoint_s::thrust, PositionControlStates::velocity, vehicle_local_position_setpoint_s::vx, vehicle_local_position_setpoint_s::vy, and vehicle_local_position_setpoint_s::vz.
Referenced by Run().
bool MulticopterPositionControl::init | ( | ) |
Definition at line 307 of file mc_pos_control_main.cpp.
References _local_pos_sub, _time_stamp_last_loop, hrt_absolute_time(), uORB::SubscriptionCallback::registerCallback(), and uORB::SubscriptionInterval::set_interval_us().
Referenced by task_spawn().
|
private |
Limit altitude based on land-detector.
setpoint | needed to detect vehicle intention. |
Definition at line 429 of file mc_pos_control_main.cpp.
References _home_pos, _local_pos, _states, _vehicle_land_detected, vehicle_land_detected_s::alt_max, math::max(), PositionControlStates::position, vehicle_local_position_s::v_z_valid, home_position_s::valid_alt, vehicle_local_position_setpoint_s::vz, vehicle_local_position_setpoint_s::z, and home_position_s::z.
Referenced by Run().
|
private |
Adjust the setpoint during landing.
Thrust is adjusted to support the land-detector during detection.
setpoint | gets adjusted based on land-detector state |
Definition at line 953 of file mc_pos_control_main.cpp.
References _control, _states, _vehicle_land_detected, vehicle_land_detected_s::ground_contact, vehicle_land_detected_s::maybe_landed, vehicle_attitude_setpoint_s::q_d, PositionControl::resetIntegralXY(), PositionControl::resetIntegralZ(), vehicle_attitude_setpoint_s::thrust_body, PositionControlStates::yaw, and vehicle_attitude_setpoint_s::yaw_sp_move_rate.
Referenced by Run().
|
private |
Update our local parameter cache.
Parameter update can be forced when argument is true.
force | forces parameter update. |
Definition at line 333 of file mc_pos_control_main.cpp.
References _control, _flight_tasks, _mavlink_log_pub, _parameter_update_sub, _takeoff, _wv_controller, math::constrain(), uORB::Subscription::copy(), Takeoff::generateInitialRampValue(), FlightTasks::handleParameterUpdate(), mavlink_log_critical, math::min(), OK, PositionControl::setHoverThrust(), PositionControl::setPositionGains(), Takeoff::setSpoolupTime(), Takeoff::setTakeoffRampTime(), PositionControl::setThrustLimits(), PositionControl::setTiltLimit(), PositionControl::setVelocityGains(), PositionControl::setVelocityLimits(), WeatherVane::update_parameters(), and uORB::Subscription::updated().
Referenced by MulticopterPositionControl(), and Run().
|
private |
Check for changes in subscribed topics.
Definition at line 395 of file mc_pos_control_main.cpp.
References _att_sub, _attitude_setpoint_id, _control_mode, _control_mode_sub, _home_pos, _home_pos_sub, _states, _vehicle_land_detected, _vehicle_land_detected_sub, _vehicle_status, _vehicle_status_sub, _wv_controller, uORB::Subscription::copy(), vehicle_status_s::is_vtol, ORB_ID, vehicle_attitude_s::q, uORB::Subscription::update(), uORB::Subscription::updated(), and PositionControlStates::yaw.
Referenced by Run().
|
override |
Definition at line 511 of file mc_pos_control_main.cpp.
References _cycle_perf, _flight_tasks, FlightTasks::getActiveTask(), FlightTasks::isAnyTaskActive(), and perf_print_counter().
|
static |
Definition at line 1108 of file mc_pos_control_main.cpp.
Referenced by custom_command().
|
private |
Publish attitude.
|
private |
Reset setpoints to NAN.
Definition at line 1019 of file mc_pos_control_main.cpp.
References vehicle_local_position_setpoint_s::acceleration, vehicle_local_position_setpoint_s::thrust, vehicle_local_position_setpoint_s::vx, vehicle_local_position_setpoint_s::vy, vehicle_local_position_setpoint_s::vz, vehicle_local_position_setpoint_s::x, vehicle_local_position_setpoint_s::y, vehicle_local_position_setpoint_s::yaw, vehicle_local_position_setpoint_s::yawspeed, and vehicle_local_position_setpoint_s::z.
Referenced by failsafe(), and Run().
|
override |
Definition at line 526 of file mc_pos_control_main.cpp.
References _attitude_setpoint_id, _control, _control_mode, _cycle_perf, control::Block::_dt, _failsafe_land_hysteresis, _flight_tasks, _in_failsafe, _landing_gear, _landing_gear_pub, _local_pos, _local_pos_sp_pub, _local_pos_sub, _old_landing_gear_position, _states, _takeoff, _time_stamp_last_loop, _traj_sp_pub, _vehicle_attitude_setpoint_pub, _vehicle_land_detected, _vel_x_deriv, _vel_y_deriv, _vel_z_deriv, _wv_controller, _wv_dcm_z_sp_prev, WeatherVane::activate(), WeatherVane::deactivate(), FlightTask::empty_constraints, FlightTask::empty_setpoint, failsafe(), vehicle_control_mode_s::flag_armed, vehicle_control_mode_s::flag_control_climb_rate_enabled, vehicle_control_mode_s::flag_control_manual_enabled, vehicle_control_mode_s::flag_control_position_enabled, flight, PositionControl::generateThrustYawSetpoint(), PositionControl::getAttitudeSetpoint(), FlightTasks::getConstraints(), FlightTasks::getGear(), PositionControl::getLocalPositionSetpoint(), FlightTasks::getPositionSetpoint(), Takeoff::getTakeoffState(), PositionControl::getVelSp(), hrt_absolute_time(), hrt_abstime, FlightTasks::isAnyTaskActive(), vehicle_land_detected_s::landed, landing_gear_s::landing_gear, limit_altitude(), limit_thrust_during_landing(), ORB_PRIO_DEFAULT, orb_publish_auto(), parameters_update(), perf_begin(), perf_end(), poll_subscriptions(), PositionControlStates::position, uORB::Publication< T >::publish(), math::radians(), rampup, FlightTasks::reActivate(), control::BlockDerivative::reset(), reset_setpoint_to_nan(), PositionControl::resetIntegralXY(), PositionControl::resetIntegralZ(), systemlib::Hysteresis::set_state_and_update(), set_vehicle_states(), control::SuperBlock::setDt(), FlightTasks::setYawHandler(), vehicle_constraints_s::speed_up, start_flight_task(), vehicle_local_position_setpoint_s::thrust, vehicle_constraints_s::tilt, vehicle_local_position_setpoint_s::timestamp, vehicle_attitude_setpoint_s::timestamp, landing_gear_s::timestamp, uORB::SubscriptionCallback::unregisterCallback(), WeatherVane::update(), FlightTasks::update(), uORB::SubscriptionInterval::update(), PositionControl::updateConstraints(), Takeoff::updateRamp(), PositionControl::updateSetpoint(), PositionControl::updateState(), Takeoff::updateTakeoffState(), FlightTasks::updateVelocityControllerIO(), vehicle_local_position_setpoint_s::vx, vehicle_local_position_setpoint_s::vy, vehicle_local_position_setpoint_s::vz, vehicle_constraints_s::want_takeoff, warn_rate_limited(), WeatherVane::weathervane_enabled(), vehicle_local_position_setpoint_s::x, vehicle_local_position_setpoint_s::y, PositionControlStates::yaw, vehicle_local_position_setpoint_s::yaw, vehicle_local_position_setpoint_s::yawspeed, and vehicle_local_position_setpoint_s::z.
|
private |
send vehicle command to inform commander about failsafe
Definition at line 1042 of file mc_pos_control_main.cpp.
References _pub_vehicle_command, command, hrt_absolute_time(), uORB::PublicationQueued< T >::publish(), PX4_CUSTOM_MAIN_MODE_ALTCTL, PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_MAIN_MODE_POSCTL, PX4_CUSTOM_MAIN_MODE_STABILIZED, and PX4_CUSTOM_SUB_MODE_AUTO_LOITER.
Referenced by check_failure().
|
private |
Check for validity of positon/velocity states.
vel_sp_z | velocity setpoint in z-direction |
Definition at line 447 of file mc_pos_control_main.cpp.
References _local_pos, _states, _vel_x_deriv, _vel_y_deriv, _vel_z_deriv, PositionControlStates::acceleration, vehicle_local_position_s::dist_bottom_rate, vehicle_local_position_s::dist_bottom_valid, f(), FLT_EPSILON, PositionControlStates::position, vehicle_local_position_s::timestamp, control::BlockDerivative::update(), vehicle_local_position_s::v_xy_valid, PositionControlStates::velocity, vehicle_local_position_s::vx, vehicle_local_position_s::vy, vehicle_local_position_s::vz, vehicle_local_position_s::x, vehicle_local_position_s::xy_valid, vehicle_local_position_s::y, vehicle_local_position_s::z, vehicle_local_position_s::z_deriv, and vehicle_local_position_s::z_valid.
Referenced by Run().
|
private |
Start flightasks based on navigation state.
This methods activates a task based on the navigation state.
Definition at line 735 of file mc_pos_control_main.cpp.
References _control_mode, _flight_tasks, _task_failure_count, _vehicle_status, check_failure(), FlightTasks::errorToString(), vehicle_control_mode_s::flag_control_acceleration_enabled, vehicle_control_mode_s::flag_control_altitude_enabled, vehicle_control_mode_s::flag_control_auto_enabled, vehicle_control_mode_s::flag_control_climb_rate_enabled, vehicle_control_mode_s::flag_control_position_enabled, vehicle_control_mode_s::flag_control_velocity_enabled, vehicle_status_s::in_transition_mode, vehicle_status_s::nav_state, NoError, FlightTasks::switchTask(), vehicle_status_s::vehicle_type, and VEHICLE_TYPE_FIXED_WING.
Referenced by Run().
|
static |
Definition at line 1080 of file mc_pos_control_main.cpp.
References init(), ll40ls::instance, and MulticopterPositionControl().
|
private |
Prints a warning message at a lowered rate.
str | the message that has to be printed. |
Definition at line 322 of file mc_pos_control_main.cpp.
References _last_warn, hrt_absolute_time(), and hrt_abstime.
Referenced by Run().
|
private |
vehicle attitude
Definition at line 124 of file mc_pos_control_main.cpp.
Referenced by poll_subscriptions().
|
private |
orb metadata to publish attitude setpoint dependent if VTOL or not
Definition at line 109 of file mc_pos_control_main.cpp.
Referenced by poll_subscriptions(), and Run().
|
private |
class for core PID position control
Definition at line 186 of file mc_pos_control_main.cpp.
Referenced by limit_thrust_during_landing(), parameters_update(), and Run().
|
private |
vehicle control mode
Definition at line 142 of file mc_pos_control_main.cpp.
Referenced by poll_subscriptions(), Run(), and start_flight_task().
|
private |
vehicle control mode subscription
Definition at line 122 of file mc_pos_control_main.cpp.
Referenced by poll_subscriptions().
|
private |
Definition at line 207 of file mc_pos_control_main.cpp.
Referenced by print_status(), Run(), and ~MulticopterPositionControl().
|
private |
becomes true if task did not update correctly for LOITER_TIME_BEFORE_DESCEND
Definition at line 202 of file mc_pos_control_main.cpp.
Referenced by failsafe(), MulticopterPositionControl(), and Run().
|
private |
class generating position controller setpoints depending on vehicle task
Definition at line 185 of file mc_pos_control_main.cpp.
Referenced by parameters_update(), print_status(), Run(), and start_flight_task().
|
private |
home position
Definition at line 144 of file mc_pos_control_main.cpp.
Referenced by limit_altitude(), and poll_subscriptions().
|
private |
home position
Definition at line 125 of file mc_pos_control_main.cpp.
Referenced by poll_subscriptions().
|
private |
true if failsafe was entered within current cycle
Definition at line 191 of file mc_pos_control_main.cpp.
Referenced by failsafe(), and Run().
|
private |
Definition at line 145 of file mc_pos_control_main.cpp.
Referenced by Run().
|
private |
Definition at line 114 of file mc_pos_control_main.cpp.
Referenced by Run().
|
private |
timer when the last warn message was sent out
Definition at line 189 of file mc_pos_control_main.cpp.
Referenced by warn_rate_limited().
|
private |
vehicle local position
Definition at line 143 of file mc_pos_control_main.cpp.
Referenced by limit_altitude(), Run(), and set_vehicle_states().
|
private |
vehicle local position setpoint publication
Definition at line 115 of file mc_pos_control_main.cpp.
Referenced by Run().
|
private |
vehicle local position
Definition at line 118 of file mc_pos_control_main.cpp.
|
private |
Definition at line 112 of file mc_pos_control_main.cpp.
Referenced by parameters_update().
|
private |
Definition at line 146 of file mc_pos_control_main.cpp.
Referenced by Run().
|
private |
notification of parameter updates
Definition at line 123 of file mc_pos_control_main.cpp.
Referenced by parameters_update().
|
private |
vehicle command publication
Definition at line 111 of file mc_pos_control_main.cpp.
Referenced by send_vehicle_cmd_do().
|
private |
structure containing vehicle state information for position control
Definition at line 187 of file mc_pos_control_main.cpp.
Referenced by failsafe(), limit_altitude(), limit_thrust_during_landing(), poll_subscriptions(), Run(), and set_vehicle_states().
|
private |
state machine and ramp to bring the vehicle off the ground without jumps
Definition at line 107 of file mc_pos_control_main.cpp.
Referenced by parameters_update(), and Run().
|
private |
counter for task failures
Definition at line 129 of file mc_pos_control_main.cpp.
Referenced by check_failure(), and start_flight_task().
|
private |
time stamp of last loop iteration
Definition at line 127 of file mc_pos_control_main.cpp.
|
private |
trajectory setpoints publication
Definition at line 116 of file mc_pos_control_main.cpp.
Referenced by Run().
|
private |
attitude setpoint publication handle
Definition at line 110 of file mc_pos_control_main.cpp.
Referenced by Run().
|
private |
Definition at line 133 of file mc_pos_control_main.cpp.
Referenced by limit_altitude(), limit_thrust_during_landing(), poll_subscriptions(), and Run().
|
private |
vehicle land detected subscription
Definition at line 121 of file mc_pos_control_main.cpp.
Referenced by poll_subscriptions().
|
private |
vehicle status
vehicle-land-detection: initialze to landed
Definition at line 131 of file mc_pos_control_main.cpp.
Referenced by poll_subscriptions(), and start_flight_task().
|
private |
vehicle status subscription
Definition at line 120 of file mc_pos_control_main.cpp.
Referenced by poll_subscriptions().
|
private |
velocity derivative in x
Definition at line 181 of file mc_pos_control_main.cpp.
Referenced by Run(), and set_vehicle_states().
|
private |
velocity derivative in y
Definition at line 182 of file mc_pos_control_main.cpp.
Referenced by Run(), and set_vehicle_states().
|
private |
velocity derivative in z
Definition at line 183 of file mc_pos_control_main.cpp.
Referenced by Run(), and set_vehicle_states().
|
private |
Definition at line 204 of file mc_pos_control_main.cpp.
Referenced by parameters_update(), poll_subscriptions(), Run(), and ~MulticopterPositionControl().
|
private |
Definition at line 205 of file mc_pos_control_main.cpp.
Referenced by Run().
|
staticprivate |
During smooth-takeoff, below ALTITUDE_THRESHOLD the yaw-control is turned off ant tilt is limited.
Definition at line 200 of file mc_pos_control_main.cpp.
|
staticprivate |
If Flighttask fails, keep 0.2 seconds the current setpoint before going into failsafe land.
Definition at line 198 of file mc_pos_control_main.cpp.
Referenced by MulticopterPositionControl().
|
staticprivate |
number of tries before switching to a failsafe flight task
Definition at line 196 of file mc_pos_control_main.cpp.
Referenced by check_failure().
|
staticprivate |
Timeout in us for trajectory data to get considered invalid.
Definition at line 194 of file mc_pos_control_main.cpp.