Skip to content

Commit 9a46b63

Browse files
committed
Update mppi_controller.param.yaml and control.launch.xml
1 parent de5e51b commit 9a46b63

File tree

5 files changed

+42
-26
lines changed

5 files changed

+42
-26
lines changed

aichallenge/workspace/src/aichallenge_submit/booars_launch/config/planning/mppi_controller.param.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
ros__parameters:
33
# mppi
44
horizon : 25
5-
num_samples : 5000
5+
num_samples : 2500
66
u_min : [-4.0, -0.25] # accel(m/s2), steer angle(rad)
77
u_max : [2.0, 0.25]
88
sigmas : [2.0, 0.25] # sample range

aichallenge/workspace/src/aichallenge_submit/booars_launch/launch/components/control.launch.xml

Lines changed: 16 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -10,20 +10,23 @@
1010
<let name="steering_tire_angle_gain_var" value="1.0" if="$(var simulation)" />
1111
<let name="steering_tire_angle_gain_var" value="1.639" unless="$(var simulation)" />
1212

13-
<!-- <node pkg="simple_pure_pursuit" exec="simple_pure_pursuit" name="simple_pure_pursuit_node"
13+
<node pkg="simple_pure_pursuit" exec="simple_pure_pursuit" name="simple_pure_pursuit_node"
1414
output="screen" unless="$(var use_stanley)">
1515
<param name="use_external_target_vel" value="false" />
1616
<param name="external_target_vel" value="8.3" />
17-
<param name="lookahead_gain" value="0.24" />
18-
<param name="lookahead_min_distance" value="2.0" />
19-
<param name="speed_proportional_gain" value="2.0" />
17+
<param name="lookahead_gain" value="0.25" />
18+
<param name="lookahead_min_distance" value="1.6" />
19+
<param name="speed_proportional_gain" value="3.0" />
2020
<param name="steering_tire_angle_gain" value="$(var steering_tire_angle_gain_var)"/>
21-
21+
<param name="curve_param_max_steer_angle" value="0.1" />
22+
<param name="curve_param_deceleration_vel" value="4.0" />
2223
<remap from="input/kinematics" to="/localization/kinematic_state" />
23-
<remap from="input/trajectory" to="/planning/scenario_planning/trajectory" />
24+
<!-- global path or mppi-->
2425
<remap from="input/trajectory" to="/planning/output/mppi_planned_path" />
26+
<!-- <remap from="input/trajectory" to="/planning/scenario_planning/trajectory" /> -->
27+
2528
<remap from="output/control_cmd" to="/control/command/control_cmd" />
26-
</node> -->
29+
</node>
2730

2831
<!-- <node pkg="stanley_control" exec="stanley_control" name="stanley_control_node" output="screen"
2932
if="$(var use_stanley)">
@@ -39,14 +42,14 @@
3942

4043
<!-- Control component -->
4144
<!-- Longitudinal (speed) control -->
42-
<node pkg="simple_pd_speed_control" exec="simple_pd_speed_control_node" name="simple_pd_speed_control" output="screen">
45+
<!--<node pkg="simple_pd_speed_control" exec="simple_pd_speed_control_node" name="simple_pd_speed_control" output="screen">
4346
<param name="speed_proportional_gain" value="2.0" />
4447
<remap from="input/kinematics" to="/localization/kinematic_state" />
4548
<remap from="input/trajectory" to="/planning/output/mppi_planned_path" />
46-
</node>
49+
</node> -->
4750

4851
<!-- Lateral (speed) control -->
49-
<node pkg="lateral_pure_pursuit" exec="lateral_pure_pursuit_node" name="lateral_pure_pursuit"
52+
<!-- <node pkg="lateral_pure_pursuit" exec="lateral_pure_pursuit_node" name="lateral_pure_pursuit"
5053
output="screen" unless="$(var use_stanley)">
5154
<param name="wheel_base" value="1.09" />
5255
<param name="lookahead_gain" value="0.24" />
@@ -61,13 +64,13 @@
6164
<param name="k_gain_slow" value="1.0" />
6265
<remap from="input/kinematics" to="/localization/kinematic_state" />
6366
<remap from="input/trajectory" to="/planning/scenario_planning/trajectory" />
64-
</node>
67+
</node> -->
6568

6669
<!-- control unifier -->
67-
<node pkg="ackermann_control_publisher" exec="ackermann_control_publisher_node" name="ackermann_control_publisher" output="screen">
70+
<!-- <node pkg="ackermann_control_publisher" exec="ackermann_control_publisher_node" name="ackermann_control_publisher" output="screen">
6871
<remap from="input/longitudinal" to="output/target_acc" />
6972
<remap from="input/lateral" to="output/steer_angle" />
7073
<remap from="output/ackermann_command" to="/control/command/control_cmd" />
71-
</node>
74+
</node> -->
7275
</group>
7376
</launch>

aichallenge/workspace/src/aichallenge_submit/control/longitudinal/simple_pd_speed_control/src/simple_pd_speed_control.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -45,14 +45,13 @@ namespace simple_speed_pd_control{
4545
return;
4646
}
4747

48-
// size_t closet_traj_point_idx = findNearestIndex(trajectory_->points, odometry_->pose.pose.position);
48+
size_t closet_traj_point_idx = findNearestIndex(trajectory_->points, odometry_->pose.pose.position);
4949

5050
// get closest trajectory point from current position
51-
// TrajectoryPoint closet_traj_point = trajectory_->points.at(closet_traj_point_idx);
51+
TrajectoryPoint closet_traj_point = trajectory_->points.at(closet_traj_point_idx);
5252

5353
// calc longitudinal speed and acceleration
54-
// double target_longitudinal_vel = closet_traj_point.longitudinal_velocity_mps;
55-
double target_longitudinal_vel = 8.0;
54+
double target_longitudinal_vel = closet_traj_point.longitudinal_velocity_mps;
5655
double current_longitudinal_vel = odometry_->twist.twist.linear.x;
5756
Float64 msg = Float64();
5857
msg.data = speed_proportional_gain_ * (target_longitudinal_vel - current_longitudinal_vel);

aichallenge/workspace/src/aichallenge_submit/simple_pure_pursuit/include/simple_pure_pursuit/simple_pure_pursuit.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,8 @@ class SimplePurePursuit : public rclcpp::Node {
5454
double speed_proportional_gain_;
5555
bool use_external_target_vel_;
5656
double external_target_vel_;
57+
double curve_param_max_steer_angle_;
58+
double curve_param_deceleration_vel_;
5759
const double steering_tire_angle_gain_;
5860
OnSetParametersCallbackHandle::SharedPtr reset_param_handler_;
5961

aichallenge/workspace/src/aichallenge_submit/simple_pure_pursuit/src/simple_pure_pursuit.cpp

Lines changed: 20 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,8 @@ SimplePurePursuit::SimplePurePursuit()
2323
speed_proportional_gain_(declare_parameter<float>("speed_proportional_gain", 1.0)),
2424
use_external_target_vel_(declare_parameter<bool>("use_external_target_vel", false)),
2525
external_target_vel_(declare_parameter<float>("external_target_vel", 0.0)),
26+
curve_param_max_steer_angle_(declare_parameter<float>("curve_param_max_steer_angle", 0.1)),
27+
curve_param_deceleration_vel_(declare_parameter<float>("curve_param_deceleration_vel", 1.0)),
2628
steering_tire_angle_gain_(declare_parameter<float>("steering_tire_angle_gain", 1.0))
2729
{
2830
pub_cmd_ = create_publisher<AckermannControlCommand>("output/control_cmd", 1);
@@ -99,14 +101,6 @@ void SimplePurePursuit::onTimer()
99101
double lookahead_point_x = lookahead_point_itr->pose.position.x;
100102
double lookahead_point_y = lookahead_point_itr->pose.position.y;
101103

102-
// calc longitudinal speed and acceleration
103-
double target_longitudinal_vel =
104-
use_external_target_vel_ ? external_target_vel_ : lookahead_point_itr->longitudinal_velocity_mps;
105-
double current_longitudinal_vel = odometry_->twist.twist.linear.x;
106-
107-
cmd.longitudinal.speed = target_longitudinal_vel;
108-
cmd.longitudinal.acceleration =
109-
speed_proportional_gain_ * (target_longitudinal_vel - current_longitudinal_vel);
110104
{
111105
// publish lookahead point marker
112106
auto marker_msg = Marker();
@@ -142,8 +136,26 @@ void SimplePurePursuit::onTimer()
142136
steering_tire_angle_gain_ *
143137
std::atan2(2.0 * wheel_base_ * std::sin(alpha), lookahead_distance);
144138
}
139+
140+
// calc longitudinal speed and acceleration
141+
double target_longitudinal_vel =
142+
use_external_target_vel_ ? external_target_vel_ : lookahead_point_itr->longitudinal_velocity_mps;
143+
double current_longitudinal_vel = odometry_->twist.twist.linear.x;
144+
145+
// ステアリング角度が大きい場合は減速する
146+
if (std::abs(cmd.lateral.steering_tire_angle) > curve_param_max_steer_angle_) {
147+
target_longitudinal_vel = std::min(target_longitudinal_vel, curve_param_deceleration_vel_);
148+
}
149+
150+
cmd.longitudinal.speed = target_longitudinal_vel;
151+
cmd.longitudinal.acceleration =
152+
speed_proportional_gain_ * (target_longitudinal_vel - current_longitudinal_vel);
153+
145154
}
155+
146156
pub_cmd_->publish(cmd);
157+
158+
// publish real-machine command
147159
cmd.lateral.steering_tire_angle /= steering_tire_angle_gain_;
148160
pub_raw_cmd_->publish(cmd);
149161
}

0 commit comments

Comments
 (0)