Skip to content

Commit

Permalink
Merge branch 'main' into feat/planning/fix_dwaP_member_scope
Browse files Browse the repository at this point in the history
  • Loading branch information
Autumn60 authored Jul 14, 2024
2 parents d118d11 + 4f37039 commit ac6629f
Show file tree
Hide file tree
Showing 3 changed files with 75 additions and 11 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
#ifndef WHEEL_STUCK_UTILS__MATH__MATH_HPP_
#define WHEEL_STUCK_UTILS__MATH__MATH_HPP_

#include <algorithm>

namespace wheel_stuck_utils::math
{
inline double clamp01(const double value)
{
return std::clamp(value, 0.0, 1.0);
}

inline double lerp(const double a, const double b, const double t)
{
return a + clamp01(t) * (b - a);
}

// lerpの逆関数
inline double inverse_lerp(const double a, const double b, const double value)
{
if (a != b) {
return clamp01((value - a) / (b - a));
} else {
return 0; // ゼロ除算のため値を定義し得ないが、便宜上0を返す。
}
}

// 符号(-1, 0, 1)を返す
inline int sign(const double i)
{
return (i > 0) ? +1 : (i < 0) ? -1 : 0;
/*
if(i > 0)
return 1;
else if(i < 0)
return -1;
else
return 0;
*/
}

// 可変長引数を受け取り最小値を返す
template <typename T>
inline T min(T a)
{
return a;
}

template <typename T, typename... Args>
inline T min(T a, Args... args)
{
return std::min(a, min(args...));
}

// 可変長引数を受け取り最大値を返す
template <typename T>
inline T max(T b)
{
return b;
}

template <typename T, typename... Args>
inline T max(T b, Args... args)
{
return std::max(b, max(args...));
}

} // namespace wheel_stuck_utils::math

#endif // WHEEL_STUCK_UTILS__MATH__MATH_HPP_
9 changes: 0 additions & 9 deletions src/planning/dwa_planner/include/dwa_planner/dwa_planner.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
#include <nav_msgs/msg/occupancy_grid.hpp>
#include <nav_msgs/msg/odometry.hpp>

#include <algorithm>
#include <vector>

namespace dwa_planner
Expand Down Expand Up @@ -73,14 +72,6 @@ class DWAPlanner : public rclcpp::Node
double calculate_stage_cost(const State & state);
double calculate_terminal_cost(const State & state);

inline static double lerp(const double a, const double b, double t)
{
t = std::max(0.0, std::min(1.0, t));
return a + t * (b - a);
}

rclcpp::TimerBase::SharedPtr update_timer_;

OccupancyGridSubscription::SharedPtr map_sub_;
OdometrySubscription::SharedPtr odom_sub_;
PoseStampedSubscription::SharedPtr goal_sub_;
Expand Down
7 changes: 5 additions & 2 deletions src/planning/dwa_planner/src/dwa_planner.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
#include "dwa_planner/dwa_planner.hpp"

#include <wheel_stuck_utils/math/math.hpp>

#include <limits>

namespace dwa_planner
Expand Down Expand Up @@ -183,9 +185,10 @@ DWAPlanner::Trajectory DWAPlanner::planning()
Trajectory best_trajectory;

for (int v = 0; v < velocity_resolution_; v++) {
double velocity = lerp(window.min_velocity, window.max_velocity, v * velocity_resolution_inv_);
double velocity = wheel_stuck_utils::math::lerp(
window.min_velocity, window.max_velocity, v * velocity_resolution_inv_);
for (int a = 0; a < angular_velocity_resolution_; a++) {
double angular_velocity = lerp(
double angular_velocity = wheel_stuck_utils::math::lerp(
window.min_angular_velocity, window.max_angular_velocity,
a * angular_velocity_resolution_inv_);

Expand Down

0 comments on commit ac6629f

Please sign in to comment.