Skip to content

県大練習会での変更の取り込み #601

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

Merged
merged 46 commits into from
Oct 30, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
46 commits
Select commit Hold shift + click to select a range
64603d1
rvoプランナ内にPIDをセットアップ
HansRobo Oct 12, 2024
4c7ed29
rvoプランナ内にPIDによる速度制限を減速時のみ導入
HansRobo Oct 12, 2024
28195ff
STOP時の30cmルール
HansRobo Oct 12, 2024
e21a8df
キーパーを少し前に出す
HansRobo Oct 12, 2024
a14dbcd
STOPで取る距離を大きく
HansRobo Oct 12, 2024
4bd0367
キーパーの爆加速をOFF
HansRobo Oct 12, 2024
ef37f63
時間の単位を確認。nsだったのをmsにした
HansRobo Oct 12, 2024
0dc4615
SingleBallPlacementStates::PULL_BACK_FROM_EDGE_PULLの制限速度を下げた
HansRobo Oct 12, 2024
8b94a77
プレイスメントの回避が足りなかったので20cm追加で回避する
HansRobo Oct 12, 2024
ae388cc
あんまり回らないのでとりあえずomega_limitを10倍にする
HansRobo Oct 12, 2024
ebd3e15
まだペナルティエリアに近づきすぎるので更にマージンをとる
HansRobo Oct 12, 2024
9e42702
キックオフが強すぎるので、少し弱くする
HansRobo Oct 12, 2024
91c1930
プレースメント成功条件がガバガバだったのを修正
HansRobo Oct 12, 2024
07d8bfb
プレースメントでけるのが強すぎたのを修正
HansRobo Oct 12, 2024
0c8e056
プレースメントで移動終わった後により長く待つ
HansRobo Oct 12, 2024
e64abf4
角速度制限の修正
HansRobo Oct 12, 2024
b785c36
style(pre-commit): autofix
pre-commit-ci[bot] Oct 12, 2024
40d576a
Merge branch 'develop' into 1012
HansRobo Oct 12, 2024
07c5d86
Merge branch 'develop' into 1012
HansRobo Oct 12, 2024
2401d3e
Merge branch 'develop' into 1012
HansRobo Oct 12, 2024
d1ab8ab
Update ball_nearby_positioner.cpp
HansRobo Oct 12, 2024
fa93d00
爆加速残ってたああああああああああああ
HansRobo Oct 13, 2024
850aebe
omega_limit
HansRobo Oct 13, 2024
ecd7b28
不要なボール回避をOFF
HansRobo Oct 13, 2024
1f05e35
プレイスメントの辺キックを弱く
HansRobo Oct 13, 2024
c3c67c3
プレイスメントの安定化
HansRobo Oct 13, 2024
7436ed8
プレイスメントの角速度設定
HansRobo Oct 13, 2024
2e9f355
ロボットが逆を向く問題の対処
HansRobo Oct 14, 2024
e1c3aa2
プレイスメントで2回目以降のリトライでスリープしない問題の対応
HansRobo Oct 14, 2024
17c9ea5
プレイスメントで初期位置修正が誤爆するので一度コメントアウト
HansRobo Oct 14, 2024
d84acbb
プレイスメントで調整
HansRobo Oct 14, 2024
5a1abe1
テスト用プランナー
HansRobo Oct 14, 2024
6061d5c
キック角度の最低要求精度を下げる
HansRobo Oct 14, 2024
e69de6f
kickスキルの調整
HansRobo Oct 14, 2024
5540263
テスト用プランナー
HansRobo Oct 14, 2024
97122f6
ハーフコート練習用ボールフィルタ
HansRobo Oct 14, 2024
c01a532
パス先固定の解除
HansRobo Oct 14, 2024
bcbc5b1
テストを四角に
HansRobo Oct 14, 2024
f64f0c8
調整
HansRobo Oct 14, 2024
d2ddbe7
データ用launch
HansRobo Oct 14, 2024
4d248e5
データ用launch
HansRobo Oct 14, 2024
87138b9
調整
HansRobo Oct 14, 2024
0c4ae38
Merge branch 'develop' into 1012
HansRobo Oct 20, 2024
5890d54
Merge branch 'develop' into 1012
HansRobo Oct 20, 2024
6144333
Merge branch 'develop' into 1012
HansRobo Oct 26, 2024
1a80774
Merge remote-tracking branch 'origin/develop' into 1012
HansRobo Oct 30, 2024
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
22 changes: 12 additions & 10 deletions crane_bringup/launch/crane.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -89,10 +89,10 @@ def generate_launch_description():
output="screen",
parameters=[
{"planner": "rvo2"},
{"p_gain": 2.0},
{"p_gain": 5.0},
{"i_gain": 0.00},
{"i_saturation": 0.00},
{"d_gain": 3.0},
{"d_gain": 1.0},
{"max_vel": LaunchConfiguration("max_vel")},
{"max_acc": 3.0},
{"deceleration_factor": 1.5},
Expand All @@ -119,11 +119,12 @@ def generate_launch_description():
output="screen",
parameters=[
{"planner": "rvo2"},
{"p_gain": 3.0},
{"p_gain": 5.5},
{"i_gain": 0.0},
{"i_saturation": 0.0},
{"d_gain": 1.5},
{"d_gain": 4.0},
{"max_vel": LaunchConfiguration("max_vel")},
{"max_acc": 4.0},
{"deceleration_factor": 1.5},
],
on_exit=default_exit_behavior,
Expand Down Expand Up @@ -158,7 +159,7 @@ def generate_launch_description():
{"no_movement": False},
{"latency_ms": 0.0},
{"sim_mode": LaunchConfiguration("sim")},
{"kick_power_limit_straight": 1.0},
{"kick_power_limit_straight": 0.30},
{"kick_power_limit_chip": 1.0},
],
on_exit=default_exit_behavior,
Expand Down Expand Up @@ -204,8 +205,10 @@ def generate_launch_description():
package="crane_play_switcher",
executable="play_switcher_node",
output="screen",
parameters=[{"team_name": LaunchConfiguration("team")}],
on_exit=default_exit_behavior,
parameters=[
{"team_name": LaunchConfiguration("team")},
],
on_exit=Shutdown(),
),
# Group with speak condition
GroupAction(
Expand All @@ -214,7 +217,6 @@ def generate_launch_description():
Node(
package="crane_speaker",
executable="crane_speaker_node",
on_exit=default_exit_behavior,
)
],
),
Expand All @@ -223,8 +225,8 @@ def generate_launch_description():
executable="speak_ros_node",
parameters=[
{"plugin_name": "voicevox_plugin::VoiceVoxPlugin"},
{"voicevox_plugin/speaker": 14},
{"voicevox_plugin/speedScale": 1.0},
{"voicevox_plugin/speaker": 13},
{"voicevox_plugin/speedScale": 0.8},
{"voicevox_plugin/volumeScale": 1.0},
],
),
Expand Down
2 changes: 1 addition & 1 deletion crane_robot_skills/src/kickoff_attack.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ KickoffAttack::KickoffAttack(RobotCommandWrapperBase::SharedPtr & base)
{
setParameter("target_x", 0.0f);
setParameter("target_y", 1.0f);
setParameter("kick_power", 0.3);
setParameter("kick_power", 0.25);
addStateFunction(
KickoffAttackState::PREPARE_KICKOFF,
[this]([[maybe_unused]] const ConsaiVisualizerWrapper::SharedPtr & visualizer) -> Status {
Expand Down