Skip to content

Commit

Permalink
Modified the autoware_freespace_planner and autoware_freespace_planni…
Browse files Browse the repository at this point in the history
…ng_algorithms packages to use the node clock instead of rclcpp detached clock. This allows the module to make use of sim time. Previously during simulation the parking trajectory would have system time in trajectory header messages causing downstream issues like non-clearance of trajectory buffers in motion planning based on elapsed time.
  • Loading branch information
Steven Brills committed Oct 24, 2024
1 parent 3e0d3c7 commit 296fd45
Show file tree
Hide file tree
Showing 9 changed files with 62 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -58,13 +58,13 @@ size_t get_next_target_index(
const size_t current_target_index);

Trajectory get_partial_trajectory(
const Trajectory & trajectory, const size_t start_index, const size_t end_index);
const Trajectory & trajectory, const size_t start_index, const size_t end_index, const rclcpp::Clock::SharedPtr clock);

Trajectory create_trajectory(
const PoseStamped & current_pose, const PlannerWaypoints & planner_waypoints,
const double & velocity);

Trajectory create_stop_trajectory(const PoseStamped & current_pose);
Trajectory create_stop_trajectory(const PoseStamped & current_pose, const rclcpp::Clock::SharedPtr clock);

Trajectory create_stop_trajectory(const Trajectory & trajectory);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ bool FreespacePlannerNode::checkCurrentTrajectoryCollision()
partial_trajectory_.points, current_pose_.pose.position);
const size_t end_index_partial = partial_trajectory_.points.size() - 1;
const auto forward_trajectory =
utils::get_partial_trajectory(partial_trajectory_, nearest_index_partial, end_index_partial);
utils::get_partial_trajectory(partial_trajectory_, nearest_index_partial, end_index_partial, get_clock());

const bool is_obs_found =
algo_->hasObstacleOnTrajectory(utils::trajectory_to_pose_array(forward_trajectory));
Expand Down Expand Up @@ -311,7 +311,7 @@ void FreespacePlannerNode::onTimer()
// stops.
if (!is_new_parking_cycle_) {
const auto stop_trajectory = partial_trajectory_.points.empty()
? utils::create_stop_trajectory(current_pose_)
? utils::create_stop_trajectory(current_pose_, get_clock())
: utils::create_stop_trajectory(partial_trajectory_);
trajectory_pub_->publish(stop_trajectory);
debug_pose_array_pub_->publish(utils::trajectory_to_pose_array(stop_trajectory));
Expand Down Expand Up @@ -347,7 +347,7 @@ void FreespacePlannerNode::onTimer()
// Update partial trajectory
updateTargetIndex();
partial_trajectory_ =
utils::get_partial_trajectory(trajectory_, prev_target_index_, target_index_);
utils::get_partial_trajectory(trajectory_, prev_target_index_, target_index_, get_clock());

// Publish messages
trajectory_pub_->publish(partial_trajectory_);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,11 +87,12 @@ size_t get_next_target_index(
}

Trajectory get_partial_trajectory(
const Trajectory & trajectory, const size_t start_index, const size_t end_index)
const Trajectory & trajectory, const size_t start_index, const size_t end_index,
const rclcpp::Clock::SharedPtr clock)
{
Trajectory partial_trajectory;
partial_trajectory.header = trajectory.header;
partial_trajectory.header.stamp = rclcpp::Clock().now();
partial_trajectory.header.stamp = clock->now();

partial_trajectory.points.reserve(trajectory.points.size());
for (size_t i = start_index; i <= end_index; ++i) {
Expand Down Expand Up @@ -134,12 +135,13 @@ Trajectory create_trajectory(
return trajectory;
}

Trajectory create_stop_trajectory(const PoseStamped & current_pose)
Trajectory create_stop_trajectory(const PoseStamped & current_pose,
const rclcpp::Clock::SharedPtr clock)
{
PlannerWaypoints waypoints;
PlannerWaypoint waypoint;

waypoints.header.stamp = rclcpp::Clock().now();
waypoints.header.stamp = clock->now();
waypoints.header.frame_id = current_pose.header.frame_id;
waypoint.pose.header = waypoints.header;
waypoint.pose.pose = current_pose.pose;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -158,8 +158,8 @@ class AbstractPlanningAlgorithm
{
public:
AbstractPlanningAlgorithm(
const PlannerCommonParam & planner_common_param, const VehicleShape & collision_vehicle_shape)
: planner_common_param_(planner_common_param), collision_vehicle_shape_(collision_vehicle_shape)
const PlannerCommonParam & planner_common_param, const rclcpp::Clock::SharedPtr & clock, const VehicleShape & collision_vehicle_shape)
: planner_common_param_(planner_common_param), collision_vehicle_shape_(collision_vehicle_shape), clock_(clock)
{
planner_common_param_.turning_steps = std::max(planner_common_param_.turning_steps, 1);
collision_vehicle_shape_.max_steering *= planner_common_param_.max_turning_ratio;
Expand All @@ -168,8 +168,8 @@ class AbstractPlanningAlgorithm

AbstractPlanningAlgorithm(
const PlannerCommonParam & planner_common_param,
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double margin = 0.0)
: planner_common_param_(planner_common_param), collision_vehicle_shape_(vehicle_info, margin)
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const rclcpp::Clock::SharedPtr & clock, const double margin = 0.0)
: planner_common_param_(planner_common_param), collision_vehicle_shape_(vehicle_info, margin), clock_(clock)
{
planner_common_param_.turning_steps = std::max(planner_common_param_.turning_steps, 1);
collision_vehicle_shape_.max_steering *= planner_common_param_.max_turning_ratio;
Expand Down Expand Up @@ -270,6 +270,9 @@ class AbstractPlanningAlgorithm
PlannerCommonParam planner_common_param_;
VehicleShape collision_vehicle_shape_;

// Pointer to the parent Node
rclcpp::Clock::SharedPtr clock_;

// costmap as occupancy grid
nav_msgs::msg::OccupancyGrid costmap_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,9 @@ class AstarSearch : public AbstractPlanningAlgorithm
const PlannerCommonParam & planner_common_param, const VehicleShape & collision_vehicle_shape,
const AstarParam & astar_param);

AstarSearch(
const PlannerCommonParam & planner_common_param, const VehicleShape & collision_vehicle_shape,
const AstarParam & astar_param, const rclcpp::Clock::SharedPtr & clock);
AstarSearch(
const PlannerCommonParam & planner_common_param, const VehicleShape & collision_vehicle_shape,
rclcpp::Node & node)
Expand All @@ -113,7 +116,8 @@ class AstarSearch : public AbstractPlanningAlgorithm
node.declare_parameter<double>("astar.distance_heuristic_weight"),
node.declare_parameter<double>("astar.smoothness_weight"),
node.declare_parameter<double>("astar.obstacle_distance_weight"),
node.declare_parameter<double>("astar.goal_lat_distance_weight")})
node.declare_parameter<double>("astar.goal_lat_distance_weight")},
node.get_clock())
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class RRTStar : public AbstractPlanningAlgorithm
public:
RRTStar(
const PlannerCommonParam & planner_common_param, const VehicleShape & original_vehicle_shape,
const RRTStarParam & rrtstar_param);
const RRTStarParam & rrtstar_param, const rclcpp::Clock::SharedPtr & clock);

RRTStar(
const PlannerCommonParam & planner_common_param, const VehicleShape & original_vehicle_shape,
Expand All @@ -51,7 +51,8 @@ class RRTStar : public AbstractPlanningAlgorithm
node.declare_parameter<bool>("rrtstar.use_informed_sampling"),
node.declare_parameter<double>("rrtstar.max_planning_time"),
node.declare_parameter<double>("rrtstar.neighbor_radius"),
node.declare_parameter<double>("rrtstar.margin")})
node.declare_parameter<double>("rrtstar.margin")},
node.get_clock())
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,33 @@ Pose calcRelativePose(const Pose & base_pose, const Pose & pose)
AstarSearch::AstarSearch(
const PlannerCommonParam & planner_common_param, const VehicleShape & collision_vehicle_shape,
const AstarParam & astar_param)
: AbstractPlanningAlgorithm(planner_common_param, collision_vehicle_shape),
: AbstractPlanningAlgorithm(planner_common_param, std::make_shared<rclcpp::Clock>(RCL_ROS_TIME), collision_vehicle_shape),
astar_param_(astar_param),
goal_node_(nullptr),
use_reeds_shepp_(true)
{
steering_resolution_ =
collision_vehicle_shape_.max_steering / planner_common_param_.turning_steps;
heading_resolution_ = 2.0 * M_PI / planner_common_param_.theta_size;

const double avg_steering =
steering_resolution_ + (collision_vehicle_shape_.max_steering - steering_resolution_) / 2.0;
avg_turning_radius_ =
kinematic_bicycle_model::getTurningRadius(collision_vehicle_shape_.base_length, avg_steering);

is_backward_search_ = astar_param_.search_method == "backward";

min_expansion_dist_ = astar_param_.expansion_distance;
max_expansion_dist_ = collision_vehicle_shape_.base_length * base_length_max_expansion_factor_;

near_goal_dist_ =
std::max(astar_param.near_goal_distance, planner_common_param.longitudinal_goal_range);
}

AstarSearch::AstarSearch(
const PlannerCommonParam & planner_common_param, const VehicleShape & collision_vehicle_shape,
const AstarParam & astar_param, const rclcpp::Clock::SharedPtr & clock)
: AbstractPlanningAlgorithm(planner_common_param, clock, collision_vehicle_shape),
astar_param_(astar_param),
goal_node_(nullptr),
use_reeds_shepp_(true)
Expand Down Expand Up @@ -404,7 +430,7 @@ double AstarSearch::getLatDistanceCost(const Pose & pose) const
void AstarSearch::setPath(const AstarNode & goal_node)
{
std_msgs::msg::Header header;
header.stamp = rclcpp::Clock(RCL_ROS_TIME).now();
header.stamp = clock_->now();
header.frame_id = costmap_.header.frame_id;

// From the goal node to the start node
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,9 +26,9 @@ rrtstar_core::Pose poseMsgToPose(const geometry_msgs::msg::Pose & pose_msg)

RRTStar::RRTStar(
const PlannerCommonParam & planner_common_param, const VehicleShape & original_vehicle_shape,
const RRTStarParam & rrtstar_param)
const RRTStarParam & rrtstar_param, const rclcpp::Clock::SharedPtr & clock)
: AbstractPlanningAlgorithm(
planner_common_param, VehicleShape(
planner_common_param, clock, VehicleShape(
original_vehicle_shape.length + 2 * rrtstar_param.margin,
original_vehicle_shape.width + 2 * rrtstar_param.margin,
original_vehicle_shape.base_length, original_vehicle_shape.max_steering,
Expand Down Expand Up @@ -130,7 +130,7 @@ bool RRTStar::hasObstacleOnTrajectory(const geometry_msgs::msg::PoseArray & traj
void RRTStar::setRRTPath(const std::vector<rrtstar_core::Pose> & waypoints)
{
std_msgs::msg::Header header;
header.stamp = rclcpp::Clock(RCL_ROS_TIME).now();
header.stamp = clock_->now();
header.frame_id = costmap_.header.frame_id;

waypoints_.header = header;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -231,7 +231,8 @@ std::unique_ptr<fpa::AbstractPlanningAlgorithm> configure_astar(bool use_multi)
obstacle_distance_weight,
goal_lat_distance_weight};

auto algo = std::make_unique<fpa::AstarSearch>(planner_common_param, vehicle_shape, astar_param);
auto clock_shrd_ptr = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
auto algo = std::make_unique<fpa::AstarSearch>(planner_common_param, vehicle_shape, astar_param, clock_shrd_ptr);
return algo;
}

Expand All @@ -244,7 +245,9 @@ std::unique_ptr<fpa::AbstractPlanningAlgorithm> configure_rrtstar(bool informed,
const double margin = 0.2;
const double max_planning_time = 200;
const auto rrtstar_param = fpa::RRTStarParam{update, informed, max_planning_time, mu, margin};
auto algo = std::make_unique<fpa::RRTStar>(planner_common_param, vehicle_shape, rrtstar_param);

auto clock_shrd_ptr = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
auto algo = std::make_unique<fpa::RRTStar>(planner_common_param, vehicle_shape, rrtstar_param, clock_shrd_ptr);
return algo;
}

Expand Down

0 comments on commit 296fd45

Please sign in to comment.