Firmware
ObstacleAvoidance.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2019 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
42 #pragma once
43 
44 #include <px4_defines.h>
45 #include <px4_module_params.h>
47 #include <drivers/drv_hrt.h>
48 
49 #include <uORB/topics/position_controller_status.h>
50 #include <uORB/topics/vehicle_command.h>
51 #include <uORB/topics/vehicle_status.h>
52 #include <uORB/topics/vehicle_trajectory_waypoint.h>
53 
54 #include <matrix/matrix/math.hpp>
55 
56 #include <SubscriptionArray.hpp>
57 
59 {
60 public:
63 
64  bool initializeSubscriptions(SubscriptionArray &subscription_array);
65 
73  void injectAvoidanceSetpoints(matrix::Vector3f &pos_sp, matrix::Vector3f &vel_sp, float &yaw_sp, float &yaw_speed_sp);
74 
84  void updateAvoidanceDesiredWaypoints(const matrix::Vector3f &curr_wp, const float curr_yaw, const float curr_yawspeed,
85  const matrix::Vector3f &next_wp, const float next_yaw, const float next_yawspeed);
91  void updateAvoidanceDesiredSetpoints(const matrix::Vector3f &pos_sp, const matrix::Vector3f &vel_sp);
92 
100  void checkAvoidanceProgress(const matrix::Vector3f &pos, const matrix::Vector3f &prev_wp,
101  float target_acceptance_radius, const matrix::Vector2f &closest_pt);
102 
103 private:
104 
105  uORB::Subscription<vehicle_trajectory_waypoint_s> *_sub_vehicle_trajectory_waypoint{nullptr};
106  uORB::Subscription<vehicle_status_s> *_sub_vehicle_status{nullptr};
108  DEFINE_PARAMETERS(
109  (ParamInt<px4::params::COM_OBS_AVOID>) COM_OBS_AVOID,
111  );
112 
113  vehicle_trajectory_waypoint_s _desired_waypoint = {};
114  orb_advert_t _pub_traj_wp_avoidance_desired{nullptr};
115  orb_advert_t _pub_pos_control_status{nullptr};
116  orb_advert_t _pub_vehicle_command{nullptr};
118  matrix::Vector3f _curr_wp = {};
119  matrix::Vector3f _position = {};
120  matrix::Vector3f _failsafe_position = {};
125  void _publishAvoidanceDesiredWaypoint();
126 
130  void _publishVehicleCmdDoLoiter();
131 
132 };
Definition: px4_param.h:313
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)
Updates the desired waypoints to send to the obstacle avoidance system.
Definition: ObstacleAvoidance.cpp:128
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
High-resolution timer with callouts and timekeeping.
Generally used magic defines.
Simple array that contains a dynamic amount of Subscription<T> instances.
Definition: px4_param.h:318
C++ base class for modules/classes using configuration parameters.
Definition: px4_module_params.h:46
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.
Definition: ObstacleAvoidance.cpp:88
void updateAvoidanceDesiredSetpoints(const matrix::Vector3f &pos_sp, const matrix::Vector3f &vel_sp)
Updates the desired setpoints to send to the obstacle avoidance system.
Definition: ObstacleAvoidance.cpp:153
PX4 custom flight modes.
Definition: ObstacleAvoidance.hpp:58
Definition: SubscriptionArray.hpp:46
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...
Definition: ObstacleAvoidance.cpp:164