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

chore: sync upstream #302

Merged
merged 1 commit into from
Mar 5, 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
Original file line number Diff line number Diff line change
Expand Up @@ -924,7 +924,7 @@ double PidLongitudinalController::applyVelocityFeedback(
m_pid_vel.calculate(error_vel_filtered, dt, enable_integration, pid_contributions);

// Feedforward scaling:
// This is for the coordinate convertion where feedforward is applied, from Time to Arclength.
// This is for the coordinate conversion where feedforward is applied, from Time to Arclength.
// Details: For accurate control, the feedforward should be calculated in the arclength coordinate
// system, not in the time coordinate system. Otherwise, even if FF is applied, the vehicle speed
// deviation will be bigger.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ BigVehicleTracker::BigVehicleTracker(
object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z};
last_input_bounding_box_ = bounding_box_;
} else {
// past defalut value
// past default value
// bounding_box_ = {7.0, 2.0, 2.0};
autoware_auto_perception_msgs::msg::DetectedObject bbox_object;
utils::convertConvexHullToBoundingBox(object, bbox_object);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
use_stuck_stopline: false # stopline generate before the intersection lanelet when is_stuck
assumed_front_car_decel: 1.0 # [m/ss] the expected deceleration of front car when front car as well as ego are turning
enable_front_car_decel_prediction: false # By default this feature is disabled
stop_overshoot_margin: 0.5 # [m] overshoot margin for stuck, collsion detection
stop_overshoot_margin: 0.5 # [m] overshoot margin for stuck, collision detection

merge_from_private_road:
stop_duration_sec: 1.0
Original file line number Diff line number Diff line change
Expand Up @@ -86,14 +86,14 @@ class IntersectionModule : public SceneModuleInterface
double min_predicted_path_confidence;
//! minimum confidence value of predicted path to use for collision detection
double external_input_timeout; //! used to disable external input
double minimum_ego_predicted_velocity; //! used to calclate ego's future velocity profile
double minimum_ego_predicted_velocity; //! used to calculate ego's future velocity profile
double collision_start_margin_time; //! start margin time to check collision
double collision_end_margin_time; //! end margin time to check collision
bool use_stuck_stopline; //! stopline generate before the intersection lanelet when is_stuck.
double
assumed_front_car_decel; //! the expected deceleration of front car when front car as well
bool enable_front_car_decel_prediction; //! flag for using above feature
double stop_overshoot_margin; //! overshoot margin for stuck, collsion detection
double stop_overshoot_margin; //! overshoot margin for stuck, collision detection
};

IntersectionModule(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -295,7 +295,7 @@ boost::optional<geometry_msgs::msg::Pose> insertStopPoint(
const geometry_msgs::msg::Point & stop_point, const size_t stop_seg_idx, PathWithLaneId & output);

/*
@brief return 'associatvie' lanes in the intersection. 'associative' means that a lane shares same
@brief return 'associative' lanes in the intersection. 'associative' means that a lane shares same
or lane-changeable parent lanes with `lane` and has same turn_direction value.
*/
std::set<int> getAssociativeIntersectionLanelets(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -296,13 +296,13 @@ class AccelBrakeMapCalibrator : public rclcpp::Node
bool isTimeout(const DataStampedPtr & data_stamped, const double timeout_sec);

/* for covariance calculation */
// mean value on each cell (counting methoud depends on the update algorithm)
// mean value on each cell (counting method depends on the update algorithm)
Eigen::MatrixXd accel_data_mean_mat_;
Eigen::MatrixXd brake_data_mean_mat_;
// calculated vairiance on each cell
// calculated variance on each cell
Eigen::MatrixXd accel_data_covariance_mat_;
Eigen::MatrixXd brake_data_covariance_mat_;
// number of data on each cell (counting methoud depends on the update algorithm)
// number of data on each cell (counting method depends on the update algorithm)
Eigen::MatrixXd accel_data_num_;
Eigen::MatrixXd brake_data_num_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -155,7 +155,7 @@ AccelBrakeMapCalibrator::AccelBrakeMapCalibrator(const rclcpp::NodeOptions & nod
std::copy(accel_map_value_.begin(), accel_map_value_.end(), update_accel_map_value_.begin());
std::copy(brake_map_value_.begin(), brake_map_value_.end(), update_brake_map_value_.begin());

// inialize matrix for covariance calculation
// initialize matrix for covariance calculation
{
const auto genConstMat = [](const Map & map, const auto val) {
return Eigen::MatrixXd::Constant(map.size(), map.at(0).size(), val);
Expand Down