Skip to content
This repository has been archived by the owner on Aug 1, 2024. It is now read-only.

rename colprev params #501

Merged
merged 5 commits into from
Oct 21, 2019
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion avoidance/include/avoidance/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ struct ModelParameters {

// TODO: add estimator limitations for max speed and height

float param_mpc_col_prev_d = NAN; // Collision Prevention distance to keep from obstacle. -1 for disabled
float param_cp_dist = NAN; // Collision Prevention distance to keep from obstacle. -1 for disabled
// clang-format on
};

Expand Down
6 changes: 3 additions & 3 deletions avoidance/src/avoidance_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ void AvoidanceNode::px4ParamsCallback(const mavros_msgs::Param& msg) {
parse_param_f("MPC_XY_CRUISE", px4_.param_mpc_xy_cruise) ||
parse_param_f("MPC_Z_VEL_MAX_DN", px4_.param_mpc_vel_max_dn) ||
parse_param_f("MPC_Z_VEL_MAX_UP", px4_.param_mpc_z_vel_max_up) ||
parse_param_f("MPC_COL_PREV_D", px4_.param_mpc_col_prev_d) ||
parse_param_f("CP_DIST", px4_.param_cp_dist) ||
parse_param_f("NAV_ACC_RAD", px4_.param_nav_acc_rad);
// clang-format on
}
Expand All @@ -131,11 +131,11 @@ void AvoidanceNode::checkPx4Parameters() {
};
while (!should_exit_) {
request_param("MPC_XY_CRUISE", px4_.param_mpc_xy_cruise);
request_param("MPC_COL_PREV_D", px4_.param_mpc_col_prev_d);
request_param("CP_DIST", px4_.param_cp_dist);
request_param("MPC_LAND_SPEED", px4_.param_mpc_land_speed);
request_param("NAV_ACC_RAD", px4_.param_nav_acc_rad);

if (!std::isfinite(px4_.param_mpc_xy_cruise) || !std::isfinite(px4_.param_mpc_col_prev_d) ||
if (!std::isfinite(px4_.param_mpc_xy_cruise) || !std::isfinite(px4_.param_cp_dist) ||
!std::isfinite(px4_.param_mpc_land_speed) || !std::isfinite(px4_.param_nav_acc_rad)) {
std::this_thread::sleep_for(std::chrono::seconds(5));
} else {
Expand Down
4 changes: 2 additions & 2 deletions local_planner/src/nodes/local_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ void LocalPlanner::determineStrategy() {
cost_image_data_.clear();
cost_image_data_.resize(3 * GRID_LENGTH_E * GRID_LENGTH_Z, 0);

create2DObstacleRepresentation(px4_.param_mpc_col_prev_d > 0.f);
create2DObstacleRepresentation(px4_.param_cp_dist > 0.f);

// calculate the vehicle projected position on the line between the previous and current goal
Eigen::Vector2f u_prev_to_goal = (goal_ - prev_goal_).head<2>().normalized();
Expand Down Expand Up @@ -198,7 +198,7 @@ void LocalPlanner::setDefaultPx4Parameters() {
px4_.param_mpc_xy_cruise = 3.f;
px4_.param_mpc_tko_speed = 1.f;
px4_.param_mpc_land_speed = 0.7f;
px4_.param_mpc_col_prev_d = 4.f;
px4_.param_cp_dist = 4.f;
}

void LocalPlanner::getTree(std::vector<TreeNode>& tree, std::vector<int>& closed_set,
Expand Down
2 changes: 1 addition & 1 deletion local_planner/src/nodes/local_planner_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -455,7 +455,7 @@ void LocalPlannerNodelet::dynamicReconfigureCallback(avoidance::LocalPlannerNode

void LocalPlannerNodelet::publishLaserScan() const {
// inverted logic to make sure values like NAN default to sending the message
if (!(local_planner_->px4_.param_mpc_col_prev_d < 0)) {
if (!(local_planner_->px4_.param_cp_dist < 0)) {
sensor_msgs::LaserScan distance_data_to_fcu;
local_planner_->getObstacleDistanceData(distance_data_to_fcu);

Expand Down