PX4 Firmware
PX4 Autopilot Software http://px4.io
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 
34 /**
35  * @file ObstacleAvoidance.hpp
36  * This class is used to inject the setpoints of an obstacle avoidance system
37  * into the FlightTasks
38  *
39  * @author Martina Rivizzigno
40  */
41 
42 #pragma once
43 
44 #include <px4_platform_common/defines.h>
45 #include <px4_platform_common/module_params.h>
47 #include <drivers/drv_hrt.h>
48 
49 #include <uORB/Publication.hpp>
51 #include <uORB/Subscription.hpp>
57 
59 
60 #include <matrix/matrix/math.hpp>
61 
62 const vehicle_trajectory_waypoint_s empty_trajectory_waypoint = {0, 0, {0, 0, 0, 0, 0, 0, 0},
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}}
68  }
69 };
70 
71 class ObstacleAvoidance : public ModuleParams
72 {
73 public:
74  ObstacleAvoidance(ModuleParams *parent);
75  ~ObstacleAvoidance() = default;
76 
77  /**
78  * Inject setpoints from obstacle avoidance system into FlightTasks.
79  * @param pos_sp, position setpoint
80  * @param vel_sp, velocity setpoint
81  * @param yaw_sp, yaw setpoint
82  * @param yaw_speed_sp, yaw speed setpoint
83  */
84  void injectAvoidanceSetpoints(matrix::Vector3f &pos_sp, matrix::Vector3f &vel_sp, float &yaw_sp, float &yaw_speed_sp);
85 
86  /**
87  * Updates the desired waypoints to send to the obstacle avoidance system. These messages don't have any direct impact on the flight.
88  * @param curr_wp, current position triplet
89  * @param curr_yaw, current yaw triplet
90  * @param curr_yawspeed, current yaw speed triplet
91  * @param next_wp, next position triplet
92  * @param next_yaw, next yaw triplet
93  * @param next_yawspeed, next yaw speed triplet
94  * @param wp_type, current triplet type
95  */
96  void updateAvoidanceDesiredWaypoints(const matrix::Vector3f &curr_wp, const float curr_yaw, const float curr_yawspeed,
97  const matrix::Vector3f &next_wp, const float next_yaw, const float next_yawspeed, const bool ext_yaw_active,
98  const int wp_type);
99  /**
100  * Updates the desired setpoints to send to the obstacle avoidance system.
101  * @param pos_sp, desired position setpoint computed by the active FlightTask
102  * @param vel_sp, desired velocity setpoint computed by the active FlightTask
103  * @param type, current triplet type
104  */
105  void updateAvoidanceDesiredSetpoints(const matrix::Vector3f &pos_sp, const matrix::Vector3f &vel_sp, const int type);
106 
107  /**
108  * Checks the vehicle progress between previous and current position waypoint of the triplet.
109  * @param pos, vehicle position
110  * @param prev_wp, previous position triplet
111  * @param target_acceptance_radius, current position triplet xy acceptance radius
112  * @param closest_pt, closest point to the vehicle on the line previous-current position triplet
113  */
114  void checkAvoidanceProgress(const matrix::Vector3f &pos, const matrix::Vector3f &prev_wp,
115  float target_acceptance_radius, const matrix::Vector2f &closest_pt);
116 
117 protected:
118 
119  uORB::SubscriptionData<vehicle_trajectory_waypoint_s> _sub_vehicle_trajectory_waypoint{ORB_ID(vehicle_trajectory_waypoint)}; /**< vehicle trajectory waypoint subscription */
120  uORB::SubscriptionData<vehicle_status_s> _sub_vehicle_status{ORB_ID(vehicle_status)}; /**< vehicle status subscription */
121 
122  vehicle_trajectory_waypoint_s _desired_waypoint{}; /**< desired vehicle trajectory waypoint to be sent to OA */
123 
124  uORB::Publication<vehicle_trajectory_waypoint_s> _pub_traj_wp_avoidance_desired{ORB_ID(vehicle_trajectory_waypoint_desired)}; /**< trajectory waypoint desired publication */
125  uORB::Publication<position_controller_status_s> _pub_pos_control_status{ORB_ID(position_controller_status)}; /**< position controller status publication */
126  uORB::PublicationQueued<vehicle_command_s> _pub_vehicle_command{ORB_ID(vehicle_command)}; /**< vehicle command do publication */
127 
128  matrix::Vector3f _curr_wp = {}; /**< current position triplet */
129  matrix::Vector3f _position = {}; /**< current vehicle position */
130  matrix::Vector3f _failsafe_position = {}; /**< vehicle position when entered in failsafe */
131 
132  systemlib::Hysteresis _avoidance_point_not_valid_hysteresis{false}; /**< becomes true if the companion doesn't start sending valid setpoints */
133  systemlib::Hysteresis _no_progress_z_hysteresis{false}; /**< becomes true if the vehicle is not making progress towards the z component of the goal */
134 
135  float _prev_pos_to_target_z = -1.f; /**< z distance to the goal */
136 
137  bool _ext_yaw_active = false; /**< true, if external yaw handling is active */
138 
139  /**
140  * Publishes vehicle command.
141  */
143 
145  (ParamFloat<px4::params::NAV_MC_ALT_RAD>) _param_nav_mc_alt_rad /**< Acceptance radius for multicopter altitude */
146  );
147 
148 };
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.
Definition: uORB.h:87
systemlib::Hysteresis _avoidance_point_not_valid_hysteresis
becomes true if the companion doesn&#39;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
PX4 custom flight modes.
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