Skip to content

Commit 3ccab13

Browse files
committed
fix phase problem and renamed old walking to quintic walking
1 parent 914d6a1 commit 3ccab13

3 files changed

Lines changed: 17 additions & 10 deletions

File tree

src/bitbots_misc/bitbots_bringup/launch/motion.launch

Lines changed: 9 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<launch>
33
<arg name="sim" default="false"/>
44
<arg name="viz" default="false"/>
5-
<arg name="walking" default="false" description="start the walking" /> <!--should be removed-->
5+
<arg name="quintic_walking" default="false" description="start quintic walking" /> <!--should be removed-->
66
<arg name="rl_policies" default="true" description="start the policies" />
77
<arg name="torqueless_mode" default="false" description="start without torque, for example for testing the falling detection"/>
88
<arg name="tts" default="true" description="Whether to speak" />
@@ -39,8 +39,8 @@
3939
<arg name="sim" value="$(var sim)" />
4040
</include>
4141

42-
<!-- launch the old walking - exists for debug purpose-->
43-
<group if="$(var walking)">
42+
<!-- launch quintic walking -->
43+
<group if="$(var quintic_walking)">
4444
<include file="$(find-pkg-share bitbots_quintic_walk)/launch/quintic_walk.launch">
4545
<arg name="sim" value="$(var sim)"/>
4646
<arg name="viz" value="$(var viz)"/>
@@ -59,11 +59,12 @@
5959
</include>
6060
-->
6161

62-
63-
<!--launch rl policies -->
64-
<include file="$(find-pkg-share bitbots_rl_motion)/launch/rl_motion.launch">
65-
<arg name="sim" value="$(var sim)"/>
66-
</include>
62+
<!--launch rl policies -->
63+
<group if="$(var rl_policies)">
64+
<include file="$(find-pkg-share bitbots_rl_motion)/launch/rl_motion.launch">
65+
<arg name="sim" value="$(var sim)"/>
66+
</include>
67+
</group>
6768

6869
<!-- launch dynup -->
6970
<include file="$(find-pkg-share bitbots_dynup)/launch/dynup.launch">

src/bitbots_motion/bitbots_rl_motion/bitbots_rl_motion/phase.py

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,12 @@ def __init__(self, config):
2121

2222
self._obs_phase = None
2323

24+
def check_phase_set(self):
25+
if self.get_phase():
26+
return True
27+
28+
return False
29+
2430
def set_phase(self, new_phase):
2531
self._phase = new_phase
2632

src/bitbots_motion/bitbots_rl_motion/nodes/rl_node.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ def _timer_callback(self):
6363

6464
# TODO consider IMU mounting offset
6565

66-
if self._phase.get_phase():
66+
if self._phase.check_phase_set():
6767
self._phase.set_obs_phase(
6868
np.array(
6969
[np.cos(self._phase.get_phase()), np.sin(self._phase.get_phase())],
@@ -80,7 +80,7 @@ def _timer_callback(self):
8080

8181
self.publisher(onnx_pred)
8282

83-
if self._phase.get_phase():
83+
if self._phase.check_phase_set():
8484
phase_tp1 = self._phase.get_phase() + self._phase.get_phase_dt()
8585
self._phase.set_phase(np.fmod(phase_tp1 + np.pi, 2 * np.pi) - np.pi)
8686

0 commit comments

Comments
 (0)