Skip to content

Commit

Permalink
feat: use vehicle_stop_checker for judging vehicle stop vehicle_cmd_g…
Browse files Browse the repository at this point in the history
…ate (autowarefoundation#4060)

* feat: use vehicle_stop_checker for  judging vehicle stop vehicle_cmd_gate

Signed-off-by: tomoya.kimura <[email protected]>

* remove unused include

Signed-off-by: tomoya.kimura <[email protected]>

---------

Signed-off-by: tomoya.kimura <[email protected]>
  • Loading branch information
tkimura4 authored and mkuri committed Jul 27, 2023
1 parent 014a92c commit 6f4abd4
Show file tree
Hide file tree
Showing 4 changed files with 13 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
emergency_acceleration: -2.4
moderate_stop_service_acceleration: -1.5
stopped_state_entry_duration_time: 0.1
stop_check_duration: 1.0
nominal:
vel_lim: 25.0
lon_acc_lim: 5.0
Expand Down
1 change: 1 addition & 0 deletions control/vehicle_cmd_gate/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
<depend>component_interface_utils</depend>
<depend>diagnostic_updater</depend>
<depend>geometry_msgs</depend>
<depend>motion_utils</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>std_srvs</depend>
Expand Down
6 changes: 5 additions & 1 deletion control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,9 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options)
rclcpp::QoS durable_qos{1};
durable_qos.transient_local();

// Stop Checker
vehicle_stop_checker_ = std::make_unique<VehicleStopChecker>(this);

// Publisher
vehicle_cmd_emergency_pub_ =
create_publisher<VehicleEmergencyStamped>("output/vehicle_cmd_emergency", durable_qos);
Expand Down Expand Up @@ -145,6 +148,7 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options)
emergency_acceleration_ = declare_parameter<double>("emergency_acceleration");
moderate_stop_service_acceleration_ =
declare_parameter<double>("moderate_stop_service_acceleration");
stop_check_duration_ = declare_parameter<double>("stop_check_duration");

// Vehicle Parameter
const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo();
Expand Down Expand Up @@ -492,7 +496,7 @@ AckermannControlCommand VehicleCmdGate::filterControlCommand(const AckermannCont
const double dt = getDt();
const auto mode = current_operation_mode_;
const auto current_status_cmd = getActualStatusAsCommand();
const auto ego_is_stopped = std::abs(current_status_cmd.longitudinal.speed) < 1e-3;
const auto ego_is_stopped = vehicle_stop_checker_->isVehicleStopped(stop_check_duration_);
const auto input_cmd_is_stopping = in.longitudinal.acceleration < 0.0;

// Apply transition_filter when transiting from MANUAL to AUTO.
Expand Down
6 changes: 6 additions & 0 deletions control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "vehicle_cmd_filter.hpp"

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <motion_utils/motion_utils.hpp>
#include <rclcpp/rclcpp.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

Expand Down Expand Up @@ -70,6 +71,7 @@ using nav_msgs::msg::Odometry;
using EngageMsg = autoware_auto_vehicle_msgs::msg::Engage;
using EngageSrv = tier4_external_api_msgs::srv::Engage;

using motion_utils::VehicleStopChecker;
struct Commands
{
AckermannControlCommand control;
Expand Down Expand Up @@ -219,6 +221,10 @@ class VehicleCmdGate : public rclcpp::Node
// Pause interface for API
std::unique_ptr<AdapiPauseInterface> adapi_pause_;
std::unique_ptr<ModerateStopInterface> moderate_stop_interface_;

// stop checker
std::unique_ptr<VehicleStopChecker> vehicle_stop_checker_;
double stop_check_duration_;
};

} // namespace vehicle_cmd_gate
Expand Down

0 comments on commit 6f4abd4

Please sign in to comment.