9 #include <px4_msgs/msg/vehicle_command.hpp>
10 #include <px4_msgs/msg/vehicle_local_position.hpp>
11 #include <px4_msgs/msg/vtol_vehicle_status.hpp>
12 #include <px4_ros2/common/context.hpp>
13 #include <px4_ros2/components/shared_subscription.hpp>
21 float deceleration_integrator_limit{0.3f};
29 VTOLConfig& withDecelerationIntegratorLimit(
const float deceleration_integrator_limit)
31 this->deceleration_integrator_limit = deceleration_integrator_limit;
35 VTOLConfig& withBackTransitionDecelerationIGain(
38 this->back_transition_deceleration_setpoint_to_pitch_i =
57 TransitionToFixedWing = 1,
58 TransitionToMulticopter = 2,
70 Eigen::Vector3f computeAccelerationSetpointDuringTransition(
71 std::optional<float> back_transition_deceleration_m_s2 = std::nullopt);
73 State getCurrentState()
const {
return _current_state; }
77 rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr _vehicle_command_pub;
78 rclcpp::Subscription<px4_msgs::msg::VtolVehicleStatus>::SharedPtr _vtol_vehicle_status_sub;
79 SharedSubscriptionCallbackInstance _vehicle_local_position_cb;
80 rclcpp::Time _last_command_sent;
81 rclcpp::Time _last_vtol_vehicle_status_received;
82 rclcpp::Time _last_pitch_integrator_update{0, 0, _node.get_clock()->get_clock_type()};
84 float _vehicle_heading{NAN};
85 float _decel_error_bt_int{0.f};
87 Eigen::Vector2f _vehicle_acceleration_xy{NAN, NAN};
89 State _current_state{State::Undefined};
91 float computePitchSetpointDuringBacktransition(
92 std::optional<float> back_transition_deceleration_m_s2 = std::nullopt);
Definition: context.hpp:18
Provides VTOL transition command.
Definition: vtol.hpp:51
float back_transition_deceleration
Definition: vtol.hpp:17
float back_transition_deceleration_setpoint_to_pitch_i
Definition: vtol.hpp:19