8 #include <px4_msgs/msg/vehicle_command.hpp>
9 #include <px4_msgs/msg/vtol_vehicle_status.hpp>
10 #include <px4_msgs/msg/vehicle_local_position.hpp>
11 #include <px4_ros2/components/shared_subscription.hpp>
14 #include <px4_ros2/common/context.hpp>
22 float deceleration_integrator_limit{0.3f};
24 VTOLConfig & withBackTransitionDeceleration(
31 VTOLConfig & withDecelerationIntegratorLimit(
32 const float deceleration_integrator_limit)
34 this->deceleration_integrator_limit = deceleration_integrator_limit;
38 VTOLConfig & withBackTransitionDecelerationIGain(
41 this->back_transition_deceleration_setpoint_to_pitch_i =
64 TransitionToFixedWing = 1,
65 TransitionToMulticopter = 2,
77 Eigen::Vector3f computeAccelerationSetpointDuringTransition(
78 std::optional<float> back_transition_deceleration_m_s2 = std::nullopt);
80 State getCurrentState()
const {
return _current_state;}
84 rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr _vehicle_command_pub;
85 rclcpp::Subscription<px4_msgs::msg::VtolVehicleStatus>::SharedPtr _vtol_vehicle_status_sub;
86 SharedSubscriptionCallbackInstance _vehicle_local_position_cb;
87 rclcpp::Time _last_command_sent;
88 rclcpp::Time _last_vtol_vehicle_status_received;
89 rclcpp::Time _last_pitch_integrator_update{0, 0, _node.get_clock()->get_clock_type()};
91 float _vehicle_heading{NAN};
92 float _decel_error_bt_int{0.f};
94 Eigen::Vector2f _vehicle_acceleration_xy{NAN, NAN};
96 State _current_state{State::Undefined};
98 float computePitchSetpointDuringBacktransition(
99 std::optional<float> back_transition_deceleration_m_s2 = std::nullopt);
Definition: context.hpp:20
Provides VTOL transition command.
Definition: vtol.hpp:57
float back_transition_deceleration
Definition: vtol.hpp:20
float back_transition_deceleration_setpoint_to_pitch_i
Definition: vtol.hpp:21