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

Commit

Permalink
Fix style and tests
Browse files Browse the repository at this point in the history
  • Loading branch information
Nico van Duijn committed Jul 29, 2019
1 parent decc63d commit 602fa5c
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 3 deletions.
1 change: 1 addition & 0 deletions local_planner/src/nodes/planner_functions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ void processPointcloud(pcl::PointCloud<pcl::PointXYZI>& final_cloud,
}
}
}
}

// combine with old cloud
for (const pcl::PointXYZI& xyzi : old_cloud) {
Expand Down
2 changes: 1 addition & 1 deletion local_planner/src/nodes/star_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ void StarPlanner::buildLookAheadTree() {
int children = 0;
for (candidateDirection candidate : candidate_vector) {
simulation_state state = tree_[origin].state;
TrajectorySimulator sim(lims_, state, 0.05f); // todo: parameterize simulation step size [s]
TrajectorySimulator sim(lims_, state, 0.05f); // todo: parameterize simulation step size [s]
std::vector<simulation_state> trajectory = sim.generate_trajectory(candidate.toEigen(), tree_node_distance_);

// Ignore node if it brings us farther away from the goal
Expand Down
10 changes: 8 additions & 2 deletions local_planner/test/test_star_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,14 @@ class StarPlannerTests : public ::testing::Test {
}
}
costParameters cost_params;

star_planner.setParams(cost_params);
simulation_limits lims;
lims.max_z_velocity = 3.f;
lims.min_z_velocity = -1.f;
lims.max_xy_velocity_norm = 3.f;
lims.max_acceleration_norm = 5.f;
lims.max_jerk_norm = 20.f;

star_planner.setParams(cost_params, lims);
star_planner.setPointcloud(cloud);
star_planner.setPose(position, velocity);
star_planner.setGoal(goal);
Expand Down

0 comments on commit 602fa5c

Please sign in to comment.