Browse Source

ObstacleAvoidance: use convention for paramter name

sbg
Martina Rivizzigno 6 years ago committed by Matthias Grob
parent
commit
61f69ed139
  1. 2
      src/lib/FlightTasks/tasks/Utility/ObstacleAvoidance.cpp
  2. 2
      src/lib/FlightTasks/tasks/Utility/ObstacleAvoidance.hpp

2
src/lib/FlightTasks/tasks/Utility/ObstacleAvoidance.cpp

@ -190,7 +190,7 @@ void ObstacleAvoidance::checkAvoidanceProgress(const Vector3f &pos, const Vector
const float pos_to_target_z = fabsf(_curr_wp(2) - _position(2)); const float pos_to_target_z = fabsf(_curr_wp(2) - _position(2));
if (pos_to_target.length() < target_acceptance_radius && pos_to_target_z > NAV_MC_ALT_RAD.get() if (pos_to_target.length() < target_acceptance_radius && pos_to_target_z > _param_nav_mc_alt_rad.get()
&& wp_type != position_setpoint_s::SETPOINT_TYPE_TAKEOFF) { && wp_type != position_setpoint_s::SETPOINT_TYPE_TAKEOFF) {
// vehicle above or below the target waypoint // vehicle above or below the target waypoint
pos_control_status.altitude_acceptance = pos_to_target_z + 0.5f; pos_control_status.altitude_acceptance = pos_to_target_z + 0.5f;

2
src/lib/FlightTasks/tasks/Utility/ObstacleAvoidance.hpp

@ -109,7 +109,7 @@ private:
uORB::Subscription<vehicle_status_s> *_sub_vehicle_status{nullptr}; /**< vehicle status subscription */ uORB::Subscription<vehicle_status_s> *_sub_vehicle_status{nullptr}; /**< vehicle status subscription */
DEFINE_PARAMETERS( DEFINE_PARAMETERS(
(ParamFloat<px4::params::NAV_MC_ALT_RAD>) NAV_MC_ALT_RAD /**< Acceptance radius for multicopter altitude */ (ParamFloat<px4::params::NAV_MC_ALT_RAD>) _param_nav_mc_alt_rad /**< Acceptance radius for multicopter altitude */
); );
vehicle_trajectory_waypoint_s _desired_waypoint = {}; /**< desired vehicle trajectory waypoint to be sent to OA */ vehicle_trajectory_waypoint_s _desired_waypoint = {}; /**< desired vehicle trajectory waypoint to be sent to OA */

Loading…
Cancel
Save