Skip to content

Commit 86b73ba

Browse files
committed
fix(hlvs): simulation configuration
by preventing duplicated rosbag recording as it moved to teamplayer and using IMU data for the walking phase reset. As we do not have foot pressure sensors in the configured devices for hlvs, the robot will not walk otherwise.
1 parent 9fb21fe commit 86b73ba

2 files changed

Lines changed: 3 additions & 9 deletions

File tree

bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_simulator.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -75,13 +75,13 @@ walking:
7575
phase_reset:
7676
min_phase: 0.90
7777
foot_pressure:
78-
active: True
78+
active: False
7979
ground_min_pressure: 1.5
8080
effort:
8181
active: False
8282
joint_min_effort: 30.0
8383
imu:
84-
active: False
84+
active: True
8585
y_acceleration_threshold: 1.4
8686

8787
trunk_pid:

bitbots_simulation/bitbots_robocup_api/launch/robocup_teamplayer.launch

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -2,13 +2,6 @@
22
<launch>
33
<arg name="record" default="true" />
44

5-
<!-- record rosbag -->
6-
<group if="$(var record)">
7-
<include file="$(find-pkg-share bitbots_bringup)/launch/rosbag_record.launch.py">
8-
<arg name="sim" value="true" />
9-
</include>
10-
</group>
11-
125
<!-- load the robocup api -->
136
<include file="$(find-pkg-share bitbots_robocup_api)/launch/bitbots_robocup_api_bridge.launch" />
147

@@ -23,5 +16,6 @@
2316
<arg name="teamcom" value="true" />
2417
<arg name="vision" value="true" />
2518
<arg name="world_model" value="true" />
19+
<arg name="record" value="$(var record)" />
2620
</include>
2721
</launch>

0 commit comments

Comments
 (0)