44 #include <px4_platform_common/defines.h> 45 #include <px4_platform_common/module_params.h> 63 { {0, {NAN, NAN, NAN}, {NAN, NAN, NAN}, {NAN, NAN, NAN}, NAN, NAN,
false, UINT8_MAX, {0, 0}},
64 {0, {NAN, NAN, NAN}, {NAN, NAN, NAN}, {NAN, NAN, NAN}, NAN, NAN,
false, UINT8_MAX, {0, 0}},
65 {0, {NAN, NAN, NAN}, {NAN, NAN, NAN}, {NAN, NAN, NAN}, NAN, NAN,
false, UINT8_MAX, {0, 0}},
66 {0, {NAN, NAN, NAN}, {NAN, NAN, NAN}, {NAN, NAN, NAN}, NAN, NAN,
false, UINT8_MAX, {0, 0}},
67 {0, {NAN, NAN, NAN}, {NAN, NAN, NAN}, {NAN, NAN, NAN}, NAN, NAN,
false, UINT8_MAX, {0, 0}}
97 const matrix::Vector3f &next_wp,
const float next_yaw,
const float next_yawspeed,
const bool ext_yaw_active,
145 (ParamFloat<px4::params::NAV_MC_ALT_RAD>) _param_nav_mc_alt_rad
void updateAvoidanceDesiredSetpoints(const matrix::Vector3f &pos_sp, const matrix::Vector3f &vel_sp, const int type)
Updates the desired setpoints to send to the obstacle avoidance system.
void checkAvoidanceProgress(const matrix::Vector3f &pos, const matrix::Vector3f &prev_wp, float target_acceptance_radius, const matrix::Vector2f &closest_pt)
Checks the vehicle progress between previous and current position waypoint of the triplet...
systemlib::Hysteresis _no_progress_z_hysteresis
becomes true if the vehicle is not making progress towards the z component of the goal ...
ObstacleAvoidance(ModuleParams *parent)
vehicle_trajectory_waypoint_s _desired_waypoint
desired vehicle trajectory waypoint to be sent to OA
void injectAvoidanceSetpoints(matrix::Vector3f &pos_sp, matrix::Vector3f &vel_sp, float &yaw_sp, float &yaw_speed_sp)
Inject setpoints from obstacle avoidance system into FlightTasks.
matrix::Vector3f _failsafe_position
vehicle position when entered in failsafe
High-resolution timer with callouts and timekeeping.
float _prev_pos_to_target_z
z distance to the goal
matrix::Vector3f _curr_wp
current position triplet
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
systemlib::Hysteresis _avoidance_point_not_valid_hysteresis
becomes true if the companion doesn't start sending valid setpoints
const vehicle_trajectory_waypoint_s empty_trajectory_waypoint
uORB::SubscriptionData< vehicle_status_s > _sub_vehicle_status
vehicle status subscription
~ObstacleAvoidance()=default
Hysteresis of a boolean value.
void updateAvoidanceDesiredWaypoints(const matrix::Vector3f &curr_wp, const float curr_yaw, const float curr_yawspeed, const matrix::Vector3f &next_wp, const float next_yaw, const float next_yawspeed, const bool ext_yaw_active, const int wp_type)
Updates the desired waypoints to send to the obstacle avoidance system.
uORB::SubscriptionData< vehicle_trajectory_waypoint_s > _sub_vehicle_trajectory_waypoint
vehicle trajectory waypoint subscription
matrix::Vector3f _position
current vehicle position
uORB::Publication< vehicle_trajectory_waypoint_s > _pub_traj_wp_avoidance_desired
trajectory waypoint desired publication
uORB::Publication< position_controller_status_s > _pub_pos_control_status
position controller status publication
uORB::PublicationQueued< vehicle_command_s > _pub_vehicle_command
vehicle command do publication
DEFINE_PARAMETERS((ParamFloat< px4::params::NAV_MC_ALT_RAD >) _param_nav_mc_alt_rad)
void _publishVehicleCmdDoLoiter()
Publishes vehicle command.
bool _ext_yaw_active
true, if external yaw handling is active