Skip to content

Commit 537ca45

Browse files
committed
some minor optimizations (#3821)
1 parent a35b443 commit 537ca45

File tree

6 files changed

+20
-19
lines changed

6 files changed

+20
-19
lines changed

nav2_mppi_controller/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@ set(XTENSOR_USE_OPENMP 0)
1010

1111
find_package(ament_cmake REQUIRED)
1212
find_package(xtensor REQUIRED)
13+
find_package(xsimd REQUIRED)
1314

1415
set(dependencies_pkgs
1516
rclcpp

nav2_mppi_controller/include/nav2_mppi_controller/critics/obstacles_critic.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ class ObstaclesCritic : public CriticFunction
5454
* @param cost Costmap cost
5555
* @return bool if in collision
5656
*/
57-
bool inCollision(float cost) const;
57+
inline bool inCollision(float cost) const;
5858

5959
/**
6060
* @brief cost at a robot pose
@@ -63,14 +63,14 @@ class ObstaclesCritic : public CriticFunction
6363
* @param theta theta of pose
6464
* @return Collision information at pose
6565
*/
66-
CollisionCost costAtPose(float x, float y, float theta);
66+
inline CollisionCost costAtPose(float x, float y, float theta);
6767

6868
/**
6969
* @brief Distance to obstacle from cost
7070
* @param cost Costmap cost
7171
* @return float Distance to the obstacle represented by cost
7272
*/
73-
float distanceToObstacle(const CollisionCost & cost);
73+
inline float distanceToObstacle(const CollisionCost & cost);
7474

7575
/**
7676
* @brief Find the min cost of the inflation decay function for which the robot MAY be

nav2_mppi_controller/src/critics/constraint_critic.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -34,8 +34,8 @@ void ConstraintCritic::initialize()
3434
getParentParam(vx_min, "vx_min", -0.35);
3535

3636
const float min_sgn = vx_min > 0.0 ? 1.0 : -1.0;
37-
max_vel_ = std::sqrt(vx_max * vx_max + vy_max * vy_max);
38-
min_vel_ = min_sgn * std::sqrt(vx_min * vx_min + vy_max * vy_max);
37+
max_vel_ = sqrtf(vx_max * vx_max + vy_max * vy_max);
38+
min_vel_ = min_sgn * sqrtf(vx_min * vx_min + vy_max * vy_max);
3939
}
4040

4141
void ConstraintCritic::score(CriticData & data)

nav2_mppi_controller/src/critics/obstacles_critic.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -115,21 +115,21 @@ void ObstaclesCritic::score(CriticData & data)
115115
}
116116

117117
auto && raw_cost = xt::xtensor<float, 1>::from_shape({data.costs.shape(0)});
118-
raw_cost.fill(0.0);
118+
raw_cost.fill(0.0f);
119119
auto && repulsive_cost = xt::xtensor<float, 1>::from_shape({data.costs.shape(0)});
120-
repulsive_cost.fill(0.0);
120+
repulsive_cost.fill(0.0f);
121121

122122
const size_t traj_len = data.trajectories.x.shape(1);
123123
bool all_trajectories_collide = true;
124124
for (size_t i = 0; i < data.trajectories.x.shape(0); ++i) {
125125
bool trajectory_collide = false;
126-
float traj_cost = 0.0;
126+
float traj_cost = 0.0f;
127127
const auto & traj = data.trajectories;
128128
CollisionCost pose_cost;
129129

130130
for (size_t j = 0; j < traj_len; j++) {
131131
pose_cost = costAtPose(traj.x(i, j), traj.y(i, j), traj.yaws(i, j));
132-
if (pose_cost.cost < 1) {continue;} // In free space
132+
if (pose_cost.cost < 1.0f) {continue;} // In free space
133133

134134
if (inCollision(pose_cost.cost)) {
135135
trajectory_collide = true;

nav2_mppi_controller/src/critics/path_align_critic.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -88,12 +88,12 @@ void PathAlignCritic::score(CriticData & data)
8888
return;
8989
}
9090

91-
float dist_sq = 0, dx = 0, dy = 0, dyaw = 0, summed_dist = 0;
91+
float dist_sq = 0.0f, dx = 0.0f, dy = 0.0f, dyaw = 0.0f, summed_dist = 0.0f;
9292
double min_dist_sq = std::numeric_limits<float>::max();
9393
size_t min_s = 0;
9494

9595
for (size_t t = 0; t < batch_size; ++t) {
96-
summed_dist = 0;
96+
summed_dist = 0.0f;
9797
for (size_t p = trajectory_point_step_; p < time_steps; p += trajectory_point_step_) {
9898
min_dist_sq = std::numeric_limits<float>::max();
9999
min_s = 0;
@@ -118,7 +118,7 @@ void PathAlignCritic::score(CriticData & data)
118118
// The nearest path point to align to needs to be not in collision, else
119119
// let the obstacle critic take over in this region due to dynamic obstacles
120120
if (min_s != 0 && (*data.path_pts_valid)[min_s]) {
121-
summed_dist += std::sqrt(min_dist_sq);
121+
summed_dist += sqrtf(min_dist_sq);
122122
}
123123
}
124124

nav2_mppi_controller/src/optimizer.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -286,8 +286,8 @@ void Optimizer::integrateStateVelocities(
286286

287287
const auto yaw_offseted = xt::view(traj_yaws, xt::range(1, _));
288288

289-
xt::noalias(xt::view(yaw_cos, 0)) = std::cos(initial_yaw);
290-
xt::noalias(xt::view(yaw_sin, 0)) = std::sin(initial_yaw);
289+
xt::noalias(xt::view(yaw_cos, 0)) = cosf(initial_yaw);
290+
xt::noalias(xt::view(yaw_sin, 0)) = sinf(initial_yaw);
291291
xt::noalias(xt::view(yaw_cos, xt::range(1, _))) = xt::cos(yaw_offseted);
292292
xt::noalias(xt::view(yaw_sin, xt::range(1, _))) = xt::sin(yaw_offseted);
293293

@@ -316,8 +316,8 @@ void Optimizer::integrateStateVelocities(
316316

317317
auto && yaw_cos = xt::xtensor<float, 2>::from_shape(trajectories.yaws.shape());
318318
auto && yaw_sin = xt::xtensor<float, 2>::from_shape(trajectories.yaws.shape());
319-
xt::noalias(xt::view(yaw_cos, xt::all(), 0)) = std::cos(initial_yaw);
320-
xt::noalias(xt::view(yaw_sin, xt::all(), 0)) = std::sin(initial_yaw);
319+
xt::noalias(xt::view(yaw_cos, xt::all(), 0)) = cosf(initial_yaw);
320+
xt::noalias(xt::view(yaw_sin, xt::all(), 0)) = sinf(initial_yaw);
321321
xt::noalias(xt::view(yaw_cos, xt::all(), xt::range(1, _))) = xt::cos(yaws_cutted);
322322
xt::noalias(xt::view(yaw_sin, xt::all(), xt::range(1, _))) = xt::sin(yaws_cutted);
323323

@@ -358,16 +358,16 @@ void Optimizer::updateControlSequence()
358358
auto bounded_noises_vx = state_.cvx - control_sequence_.vx;
359359
auto bounded_noises_wz = state_.cwz - control_sequence_.wz;
360360
xt::noalias(costs_) +=
361-
s.gamma / std::pow(s.sampling_std.vx, 2) * xt::sum(
361+
s.gamma / powf(s.sampling_std.vx, 2) * xt::sum(
362362
xt::view(control_sequence_.vx, xt::newaxis(), xt::all()) * bounded_noises_vx, 1, immediate);
363363
xt::noalias(costs_) +=
364-
s.gamma / std::pow(s.sampling_std.wz, 2) * xt::sum(
364+
s.gamma / powf(s.sampling_std.wz, 2) * xt::sum(
365365
xt::view(control_sequence_.wz, xt::newaxis(), xt::all()) * bounded_noises_wz, 1, immediate);
366366

367367
if (isHolonomic()) {
368368
auto bounded_noises_vy = state_.cvy - control_sequence_.vy;
369369
xt::noalias(costs_) +=
370-
s.gamma / std::pow(s.sampling_std.vy, 2) * xt::sum(
370+
s.gamma / powf(s.sampling_std.vy, 2) * xt::sum(
371371
xt::view(control_sequence_.vy, xt::newaxis(), xt::all()) * bounded_noises_vy,
372372
1, immediate);
373373
}

0 commit comments

Comments
 (0)