forked from Archive/PX4-Autopilot
Alphabetize flight_mode_manager CMakeLists.txt list, and group/format types in FlightTask.cpp/hpp.
This commit is contained in:
parent
759a60ac82
commit
4eb758edf0
|
@ -52,16 +52,16 @@ endif()
|
||||||
|
|
||||||
# add core flight tasks to list
|
# add core flight tasks to list
|
||||||
list(APPEND flight_tasks_all
|
list(APPEND flight_tasks_all
|
||||||
|
AutoFollowMe
|
||||||
|
AutoLineSmoothVel
|
||||||
|
Descend
|
||||||
|
Failsafe
|
||||||
|
ManualAcceleration
|
||||||
ManualAltitude
|
ManualAltitude
|
||||||
ManualAltitudeSmoothVel
|
ManualAltitudeSmoothVel
|
||||||
ManualPosition
|
ManualPosition
|
||||||
ManualPositionSmoothVel
|
ManualPositionSmoothVel
|
||||||
AutoLineSmoothVel
|
|
||||||
AutoFollowMe
|
|
||||||
Failsafe
|
|
||||||
Descend
|
|
||||||
Transition
|
Transition
|
||||||
ManualAcceleration
|
|
||||||
${flight_tasks_to_add}
|
${flight_tasks_to_add}
|
||||||
)
|
)
|
||||||
|
|
||||||
|
|
|
@ -87,11 +87,12 @@ const vehicle_local_position_setpoint_s FlightTask::getPositionSetpoint()
|
||||||
vehicle_local_position_setpoint.vy = _velocity_setpoint(1);
|
vehicle_local_position_setpoint.vy = _velocity_setpoint(1);
|
||||||
vehicle_local_position_setpoint.vz = _velocity_setpoint(2);
|
vehicle_local_position_setpoint.vz = _velocity_setpoint(2);
|
||||||
|
|
||||||
_acceleration_setpoint.copyTo(vehicle_local_position_setpoint.acceleration);
|
|
||||||
_jerk_setpoint.copyTo(vehicle_local_position_setpoint.jerk);
|
|
||||||
vehicle_local_position_setpoint.yaw = _yaw_setpoint;
|
vehicle_local_position_setpoint.yaw = _yaw_setpoint;
|
||||||
vehicle_local_position_setpoint.yawspeed = _yawspeed_setpoint;
|
vehicle_local_position_setpoint.yawspeed = _yawspeed_setpoint;
|
||||||
|
|
||||||
|
_acceleration_setpoint.copyTo(vehicle_local_position_setpoint.acceleration);
|
||||||
|
_jerk_setpoint.copyTo(vehicle_local_position_setpoint.jerk);
|
||||||
|
|
||||||
// deprecated, only kept for output logging
|
// deprecated, only kept for output logging
|
||||||
matrix::Vector3f(NAN, NAN, NAN).copyTo(vehicle_local_position_setpoint.thrust);
|
matrix::Vector3f(NAN, NAN, NAN).copyTo(vehicle_local_position_setpoint.thrust);
|
||||||
|
|
||||||
|
@ -104,7 +105,8 @@ void FlightTask::_resetSetpoints()
|
||||||
_velocity_setpoint.setNaN();
|
_velocity_setpoint.setNaN();
|
||||||
_acceleration_setpoint.setNaN();
|
_acceleration_setpoint.setNaN();
|
||||||
_jerk_setpoint.setNaN();
|
_jerk_setpoint.setNaN();
|
||||||
_yaw_setpoint = _yawspeed_setpoint = NAN;
|
_yaw_setpoint = NAN;
|
||||||
|
_yawspeed_setpoint = NAN;
|
||||||
}
|
}
|
||||||
|
|
||||||
void FlightTask::_evaluateVehicleLocalPosition()
|
void FlightTask::_evaluateVehicleLocalPosition()
|
||||||
|
|
|
@ -244,15 +244,14 @@ protected:
|
||||||
*/
|
*/
|
||||||
matrix::Vector3f _position_setpoint;
|
matrix::Vector3f _position_setpoint;
|
||||||
matrix::Vector3f _velocity_setpoint;
|
matrix::Vector3f _velocity_setpoint;
|
||||||
|
matrix::Vector3f _velocity_setpoint_feedback;
|
||||||
matrix::Vector3f _acceleration_setpoint;
|
matrix::Vector3f _acceleration_setpoint;
|
||||||
|
matrix::Vector3f _acceleration_setpoint_feedback;
|
||||||
matrix::Vector3f _jerk_setpoint;
|
matrix::Vector3f _jerk_setpoint;
|
||||||
|
|
||||||
float _yaw_setpoint{};
|
float _yaw_setpoint{};
|
||||||
float _yawspeed_setpoint{};
|
float _yawspeed_setpoint{};
|
||||||
|
|
||||||
matrix::Vector3f _velocity_setpoint_feedback;
|
|
||||||
matrix::Vector3f _acceleration_setpoint_feedback;
|
|
||||||
|
|
||||||
ekf_reset_counters_s _reset_counters{}; ///< Counters for estimator local position resets
|
ekf_reset_counters_s _reset_counters{}; ///< Counters for estimator local position resets
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
Loading…
Reference in New Issue