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

Add param for turning in place #38

Merged
merged 1 commit into from
Oct 20, 2023
Merged
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
2 changes: 1 addition & 1 deletion config/planner_param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ angle_resolution: 0.0087
dist_to_goal_th: 0.3
turn_direction_th: 0.1
angle_to_goal_th: 0.26
max_yawrate_in_situ_turns: 0.4
min_in_place_yawrate: 0.3
dist_from_head_to_obj: 0.5
velocity_samples: 3
yawrate_samples: 20
1 change: 1 addition & 0 deletions config/robot_param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,6 @@ robot_frame: "base_link"
max_velocity: 1.0
min_velocity: 0.0
max_yawrate: 1.0
min_in_place_yawrate: 0.3
max_acceleration: 0.5
max_d_yawrate: 3.2
2 changes: 1 addition & 1 deletion include/point_follow_planner/point_follow_planner.h
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ class PointFollowPlanner
double max_velocity_;
double min_velocity_;
double max_yawrate_;
double max_yawrate_in_situ_turns_;
double min_in_place_yawrate_;
double max_acceleration_;
double max_d_yawrate_;
double angle_resolution_;
Expand Down
16 changes: 11 additions & 5 deletions src/point_follow_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ PointFollowPlanner::PointFollowPlanner(void)
private_nh_.param<double>("max_velocity", max_velocity_, {0.55});
private_nh_.param<double>("min_velocity", min_velocity_, {0.0});
private_nh_.param<double>("max_yawrate", max_yawrate_, {1.0});
private_nh_.param<double>("max_yawrate_in_situ_turns", max_yawrate_in_situ_turns_, max_yawrate_);
private_nh_.param<double>("min_in_place_yawrate", min_in_place_yawrate_, {0.3});
private_nh_.param<double>("max_acceleration", max_acceleration_, {0.5});
private_nh_.param<double>("max_d_yawrate", max_d_yawrate_, {3.2});
private_nh_.param<double>("angle_resolution", angle_resolution_, {0.2});
Expand All @@ -38,7 +38,7 @@ PointFollowPlanner::PointFollowPlanner(void)
ROS_INFO_STREAM("max_velocity: " << max_velocity_);
ROS_INFO_STREAM("min_velocity: " << min_velocity_);
ROS_INFO_STREAM("max_yawrate: " << max_yawrate_);
ROS_INFO_STREAM("max_yawrate_in_situ_turns: " << max_yawrate_in_situ_turns_);
ROS_INFO_STREAM("min_in_place_yawrate: " << min_in_place_yawrate_);
ROS_INFO_STREAM("max_acceleration: " << max_acceleration_);
ROS_INFO_STREAM("max_d_yawrate: " << max_d_yawrate_);
ROS_INFO_STREAM("angle_resolution: " << angle_resolution_);
Expand Down Expand Up @@ -411,7 +411,9 @@ geometry_msgs::Twist PointFollowPlanner::calc_cmd_vel()
{
const double angle_to_goal = atan2(goal.y(), goal.x());
cmd_vel.angular.z =
std::min(std::max(angle_to_goal, -max_yawrate_in_situ_turns_), max_yawrate_in_situ_turns_);
angle_to_goal > 0 ? std::min(angle_to_goal, max_yawrate_) : std::max(angle_to_goal, -max_yawrate_);
cmd_vel.angular.z = cmd_vel.angular.z > 0 ? std::max(cmd_vel.angular.z, min_in_place_yawrate_)
: std::min(cmd_vel.angular.z, -min_in_place_yawrate_);
generate_trajectory(best_traj, cmd_vel.angular.z, goal);
trajectories.push_back(best_traj);
}
Expand All @@ -427,7 +429,9 @@ geometry_msgs::Twist PointFollowPlanner::calc_cmd_vel()
has_reached_ = true;
if (turn_direction_th_ < fabs(goal[2]))
{
cmd_vel.angular.z = std::min(std::max(goal[2], -max_yawrate_in_situ_turns_), max_yawrate_in_situ_turns_);
cmd_vel.angular.z = goal[2] > 0 ? std::min(goal[2], max_yawrate_) : std::max(goal[2], -max_yawrate_);
cmd_vel.angular.z = cmd_vel.angular.z > 0 ? std::max(cmd_vel.angular.z, min_in_place_yawrate_)
: std::min(cmd_vel.angular.z, -min_in_place_yawrate_);
}
else
{
Expand All @@ -451,7 +455,9 @@ bool PointFollowPlanner::can_adjust_robot_direction(const Eigen::Vector3d &goal)
if (fabs(angle_to_goal) < angle_to_goal_th_)
return false;

const double yawrate = std::min(std::max(angle_to_goal, -max_yawrate_in_situ_turns_), max_yawrate_in_situ_turns_);
double yawrate = angle_to_goal > 0 ? std::min(angle_to_goal, max_yawrate_) : std::max(angle_to_goal, -max_yawrate_);
yawrate = yawrate > 0 ? std::max(yawrate, min_in_place_yawrate_) : std::min(yawrate, -min_in_place_yawrate_);

std::vector<State> traj;
generate_trajectory(traj, yawrate, goal);

Expand Down