Skip to content

Commit

Permalink
feat(behavior_velocity_planner_common): add node clock, use sim time …
Browse files Browse the repository at this point in the history
…in isVehicleStopped()
  • Loading branch information
dmoszynski committed Aug 16, 2024
1 parent d54286f commit 682f1cf
Showing 1 changed file with 5 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,8 @@ class BehaviorVelocityPlannerNode;
struct PlannerData
{
explicit PlannerData(rclcpp::Node & node)
: vehicle_info_(vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo())
: clock_(node.get_clock()),
vehicle_info_(vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo())
{
max_stop_acceleration_threshold = node.declare_parameter<double>(
"max_accel"); // TODO(someone): read min_acc in velocity_controller.param.yaml?
Expand All @@ -60,6 +61,8 @@ struct PlannerData
delay_response_time = node.declare_parameter<double>("delay_response_time");
}

rclcpp::Clock::SharedPtr clock_;

// msgs from callbacks that are used for data-ready
geometry_msgs::msg::PoseStamped::ConstSharedPtr current_odometry;
geometry_msgs::msg::TwistStamped::ConstSharedPtr current_velocity;
Expand Down Expand Up @@ -108,7 +111,7 @@ struct PlannerData
}

// Get velocities within stop_duration
const auto now = rclcpp::Clock{RCL_ROS_TIME}.now();
const auto now = clock_->now();
std::vector<double> vs;
for (const auto & velocity : velocity_buffer) {
vs.push_back(velocity.twist.linear.x);
Expand Down

0 comments on commit 682f1cf

Please sign in to comment.