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

feat(pid_longitudinal_controller): add virtual wall for dry steering and emergency #9685

Merged
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 @@ -50,11 +50,8 @@

namespace autoware::motion::control::pid_longitudinal_controller
{
using autoware::universe_utils::createDefaultMarker;
using autoware::universe_utils::createMarkerColor;
using autoware::universe_utils::createMarkerScale;
using autoware_adapi_v1_msgs::msg::OperationModeState;
using visualization_msgs::msg::Marker;
using visualization_msgs::msg::MarkerArray;

namespace trajectory_follower = ::autoware::motion::control::trajectory_follower;

Expand Down Expand Up @@ -104,7 +101,7 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
// ros variables
rclcpp::Publisher<tier4_debug_msgs::msg::Float32MultiArrayStamped>::SharedPtr m_pub_slope;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32MultiArrayStamped>::SharedPtr m_pub_debug;
rclcpp::Publisher<Marker>::SharedPtr m_pub_stop_reason_marker;
rclcpp::Publisher<MarkerArray>::SharedPtr m_pub_virtual_wall_marker;

rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr m_set_param_res;
rcl_interfaces::msg::SetParametersResult paramCallback(
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc. All rights reserved.

Check notice on line 1 in control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 4.63 to 4.67, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -14,6 +14,7 @@

#include "autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp"

#include "autoware/motion_utils/marker/marker_helper.hpp"
#include "autoware/motion_utils/trajectory/trajectory.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "autoware/universe_utils/math/normalization.hpp"
Expand Down Expand Up @@ -219,7 +220,7 @@
"~/output/slope_angle", rclcpp::QoS{1});
m_pub_debug = node.create_publisher<tier4_debug_msgs::msg::Float32MultiArrayStamped>(
"~/output/longitudinal_diagnostic", rclcpp::QoS{1});
m_pub_stop_reason_marker = node.create_publisher<Marker>("~/output/stop_reason", rclcpp::QoS{1});
m_pub_virtual_wall_marker = node.create_publisher<MarkerArray>("~/virtual_wall", 1);

// set parameter callback
m_set_param_res = node.add_on_set_parameters_callback(
Expand Down Expand Up @@ -562,8 +563,8 @@

// distance to stopline
control_data.stop_dist = longitudinal_utils::calcStopDistance(
control_data.interpolated_traj.points.at(control_data.nearest_idx).pose,
control_data.interpolated_traj, m_ego_nearest_dist_threshold, m_ego_nearest_yaw_threshold);
current_pose, control_data.interpolated_traj, m_ego_nearest_dist_threshold,
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This change using current_pose is necessary to calculate the negative distance when the ego exceeds the stop point so that the pid_longitudinal_controller will be in an emergency.

Is this okay for you considering the following PR where you replaced current_pose with control_data.interpolated_traj.points.at(control_data.nearest_idx).pose?
#4712

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@brkay54
I will merge now, but let me know anytime if the change does not look good to you.

m_ego_nearest_yaw_threshold);

// pitch
// NOTE: getPitchByTraj() calculates the pitch angle as defined in
Expand Down Expand Up @@ -617,6 +618,11 @@
longitudinal_utils::applyDiffLimitFilter(raw_ctrl_cmd.acc, m_prev_raw_ctrl_cmd.acc, dt, p.jerk);
m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_JERK_LIMITED, raw_ctrl_cmd.acc);

const auto virtual_wall_marker = autoware::motion_utils::createStopVirtualWallMarker(
m_current_kinematic_state.pose.pose, "velocity control\n (emergency)", clock_->now(), 0,
m_wheel_base + m_front_overhang);
m_pub_virtual_wall_marker->publish(virtual_wall_marker);

return raw_ctrl_cmd;
}

Expand Down Expand Up @@ -781,14 +787,12 @@
}

// publish debug marker
auto marker = createDefaultMarker(
"map", clock_->now(), "stop_reason", 0, Marker::TEXT_VIEW_FACING,
createMarkerScale(0.0, 0.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999));
marker.pose = autoware::universe_utils::calcOffsetPose(
m_current_kinematic_state.pose.pose, m_wheel_base + m_front_overhang,
m_vehicle_width / 2 + 2.0, 1.5);
marker.text = "steering not\nconverged";
m_pub_stop_reason_marker->publish(marker);
if (is_under_control) {
const auto virtual_wall_marker = autoware::motion_utils::createStopVirtualWallMarker(
m_current_kinematic_state.pose.pose, "velocity control\n(steering not converged)",

Check warning on line 792 in control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

View check run for this annotation

Codecov / codecov/patch

control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp#L792

Added line #L792 was not covered by tests
clock_->now(), 0, m_wheel_base + m_front_overhang);
m_pub_virtual_wall_marker->publish(virtual_wall_marker);
}

Check warning on line 795 in control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

PidLongitudinalController::updateControlState increases in cyclomatic complexity from 41 to 42, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

// keep STOPPED
return;
Expand Down
Loading