Skip to content

Commit

Permalink
feat(obstacle_cruies_planner): improve pid_based cruise planner (#2507)
Browse files Browse the repository at this point in the history
* feat(obstacle_cruies_planner): improve pid_based cruise planner

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

* fix

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

* update param in tier4_planning_launch

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
  • Loading branch information
takayuki5168 authored Dec 18, 2022
1 parent fc1d820 commit 9ecc3a2
Show file tree
Hide file tree
Showing 12 changed files with 939 additions and 222 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,18 @@
common:
planning_algorithm: "pid_base" # currently supported algorithm is "pid_base"

is_showing_debug_info: true
is_showing_debug_info: false
disable_stop_planning: false # true

# longitudinal info
idling_time: 1.5 # idling time to detect front vehicle starting deceleration [s]
idling_time: 2.0 # idling time to detect front vehicle starting deceleration [s]
min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss]
min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss]
safe_distance_margin : 6.0 # This is also used as a stop margin [m]
terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m]

lpf_gain_for_accel: 0.2 # gain of low pass filter for ego acceleration [-]

nearest_dist_deviation_threshold: 3.0 # [m] for finding nearest index
nearest_yaw_deviation_threshold: 1.57 # [rad] for finding nearest index
min_behavior_stop_margin: 3.0 # [m]
Expand All @@ -25,7 +28,7 @@
bus: true
trailer: true
motorcycle: true
bicycle: false
bicycle: true
pedestrian: false

stop_obstacle_type:
Expand Down Expand Up @@ -62,7 +65,7 @@
stop_obstacle_hold_time_threshold : 1.0 # maximum time for holding closest stop obstacle

ignored_outside_obstacle_type:
unknown: false
unknown: true
car: false
truck: false
bus: false
Expand All @@ -72,21 +75,41 @@
pedestrian: true

pid_based_planner:
# use_predicted_obstacle_pose: false
use_velocity_limit_based_planner: true
error_function_type: quadratic # choose from linear, quadratic

# PID gains to keep safe distance with the front vehicle
kp: 2.5
ki: 0.0
kd: 2.3
velocity_limit_based_planner:
# PID gains to keep safe distance with the front vehicle
kp: 10.0
ki: 0.0
kd: 2.0

min_accel_during_cruise: -2.0 # minimum acceleration during cruise to slow down [m/ss]
output_ratio_during_accel: 0.6 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-]
vel_to_acc_weight: 12.0 # target acceleration is calculated by (target_velocity - current_velocity) * vel_to_acc_weight [-]

enable_jerk_limit_to_output_acc: false

output_ratio_during_accel: 0.6 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-]
vel_to_acc_weight: 3.0 # target acceleration is calculated by (target_velocity - current_velocity) * vel_to_acc_weight [-]
disable_target_acceleration: true

velocity_insertion_based_planner:
kp_acc: 6.0
ki_acc: 0.0
kd_acc: 2.0

kp_jerk: 20.0
ki_jerk: 0.0
kd_jerk: 0.0

output_acc_ratio_during_accel: 0.6 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-]
output_jerk_ratio_during_accel: 1.0 # target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-]

enable_jerk_limit_to_output_acc: true

min_accel_during_cruise: -2.0 # minimum acceleration during cruise to slow down [m/ss]
min_cruise_target_vel: 0.0 # minimum target velocity during slow down [m/s]
time_to_evaluate_rss: 0.0

lpf_cruise_gain: 0.2
lpf_normalized_error_cruise_dist_gain: 0.2

optimization_based_planner:
dense_resampling_time_interval: 0.2
Expand Down
10 changes: 5 additions & 5 deletions planning/obstacle_cruise_planner/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -56,15 +56,15 @@ struct ObstacleCruisePlannerData
struct TargetObstacle
{
rclcpp::Time time_stamp;
bool orientation_reliable;
geometry_msgs::msg::Pose pose;
bool orientation_reliable;
double velocity;
bool velocity_reliable;
float velocity;
bool is_classified;
ObjectClassification classification;
Shape shape;
std::string uuid;
std::vector<PredictedPath> predicted_paths;
geometry_msgs::msg::Point collision_point;
std::vector<geometry_msgs::msg::PointStamped> collision_points;
bool has_stopped;
};
```

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,17 +10,17 @@
<plot flip_y="false" mode="TimeSeries" flip_x="false" style="Lines">
<range bottom="-68.642152" left="1648801093.897904" right="1648801193.801909" top="94.063676"/>
<limitY/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.10" color="#1ac938"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.12" color="#17becf"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.16" color="#d62728"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.10" color="#1ac938"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.12" color="#17becf"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.16" color="#d62728"/>
</plot>
</DockArea>
<DockArea name="...">
<plot flip_y="false" mode="TimeSeries" flip_x="false" style="Lines">
<range bottom="-1.341975" left="1648801093.897904" right="1648801193.801909" top="1.170411"/>
<limitY/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.1" color="#f14cc1"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.14" color="#1f77b4"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.1" color="#f14cc1"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.14" color="#1f77b4"/>
</plot>
</DockArea>
</DockSplitter>
Expand All @@ -29,17 +29,17 @@
<plot flip_y="false" mode="TimeSeries" flip_x="false" style="Lines">
<range bottom="-0.293676" left="1648801093.897904" right="1648801193.801909" top="12.040726"/>
<limitY/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.0" color="#ff7f0e"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.11" color="#9467bd"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.13" color="#bcbd22"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.0" color="#ff7f0e"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.11" color="#9467bd"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.13" color="#bcbd22"/>
</plot>
</DockArea>
<DockArea name="...">
<plot flip_y="false" mode="TimeSeries" flip_x="false" style="Lines">
<range bottom="-0.100000" left="1648801093.897904" right="1648801193.801909" top="0.100000"/>
<limitY/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.15" color="#1ac938"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.2" color="#ff7f0e"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.15" color="#1ac938"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.2" color="#ff7f0e"/>
</plot>
</DockArea>
</DockSplitter>
Expand All @@ -56,17 +56,17 @@
<plot flip_y="false" mode="TimeSeries" flip_x="false" style="Lines">
<range bottom="-4.440820" left="1648801040.096838" right="1648801140.095224" top="182.073633"/>
<limitY/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.3" color="#17becf"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.5" color="#1f77b4"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.9" color="#d62728"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.3" color="#17becf"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.5" color="#1f77b4"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.9" color="#d62728"/>
</plot>
</DockArea>
<DockArea name="...">
<plot flip_y="false" mode="TimeSeries" flip_x="false" style="Lines">
<range bottom="-1.411967" left="1648801040.096838" right="1648801140.095224" top="1.117231"/>
<limitY/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.1" color="#f14cc1"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.7" color="#1ac938"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.1" color="#f14cc1"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.7" color="#1ac938"/>
</plot>
</DockArea>
</DockSplitter>
Expand All @@ -75,9 +75,9 @@
<plot flip_y="false" mode="TimeSeries" flip_x="false" style="Lines">
<range bottom="-0.364903" left="1648801040.096838" right="1648801140.095224" top="12.034235"/>
<limitY/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.0" color="#ff7f0e"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.4" color="#bcbd22"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/values/data.6" color="#d62728"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.0" color="#ff7f0e"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.4" color="#bcbd22"/>
<curve name="/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/stop_planning_debug_info/data.6" color="#d62728"/>
</plot>
</DockArea>
<DockArea name="...">
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,6 @@ struct TargetObstacle
pose = object.kinematics.initial_pose_with_covariance.pose;
velocity_reliable = true;
velocity = aligned_velocity;
is_classified = true;
classification = object.classification.at(0);
uuid = toHexString(object.object_id);

Expand All @@ -72,11 +71,10 @@ struct TargetObstacle
}

rclcpp::Time time_stamp;
bool orientation_reliable;
geometry_msgs::msg::Pose pose;
bool orientation_reliable;
double velocity;
bool velocity_reliable;
float velocity;
bool is_classified;
ObjectClassification classification;
std::string uuid;
std::vector<PredictedPath> predicted_paths;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,8 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
const PredictedObject & predicted_object, const Trajectory & traj,
const bool is_driving_forward);
void publishVelocityLimit(const boost::optional<VelocityLimit> & vel_limit);
void publishDebugData(const DebugData & debug_data) const;
void publishDebugMarker(const DebugData & debug_data) const;
void publishDebugInfo() const;
void publishCalculationTime(const double calculation_time) const;

bool isCruiseObstacle(const uint8_t label);
Expand Down Expand Up @@ -128,6 +129,8 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr debug_marker_pub_;
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr debug_cruise_wall_marker_pub_;
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr debug_stop_wall_marker_pub_;
rclcpp::Publisher<Float32MultiArrayStamped>::SharedPtr debug_stop_planning_info_pub_;
rclcpp::Publisher<Float32MultiArrayStamped>::SharedPtr debug_cruise_planning_info_pub_;
rclcpp::Publisher<Float32Stamped>::SharedPtr debug_calculation_time_pub_;

// subscriber
Expand All @@ -141,10 +144,9 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
tier4_autoware_utils::SelfPoseListener self_pose_listener_;

// data for callback functions
PredictedObjects::ConstSharedPtr in_objects_ptr_;
geometry_msgs::msg::TwistStamped::SharedPtr current_twist_ptr_;

geometry_msgs::msg::AccelStamped::SharedPtr current_accel_ptr_;
PredictedObjects::ConstSharedPtr in_objects_ptr_{nullptr};
geometry_msgs::msg::TwistStamped::SharedPtr current_twist_ptr_{nullptr};
geometry_msgs::msg::AccelStamped::SharedPtr current_accel_ptr_{nullptr};

// Vehicle Parameters
VehicleInfo vehicle_info_;
Expand All @@ -160,7 +162,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
stop_watch_;

// planner
std::unique_ptr<PlannerInterface> planner_ptr_;
std::unique_ptr<PlannerInterface> planner_ptr_{nullptr};

// previous closest obstacle
std::shared_ptr<TargetObstacle> prev_closest_obstacle_ptr_{nullptr};
Expand Down Expand Up @@ -195,8 +197,11 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
bool need_to_clear_vel_limit_{false};

bool is_driving_forward_{true};
bool disable_stop_planning_{false};

std::vector<TargetObstacle> prev_target_obstacles_;

std::shared_ptr<LowpassFilter1d> lpf_acc_ptr_;
};
} // namespace motion_planning

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
// Copyright 2022 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
#define OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_

#include <rclcpp/rclcpp.hpp>

#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp"

#include <array>

using tier4_debug_msgs::msg::Float32MultiArrayStamped;

class CruisePlanningDebugInfo
{
public:
enum class TYPE {
// ego
EGO_VELOCITY = 0, // index: 0
EGO_ACCELERATION,
EGO_JERK, // no data

// cruise planning
CRUISE_CURRENT_OBSTACLE_DISTANCE_RAW, // index: 3
CRUISE_CURRENT_OBSTACLE_DISTANCE_FILTERED,
CRUISE_CURRENT_OBSTACLE_VELOCITY_RAW,
CRUISE_CURRENT_OBSTACLE_VELOCITY_FILTERED,
CRUISE_TARGET_OBSTACLE_DISTANCE,
CRUISE_ERROR_DISTANCE_RAW,
CRUISE_ERROR_DISTANCE_FILTERED,

CRUISE_RELATIVE_EGO_VELOCITY, // index: 10
CRUISE_TIME_TO_COLLISION,

CRUISE_TARGET_VELOCITY, // index: 12
CRUISE_TARGET_ACCELERATION,
CRUISE_TARGET_JERK_RATIO,

SIZE
};

/**
* @brief get the index corresponding to the given value TYPE
* @param [in] type the TYPE enum for which to get the index
* @return index of the type
*/
int getIndex(const TYPE type) const { return static_cast<int>(type); }

/**
* @brief get all the debug values as an std::array
* @return array of all debug values
*/
std::array<double, static_cast<int>(TYPE::SIZE)> get() const { return info_; }

/**
* @brief set the given type to the given value
* @param [in] type TYPE of the value
* @param [in] value value to set
*/
void set(const TYPE type, const double val) { info_.at(static_cast<int>(type)) = val; }

/**
* @brief set the given type to the given value
* @param [in] type index of the type
* @param [in] value value to set
*/
void set(const int type, const double val) { info_.at(type) = val; }

void reset() { info_.fill(0.0); }

Float32MultiArrayStamped convertToMessage(const rclcpp::Time & current_time) const
{
Float32MultiArrayStamped msg{};
msg.stamp = current_time;
for (const auto & v : get()) {
msg.data.push_back(v);
}
return msg;
}

private:
std::array<double, static_cast<int>(TYPE::SIZE)> info_;
};

#endif // OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
Loading

0 comments on commit 9ecc3a2

Please sign in to comment.