Rename parameter MPC_OBS_AVOID to COM_OBS_AVOID and change the location to commander.

This commit is contained in:
baumanta 2018-12-19 11:19:45 +01:00 committed by Beat Küng
parent f42b378b9b
commit d42b9205f9
7 changed files with 18 additions and 19 deletions

View File

@ -55,8 +55,8 @@ px4_add_board(
logger
mavlink
#mc_att_control
mc_pos_control
navigator
#mc_pos_control
#navigator
position_estimator_inav
#sensors
#vmount

View File

@ -227,7 +227,7 @@ bool FlightTaskAuto::_evaluateTriplets()
_mission_gear = _sub_triplet_setpoint->get().current.landing_gear;
}
if (MPC_OBS_AVOID.get() && _sub_vehicle_status->get().is_rotary_wing) {
if (COM_OBS_AVOID.get() && _sub_vehicle_status->get().is_rotary_wing) {
_checkAvoidanceProgress();
}

View File

@ -109,7 +109,7 @@ protected:
(ParamFloat<px4::params::MPC_CRUISE_90>) MPC_CRUISE_90, // speed at corner when angle is 90 degrees move to line
(ParamFloat<px4::params::NAV_MC_ALT_RAD>) NAV_MC_ALT_RAD, //vertical acceptance radius at which waypoints are updated
(ParamInt<px4::params::MPC_YAW_MODE>) MPC_YAW_MODE, // defines how heading is executed,
(ParamInt<px4::params::MPC_OBS_AVOID>) MPC_OBS_AVOID // obstacle avoidance active
(ParamInt<px4::params::COM_OBS_AVOID>) COM_OBS_AVOID // obstacle avoidance active
);
private:

View File

@ -118,7 +118,7 @@ private:
(ParamInt<px4::params::COM_LOW_BAT_ACT>) _low_bat_action,
(ParamFloat<px4::params::COM_DISARM_LAND>) _disarm_when_landed_timeout,
(ParamInt<px4::params::MPC_OBS_AVOID>) _obs_avoid
(ParamInt<px4::params::COM_OBS_AVOID>) _obs_avoid
)
const int64_t POSVEL_PROBATION_MIN = 1_s; /**< minimum probation duration (usec) */

View File

@ -811,3 +811,12 @@ PARAM_DEFINE_INT32(NAV_DLL_ACT, 0);
* @group Mission
*/
PARAM_DEFINE_INT32(NAV_RCL_ACT, 2);
/**
* Flag to enable obstacle avoidance
* Temporary Parameter to enable interface testing
*
* @boolean
* @group Mission
*/
PARAM_DEFINE_INT32(COM_OBS_AVOID, 0);

View File

@ -160,7 +160,7 @@ private:
(ParamInt<px4::params::MPC_AUTO_MODE>) MPC_AUTO_MODE,
(ParamInt<px4::params::MPC_ALT_MODE>) MPC_ALT_MODE,
(ParamFloat<px4::params::MPC_SPOOLUP_TIME>) MPC_SPOOLUP_TIME, /**< time to let motors spool up after arming */
(ParamInt<px4::params::MPC_OBS_AVOID>) MPC_OBS_AVOID, /**< enable obstacle avoidance */
(ParamInt<px4::params::COM_OBS_AVOID>) COM_OBS_AVOID, /**< enable obstacle avoidance */
(ParamFloat<px4::params::MPC_TILTMAX_LND>) MPC_TILTMAX_LND /**< maximum tilt for landing and smooth takeoff */
);
@ -1141,7 +1141,7 @@ void
MulticopterPositionControl::update_avoidance_waypoint_desired(PositionControlStates &states,
vehicle_local_position_setpoint_s &setpoint)
{
if (MPC_OBS_AVOID.get()) {
if (COM_OBS_AVOID.get()) {
_traj_wp_avoidance_desired = _flight_tasks.getAvoidanceWaypoint();
_traj_wp_avoidance_desired.timestamp = hrt_absolute_time();
_traj_wp_avoidance_desired.type = vehicle_trajectory_waypoint_s::MAV_TRAJECTORY_REPRESENTATION_WAYPOINTS;
@ -1193,7 +1193,7 @@ MulticopterPositionControl::reset_setpoint_to_nan(vehicle_local_position_setpoin
bool
MulticopterPositionControl::use_obstacle_avoidance()
{
if (MPC_OBS_AVOID.get()) {
if (COM_OBS_AVOID.get()) {
const bool avoidance_data_timeout = hrt_elapsed_time((hrt_abstime *)&_traj_wp_avoidance.timestamp) > TRAJECTORY_STREAM_TIMEOUT_US;
const bool avoidance_point_valid = _traj_wp_avoidance.waypoints[vehicle_trajectory_waypoint_s::POINT_0].point_valid == true;
const bool in_mission = _vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION;

View File

@ -705,16 +705,7 @@ PARAM_DEFINE_INT32(MPC_AUTO_MODE, 1);
PARAM_DEFINE_FLOAT(MPC_SPOOLUP_TIME, 0.0f);
/**
* Flag to enable obstacle avoidance
* Temporary Parameter to enable interface testing
*
* @boolean
* @group Multicopter Position Control
*/
PARAM_DEFINE_INT32(MPC_OBS_AVOID, 0);
/**
* Yaw mode
* Yaw mode.
*
* Specifies the heading in Auto.
*
@ -727,4 +718,3 @@ PARAM_DEFINE_INT32(MPC_OBS_AVOID, 0);
* @group Mission
*/
PARAM_DEFINE_INT32(MPC_YAW_MODE, 0);