Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: fix dwa_planner member scope #40

Closed
wants to merge 4 commits into from
Closed
Show file tree
Hide file tree
Changes from all 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

This file was deleted.

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

#include <algorithm>
#include <vector>

namespace dwa_planner
Expand Down Expand Up @@ -59,11 +60,9 @@ class DWAPlanner : public rclcpp::Node

public:
explicit DWAPlanner(const rclcpp::NodeOptions & options);
void update();

rclcpp::TimerBase::SharedPtr update_timer_;

private:
void update();
bool subscribe_and_validate();
bool try_subscribe_map();
bool try_subscribe_odom();
Expand All @@ -74,6 +73,14 @@ 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: 2 additions & 5 deletions src/planning/dwa_planner/src/dwa_planner.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,5 @@
#include "dwa_planner/dwa_planner.hpp"

#include <wheel_stuck_utils/math/math.hpp>

#include <limits>

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

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

Expand Down
Loading