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

fix(freespace_planner): fix motion_velocity_smoother error while parking #6713

Merged
Changes from 1 commit
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
Next Next commit
fix(freespace_planner): prevent publishing stop trajectory with only …
…one point in a new parking cycle

Signed-off-by: AhmedEbrahim <ahmed.a.d.ebrahim@gmail.com>

fix(freespace_planner): prevent publishing stop trajectory with only one point in a new parking cycle

Signed-off-by: Ahmed Ebrahim <ahmed.ebrahim@leodrive.ai>
ahmeddesokyebrahim committed May 9, 2024
commit e7f019916ccf0fb137785abfeb54314ecab52efb
Original file line number Diff line number Diff line change
@@ -134,6 +134,7 @@ class FreespacePlannerNode : public rclcpp::Node
size_t target_index_;
bool is_completed_ = false;
bool reset_in_progress_ = false;
bool is_new_parking_cycle_ = true;

LaneletRoute::ConstSharedPtr route_;
OccupancyGrid::ConstSharedPtr occupancy_grid_;
Original file line number Diff line number Diff line change
@@ -321,6 +321,8 @@ void FreespacePlannerNode::onRoute(const LaneletRoute::ConstSharedPtr msg)
goal_pose_.header = msg->header;
goal_pose_.pose = msg->goal_pose;

is_new_parking_cycle_ = true;

reset();
}

@@ -447,13 +449,16 @@ void FreespacePlannerNode::onTimer()
// Must stop before replanning any new trajectory
const bool is_reset_required = !reset_in_progress_ && isPlanRequired();
if (is_reset_required) {
// Stop before planning new trajectory
const auto stop_trajectory = partial_trajectory_.points.empty()
? createStopTrajectory(current_pose_)
: createStopTrajectory(partial_trajectory_);
trajectory_pub_->publish(stop_trajectory);
debug_pose_array_pub_->publish(trajectory2PoseArray(stop_trajectory));
debug_partial_pose_array_pub_->publish(trajectory2PoseArray(stop_trajectory));
// Stop before planning new trajectory, except in a new parking cycle as the vehicle already
// stops.
if (!is_new_parking_cycle_) {
const auto stop_trajectory = partial_trajectory_.points.empty()
? createStopTrajectory(current_pose_)
: createStopTrajectory(partial_trajectory_);
trajectory_pub_->publish(stop_trajectory);
debug_pose_array_pub_->publish(trajectory2PoseArray(stop_trajectory));
debug_partial_pose_array_pub_->publish(trajectory2PoseArray(stop_trajectory));
}

reset();

@@ -487,6 +492,8 @@ void FreespacePlannerNode::onTimer()
trajectory_pub_->publish(partial_trajectory_);
debug_pose_array_pub_->publish(trajectory2PoseArray(trajectory_));
debug_partial_pose_array_pub_->publish(trajectory2PoseArray(partial_trajectory_));

is_new_parking_cycle_ = false;
}

void FreespacePlannerNode::planTrajectory()