Skip to content

Commit e3b68d5

Browse files
go-sakayorishmpwk
andcommitted
feat(motion_velocity_smoother)!: added force acceleration (#1329)
* add feature for force acceleration Signed-off-by: Go Sakayori <go.sakayori@tier4.jp> * Add log info when force acceleration is activated/deactivated Signed-off-by: Go Sakayori <go.sakayori@tier4.jp> * fix enagage velocity/acceleration Signed-off-by: Go Sakayori <gsakayori@gmail.com> * Update planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp * Update planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp --------- Signed-off-by: Go Sakayori <go.sakayori@tier4.jp> Signed-off-by: Go Sakayori <gsakayori@gmail.com> Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com>
1 parent 0e539d1 commit e3b68d5

File tree

5 files changed

+106
-0
lines changed

5 files changed

+106
-0
lines changed

planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp

+20
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@
4343
#include "autoware_planning_msgs/msg/trajectory_point.hpp"
4444
#include "geometry_msgs/msg/accel_with_covariance_stamped.hpp"
4545
#include "nav_msgs/msg/odometry.hpp"
46+
#include "std_srvs/srv/set_bool.hpp"
4647
#include "tier4_debug_msgs/msg/float32_stamped.hpp" // temporary
4748
#include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" // temporary
4849
#include "tier4_planning_msgs/msg/velocity_limit.hpp" // temporary
@@ -65,6 +66,7 @@ using geometry_msgs::msg::AccelWithCovarianceStamped;
6566
using geometry_msgs::msg::Pose;
6667
using geometry_msgs::msg::PoseStamped;
6768
using nav_msgs::msg::Odometry;
69+
using std_srvs::srv::SetBool;
6870
using tier4_debug_msgs::msg::Float32Stamped; // temporary
6971
using tier4_planning_msgs::msg::StopSpeedExceeded; // temporary
7072
using tier4_planning_msgs::msg::VelocityLimit; // temporary
@@ -97,6 +99,8 @@ class VelocitySmootherNode : public rclcpp::Node
9799
sub_external_velocity_limit_{this, "~/input/external_velocity_limit_mps"};
98100
autoware::universe_utils::InterProcessPollingSubscriber<OperationModeState> sub_operation_mode_{
99101
this, "~/input/operation_mode_state"};
102+
rclcpp::Service<SetBool>::SharedPtr srv_force_acceleration_;
103+
rclcpp::Service<SetBool>::SharedPtr srv_slow_driving_;
100104

101105
Odometry::ConstSharedPtr current_odometry_ptr_; // current odometry
102106
AccelWithCovarianceStamped::ConstSharedPtr current_acceleration_ptr_;
@@ -134,6 +138,15 @@ class VelocitySmootherNode : public rclcpp::Node
134138
NORMAL = 3,
135139
};
136140

141+
struct ForceAccelerationParam
142+
{
143+
double max_acceleration;
144+
double max_jerk;
145+
double max_lateral_acceleration;
146+
double engage_velocity;
147+
double engage_acceleration;
148+
};
149+
137150
struct Param
138151
{
139152
bool enable_lateral_acc_limit;
@@ -159,6 +172,8 @@ class VelocitySmootherNode : public rclcpp::Node
159172
AlgorithmType algorithm_type; // Option : JerkFiltered, Linf, L2
160173

161174
bool plan_from_ego_speed_on_manual_mode = true;
175+
176+
ForceAccelerationParam force_acceleration_param;
162177
} node_param_{};
163178

164179
struct ExternalVelocityLimit
@@ -244,6 +259,11 @@ class VelocitySmootherNode : public rclcpp::Node
244259

245260
// parameter handling
246261
void initCommonParam();
262+
void onForceAcceleration(
263+
const std::shared_ptr<SetBool::Request> request, std::shared_ptr<SetBool::Response> response);
264+
bool force_acceleration_mode_;
265+
void onSlowDriving(
266+
const std::shared_ptr<SetBool::Request> request, std::shared_ptr<SetBool::Response> response);
247267

248268
// debug
249269
autoware::universe_utils::StopWatch<std::chrono::milliseconds> stop_watch_;

planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -82,6 +82,9 @@ class SmootherBase
8282
double getMinJerk() const;
8383

8484
void setWheelBase(const double wheel_base);
85+
void setMaxAccel(const double max_accel);
86+
void setMaxJerk(const double max_jerk);
87+
void setMaxLatAccel(const double max_accel);
8588

8689
void setParam(const BaseParam & param);
8790
BaseParam getBaseParam() const;

planning/autoware_velocity_smoother/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030
<depend>nav_msgs</depend>
3131
<depend>osqp_interface</depend>
3232
<depend>rclcpp</depend>
33+
<depend>std_srvs</depend>
3334
<depend>tf2</depend>
3435
<depend>tf2_ros</depend>
3536
<depend>tier4_debug_msgs</depend>

planning/autoware_velocity_smoother/src/node.cpp

+67
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,7 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti
3838
: Node("velocity_smoother", node_options)
3939
{
4040
using std::placeholders::_1;
41+
using std::placeholders::_2;
4142

4243
// set common params
4344
const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo();
@@ -66,6 +67,13 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti
6667
sub_current_trajectory_ = create_subscription<Trajectory>(
6768
"~/input/trajectory", 1, std::bind(&VelocitySmootherNode::onCurrentTrajectory, this, _1));
6869

70+
srv_force_acceleration_ = create_service<SetBool>(
71+
"~/adjust_common_param",
72+
std::bind(&MotionVelocitySmootherNode::onForceAcceleration, this, _1, _2));
73+
srv_slow_driving_ = create_service<SetBool>(
74+
"~/slow_driving", std::bind(&MotionVelocitySmootherNode::onSlowDriving, this, _1, _2));
75+
force_acceleration_mode_ = false;
76+
6977
// parameter update
7078
set_param_res_ =
7179
this->add_on_set_parameters_callback(std::bind(&VelocitySmootherNode::onParameter, this, _1));
@@ -184,6 +192,14 @@ rcl_interfaces::msg::SetParametersResult VelocitySmootherNode::onParameter(
184192
update_param("ego_nearest_dist_threshold", p.ego_nearest_dist_threshold);
185193
update_param("ego_nearest_yaw_threshold", p.ego_nearest_yaw_threshold);
186194
update_param_bool("plan_from_ego_speed_on_manual_mode", p.plan_from_ego_speed_on_manual_mode);
195+
196+
update_param("force_acceleration.max_acc", p.force_acceleration_param.max_acceleration);
197+
update_param("force_acceleration.max_jerk", p.force_acceleration_param.max_jerk);
198+
update_param(
199+
"force_acceleration.max_lateral_acc", p.force_acceleration_param.max_lateral_acceleration);
200+
update_param("force_acceleration.engage_velocity", p.force_acceleration_param.engage_velocity);
201+
update_param(
202+
"force_acceleration.engage_acceleration", p.force_acceleration_param.engage_acceleration);
187203
}
188204

189205
{
@@ -303,6 +319,16 @@ void VelocitySmootherNode::initCommonParam()
303319

304320
p.plan_from_ego_speed_on_manual_mode =
305321
declare_parameter<bool>("plan_from_ego_speed_on_manual_mode");
322+
323+
p.force_acceleration_param.max_acceleration =
324+
declare_parameter<double>("force_acceleration.max_acc");
325+
p.force_acceleration_param.max_jerk = declare_parameter<double>("force_acceleration.max_jerk");
326+
p.force_acceleration_param.max_lateral_acceleration =
327+
declare_parameter<double>("force_acceleration.max_lateral_acc");
328+
p.force_acceleration_param.engage_velocity =
329+
declare_parameter<double>("force_acceleration.engage_velocity");
330+
p.force_acceleration_param.engage_acceleration =
331+
declare_parameter<double>("force_acceleration.engage_acceleration");
306332
}
307333

308334
void VelocitySmootherNode::publishTrajectory(const TrajectoryPoints & trajectory) const
@@ -1116,6 +1142,47 @@ TrajectoryPoint VelocitySmootherNode::calcProjectedTrajectoryPointFromEgo(
11161142
return calcProjectedTrajectoryPoint(trajectory, current_odometry_ptr_->pose.pose);
11171143
}
11181144

1145+
void MotionVelocitySmootherNode::onForceAcceleration(
1146+
const std::shared_ptr<SetBool::Request> request, std::shared_ptr<SetBool::Response> response)
1147+
{
1148+
std::string message = "default";
1149+
1150+
if (request->data && !force_acceleration_mode_) {
1151+
RCLCPP_INFO(get_logger(), "Force acceleration is activated");
1152+
smoother_->setMaxAccel(get_parameter("force_acceleration.max_acc").as_double());
1153+
smoother_->setMaxJerk(get_parameter("force_acceleration.max_jerk").as_double());
1154+
smoother_->setMaxLatAccel(get_parameter("force_acceleration.max_lateral_acc").as_double());
1155+
node_param_.engage_velocity = get_parameter("force_acceleration.engage_velocity").as_double();
1156+
node_param_.engage_acceleration =
1157+
get_parameter("force_acceleration.engage_acceleration").as_double();
1158+
1159+
force_acceleration_mode_ = true;
1160+
message = "Trigger force acceleration";
1161+
} else if (!request->data && force_acceleration_mode_) {
1162+
RCLCPP_INFO(get_logger(), "Force acceleration is deactivated");
1163+
smoother_->setMaxAccel(get_parameter("normal.max_acc").as_double());
1164+
smoother_->setMaxJerk(get_parameter("normal.max_jerk").as_double());
1165+
smoother_->setMaxLatAccel(get_parameter("max_lateral_accel").as_double());
1166+
1167+
node_param_.engage_velocity = get_parameter("engage_velocity").as_double();
1168+
node_param_.engage_acceleration = get_parameter("engage_acceleration").as_double();
1169+
1170+
force_acceleration_mode_ = false;
1171+
message = "Trigger normal acceleration";
1172+
}
1173+
1174+
response->success = true;
1175+
}
1176+
1177+
void MotionVelocitySmootherNode::onSlowDriving(
1178+
const std::shared_ptr<SetBool::Request> request, std::shared_ptr<SetBool::Response> response)
1179+
{
1180+
const std::string message = request->data ? "Slow driving" : "Default";
1181+
1182+
response->success = true;
1183+
response->message = message;
1184+
}
1185+
11191186
} // namespace autoware::velocity_smoother
11201187

11211188
#include "rclcpp_components/register_node_macro.hpp"

planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp

+15
Original file line numberDiff line numberDiff line change
@@ -97,6 +97,21 @@ void SmootherBase::setWheelBase(const double wheel_base)
9797
base_param_.wheel_base = wheel_base;
9898
}
9999

100+
void SmootherBase::setMaxAccel(const double max_accel)
101+
{
102+
base_param_.max_accel = max_accel;
103+
}
104+
105+
void SmootherBase::setMaxJerk(const double max_jerk)
106+
{
107+
base_param_.max_jerk = max_jerk;
108+
}
109+
110+
void SmootherBase::setMaxLatAccel(const double max_accel)
111+
{
112+
base_param_.max_lateral_accel = max_accel;
113+
}
114+
100115
void SmootherBase::setParam(const BaseParam & param)
101116
{
102117
base_param_ = param;

0 commit comments

Comments
 (0)