46 #include <matrix/matrix/math.hpp> 47 #include <uORB/topics/obstacle_distance.h> 48 #include <uORB/topics/collision_constraints.h> 51 #include <uORB/topics/mavlink_log.h> 69 bool is_active() {
return _param_mpc_col_prev_d.get() > 0; }
71 void modifySetpoint(matrix::Vector2f &original_setpoint,
const float max_speed);
75 bool _interfering =
false;
82 static constexpr uint64_t RANGE_STREAM_TIMEOUT_US = 500000;
83 static constexpr uint64_t MESSAGE_THROTTLE_US = 5000000;
87 matrix::Vector2f _move_constraints_x_normalized;
88 matrix::Vector2f _move_constraints_y_normalized;
89 matrix::Vector2f _move_constraints_x;
90 matrix::Vector2f _move_constraints_y;
98 void update_range_constraints();
100 void reset_constraints();
102 void publish_constraints(
const matrix::Vector2f &original_setpoint,
const matrix::Vector2f &adapted_setpoint);
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
High-resolution timer with callouts and timekeeping.
Simple array that contains a dynamic amount of Subscription<T> instances.
Definition: CollisionPrevention.hpp:56
API for the uORB lightweight object broker.
Definition: px4_param.h:318
C++ base class for modules/classes using configuration parameters.
Definition: px4_module_params.h:46
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
bool initializeSubscriptions(SubscriptionArray &subscription_array)
Initialize the uORB subscriptions using an array.
Definition: CollisionPrevention.cpp:63
Common header for mathlib exports.
Definition: SubscriptionArray.hpp:46