PX4 Firmware
PX4 Autopilot Software http://px4.io
ObstacleAvoidance.cpp
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.cpp
36  */
37 
38 #include "ObstacleAvoidance.hpp"
39 
40 using namespace matrix;
41 using namespace time_literals;
42 
43 /** Timeout in us for trajectory data to get considered invalid */
44 static constexpr uint64_t TRAJECTORY_STREAM_TIMEOUT_US = 500_ms;
45 /** If Flighttask fails, keep 0.5 seconds the current setpoint before going into failsafe land */
46 static constexpr uint64_t TIME_BEFORE_FAILSAFE = 500_ms;
47 static constexpr uint64_t Z_PROGRESS_TIMEOUT_US = 2_s;
48 
49 ObstacleAvoidance::ObstacleAvoidance(ModuleParams *parent) :
50  ModuleParams(parent)
51 {
56 
57 }
58 
59 void ObstacleAvoidance::injectAvoidanceSetpoints(Vector3f &pos_sp, Vector3f &vel_sp, float &yaw_sp,
60  float &yaw_speed_sp)
61 {
64 
65  if (_sub_vehicle_status.get().nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER) {
66  // if in failsafe nav_state LOITER, don't inject setpoints from avoidance system
67  return;
68  }
69 
70  const bool avoidance_data_timeout = hrt_elapsed_time((hrt_abstime *)&_sub_vehicle_trajectory_waypoint.get().timestamp)
72  const bool avoidance_point_valid =
73  _sub_vehicle_trajectory_waypoint.get().waypoints[vehicle_trajectory_waypoint_s::POINT_0].point_valid;
74 
76 
77  if (avoidance_data_timeout || _avoidance_point_not_valid_hysteresis.get_state()) {
78  PX4_WARN("Obstacle Avoidance system failed, loitering");
80 
81  if (!PX4_ISFINITE(_failsafe_position(0)) || !PX4_ISFINITE(_failsafe_position(1))
82  || !PX4_ISFINITE(_failsafe_position(2))) {
83  // save vehicle position when entering failsafe
85  }
86 
87  pos_sp = _failsafe_position;
88  vel_sp.setNaN();
89  yaw_sp = NAN;
90  yaw_speed_sp = NAN;
91  return;
92 
93  } else {
95  }
96 
97  if (avoidance_point_valid) {
98  pos_sp = Vector3f(_sub_vehicle_trajectory_waypoint.get().waypoints[vehicle_trajectory_waypoint_s::POINT_0].position);
99  vel_sp = Vector3f(_sub_vehicle_trajectory_waypoint.get().waypoints[vehicle_trajectory_waypoint_s::POINT_0].velocity);
100 
101  if (!_ext_yaw_active) {
102  // inject yaw setpoints only if weathervane isn't active
103  yaw_sp = _sub_vehicle_trajectory_waypoint.get().waypoints[vehicle_trajectory_waypoint_s::POINT_0].yaw;
104  yaw_speed_sp = _sub_vehicle_trajectory_waypoint.get().waypoints[vehicle_trajectory_waypoint_s::POINT_0].yaw_speed;
105  }
106  }
107 
108 }
109 
110 void ObstacleAvoidance::updateAvoidanceDesiredWaypoints(const Vector3f &curr_wp, const float curr_yaw,
111  const float curr_yawspeed, const Vector3f &next_wp, const float next_yaw, const float next_yawspeed,
112  const bool ext_yaw_active, const int wp_type)
113 {
115  _desired_waypoint.type = vehicle_trajectory_waypoint_s::MAV_TRAJECTORY_REPRESENTATION_WAYPOINTS;
116  _curr_wp = curr_wp;
117  _ext_yaw_active = ext_yaw_active;
118 
119  curr_wp.copyTo(_desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_1].position);
120  Vector3f(NAN, NAN, NAN).copyTo(_desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_1].velocity);
121  Vector3f(NAN, NAN, NAN).copyTo(_desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_1].acceleration);
122 
123  _desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_1].yaw = curr_yaw;
124  _desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_1].yaw_speed = curr_yawspeed;
125  _desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_1].point_valid = true;
126  _desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_1].type = wp_type;
127 
128  next_wp.copyTo(_desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_2].position);
129  Vector3f(NAN, NAN, NAN).copyTo(_desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_2].velocity);
130  Vector3f(NAN, NAN, NAN).copyTo(_desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_2].acceleration);
131 
132  _desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_2].yaw = next_yaw;
133  _desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_2].yaw_speed = next_yawspeed;
134  _desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_2].point_valid = true;
135 }
136 
137 void ObstacleAvoidance::updateAvoidanceDesiredSetpoints(const Vector3f &pos_sp, const Vector3f &vel_sp, const int type)
138 {
139  pos_sp.copyTo(_desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_0].position);
140  vel_sp.copyTo(_desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_0].velocity);
141  _desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_0].type = type;
142  _desired_waypoint.waypoints[vehicle_trajectory_waypoint_s::POINT_0].point_valid = true;
143 
145 
147 }
148 
150  float target_acceptance_radius, const Vector2f &closest_pt)
151 {
152  _position = pos;
153  position_controller_status_s pos_control_status = {};
154  pos_control_status.timestamp = hrt_absolute_time();
155 
156  // vector from previous triplet to current target
157  Vector2f prev_to_target = Vector2f(_curr_wp - prev_wp);
158  // vector from previous triplet to the vehicle projected position on the line previous-target triplet
159  Vector2f prev_to_closest_pt = closest_pt - Vector2f(prev_wp);
160  // fraction of the previous-tagerget line that has been flown
161  const float prev_curr_travelled = prev_to_closest_pt.length() / prev_to_target.length();
162 
163  Vector2f pos_to_target = Vector2f(_curr_wp - _position);
164 
165  if (prev_curr_travelled > 1.0f) {
166  // if the vehicle projected position on the line previous-target is past the target waypoint,
167  // increase the target acceptance radius such that navigator will update the triplets
168  pos_control_status.acceptance_radius = pos_to_target.length() + 0.5f;
169  }
170 
171  const float pos_to_target_z = fabsf(_curr_wp(2) - _position(2));
172 
173  bool no_progress_z = (pos_to_target_z > _prev_pos_to_target_z);
175 
176  if (pos_to_target.length() < target_acceptance_radius && pos_to_target_z > _param_nav_mc_alt_rad.get()
178  // vehicle above or below the target waypoint
179  pos_control_status.altitude_acceptance = pos_to_target_z + 0.5f;
180  }
181 
182  _prev_pos_to_target_z = pos_to_target_z;
183 
184  // do not check for waypoints yaw acceptance in navigator
185  pos_control_status.yaw_acceptance = NAN;
186 
187  _pub_pos_control_status.publish(pos_control_status);
188 }
189 
191 {
193  command.timestamp = hrt_absolute_time();
194  command.command = vehicle_command_s::VEHICLE_CMD_DO_SET_MODE;
195  command.param1 = (float)1; // base mode
196  command.param3 = (float)0; // sub mode
197  command.target_system = 1;
198  command.target_component = 1;
199  command.source_system = 1;
200  command.source_component = 1;
201  command.confirmation = false;
202  command.from_external = false;
203  command.param2 = (float)PX4_CUSTOM_MAIN_MODE_AUTO;
205 
206  // publish the vehicle command
208 }
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...
bool publish(const T &data)
Publish the struct.
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.
static constexpr uint64_t TIME_BEFORE_FAILSAFE
If Flighttask fails, keep 0.5 seconds the current setpoint before going into failsafe land...
matrix::Vector3f _failsafe_position
vehicle position when entered in failsafe
void copyTo(Type dst[M *N]) const
Definition: Matrix.hpp:115
float _prev_pos_to_target_z
z distance to the goal
matrix::Vector3f _curr_wp
current position triplet
void set_state_and_update(const bool new_state, const hrt_abstime &now_us)
Definition: hysteresis.cpp:57
bool publish(const T &data)
Publish the struct.
Definition: Publication.hpp:68
systemlib::Hysteresis _avoidance_point_not_valid_hysteresis
becomes true if the companion doesn&#39;t start sending valid setpoints
bool get_state() const
Definition: hysteresis.h:60
const vehicle_trajectory_waypoint_s empty_trajectory_waypoint
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
uORB::SubscriptionData< vehicle_status_s > _sub_vehicle_status
vehicle status subscription
Vector2< float > Vector2f
Definition: Vector2.hpp:69
static hrt_abstime hrt_elapsed_time(const hrt_abstime *then)
Compute the delta between a timestamp taken in the past and now.
Definition: drv_hrt.h:102
static constexpr uint64_t Z_PROGRESS_TIMEOUT_US
Type length() const
Definition: Vector.hpp:83
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
const T & get() const
Vector3< float > Vector3f
Definition: Vector3.hpp:136
static constexpr uint64_t TRAJECTORY_STREAM_TIMEOUT_US
Timeout in us for trajectory data to get considered invalid.
void setNaN()
Definition: Matrix.hpp:442
void set_hysteresis_time_from(const bool from_state, const hrt_abstime new_hysteresis_time_us)
Definition: hysteresis.cpp:46
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
struct trajectory_waypoint_s waypoints[5]
uORB::PublicationQueued< vehicle_command_s > _pub_vehicle_command
vehicle command do publication
void _publishVehicleCmdDoLoiter()
Publishes vehicle command.
bool _ext_yaw_active
true, if external yaw handling is active
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
This class is used to inject the setpoints of an obstacle avoidance system into the FlightTasks...