19class SetpointBase :
public std::enable_shared_from_this<SetpointBase> {
21 using ShouldActivateCB = std::function<void()>;
24 void fillControlMode(px4_msgs::msg::VehicleControlMode& control_mode)
26 control_mode.flag_control_rates_enabled = rates_enabled;
27 control_mode.flag_control_attitude_enabled = attitude_enabled;
28 control_mode.flag_control_acceleration_enabled = acceleration_enabled;
29 control_mode.flag_control_velocity_enabled = velocity_enabled;
30 control_mode.flag_control_position_enabled = position_enabled;
31 control_mode.flag_control_altitude_enabled = altitude_enabled;
32 control_mode.flag_control_allocation_enabled = control_allocation_enabled;
33 control_mode.flag_control_climb_rate_enabled = climb_rate_enabled;
36 bool control_allocation_enabled{
true};
37 bool rates_enabled{
true};
38 bool attitude_enabled{
true};
39 bool altitude_enabled{
true};
40 bool acceleration_enabled{
true};
41 bool velocity_enabled{
true};
42 bool position_enabled{
true};
43 bool local_position_is_optional{
false};
44 bool climb_rate_enabled{
false};
51 std::shared_ptr<SetpointBase> getSharedPtr()
54 return shared_from_this();
55 }
catch (
const std::bad_weak_ptr& exception) {
56 throw Exception(
"Setpoint must be instantiated with std::make_shared<>");
61 virtual Configuration getConfiguration() = 0;
63 virtual float desiredUpdateRateHz() {
return 50.f; }
65 void setShouldActivateCallback(
const ShouldActivateCB& should_activate_cb)
67 _should_activate_cb = should_activate_cb;
69 void setActive(
bool active) { _active = active; }
74 if (!_active && _should_activate_cb) {
75 _should_activate_cb();
80 ShouldActivateCB _should_activate_cb;
Definition context.hpp:18