Skip to content

Commit 2267fdb

Browse files
PotatoPeeler3000calvertdwihmc-rosieAlexander OCU
authored
Fix the infinite loop with the height map in the controlller, cleaned up the UI for RDX with CSG, and removed a duplicate updater. (#1116)
* Fix Ability hand VR rotator streaming. * Fix the bugs with the CSG and the height map, and more * made csg rdx panel buttons for snapping to heightmap and accounting for ground height drift/footstep z error --------- Co-authored-by: Duncan Calvert <dcalvert@ihmc.us> Co-authored-by: ihmc-rosie <rosie@ihmc.us> Co-authored-by: Alexander OCU <rosie@ihmc.org>
1 parent f069aee commit 2267fdb

File tree

26 files changed

+336
-72
lines changed

26 files changed

+336
-72
lines changed

ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/AvatarStepGeneratorThread.java

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
import java.util.ArrayList;
44
import java.util.Arrays;
55
import java.util.List;
6+
import java.util.function.Consumer;
67

78
import us.ihmc.avatar.drcRobot.DRCRobotModel;
89
import us.ihmc.commonWalkingControlModules.barrierScheduler.context.HumanoidRobotContextData;
@@ -11,6 +12,7 @@
1112
import us.ihmc.commonWalkingControlModules.barrierScheduler.context.HumanoidRobotContextTools;
1213
import us.ihmc.commonWalkingControlModules.controllerCore.command.lowLevel.LowLevelOneDoFJointDesiredDataHolder;
1314
import us.ihmc.commonWalkingControlModules.desiredFootStep.footstepGenerator.FootstepValidityIndicator;
15+
import us.ihmc.commonWalkingControlModules.highLevelHumanoidControl.plugin.ContinuousStepGeneratorParametersCommand;
1416
import us.ihmc.commonWalkingControlModules.highLevelHumanoidControl.plugin.HumanoidSteppingPlugin;
1517
import us.ihmc.commonWalkingControlModules.highLevelHumanoidControl.plugin.HumanoidSteppingPluginFactory;
1618
import us.ihmc.commonWalkingControlModules.highLevelHumanoidControl.plugin.StepGeneratorCommandInputManager;
@@ -90,6 +92,8 @@ public AvatarStepGeneratorThread(HumanoidSteppingPluginFactory pluginFactory,
9092
for (FootstepValidityIndicator footstepValidityIndicator : environmentalConstraints.getFootstepValidityIndicators())
9193
pluginFactory.addFootstepValidityIndicator(footstepValidityIndicator);
9294

95+
csgCommandInputManager.addCSGParametersCommandConsumer(csgParameters -> environmentalConstraints.setSnapToHeightMap(csgParameters.getRequestSnapToHeightmap()));
96+
9397
// clear the environment at the beginning of every update
9498
pluginFactory.addUpdatable(environmentalConstraints);
9599
}

ihmc-common-walking-control-modules/src/main/java/us/ihmc/commonWalkingControlModules/desiredFootStep/footstepGenerator/ContinuousStepGenerator.java

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -325,6 +325,7 @@ else if (statusToProcess == FootstepStatus.COMPLETED)
325325
footstepDataListMessage.setDefaultTransferDuration(parameters.getTransferDuration());
326326
footstepDataListMessage.setFinalTransferDuration(parameters.getTransferDuration());
327327
footstepDataListMessage.setAreFootstepsAdjustable(parameters.getStepsAreAdjustable());
328+
footstepDataListMessage.setOffsetFootstepsHeightWithExecutionError(parameters.getAccountForGroundDrift());
328329
footstepDataListMessage.setOffsetFootstepsWithExecutionError(parameters.getShiftUpcomingStepsWithTouchdown());
329330
}
330331

@@ -522,7 +523,6 @@ else if (swingHeightInputProvider == null && currentCSGMode.getEnumValue() == Co
522523
footstepDataListMessage.setSequenceId(currentFootstepDataListCommandID.getValue());
523524
footstepDataListMessage.getQueueingProperties().setSequenceId(currentFootstepDataListCommandID.getValue());
524525
footstepDataListMessage.getQueueingProperties().setMessageId(currentFootstepDataListCommandID.getValue());
525-
footstepDataListMessage.setOffsetFootstepsHeightWithExecutionError(enableHeightOffsetErrorCompensation.getBooleanValue());
526526
footstepMessenger.submitFootsteps(footstepDataListMessage);
527527
counter = 0;
528528
}
@@ -563,6 +563,8 @@ private void updateCSGStatusMessage()
563563
csgStatusMessage.setCurrentTurnMaxAngleInward(parameters.getTurnMaxAngleInward());
564564
csgStatusMessage.setCurrentTurnMaxAngleOutward(parameters.getTurnMaxAngleOutward());
565565
csgStatusMessage.setAreStepsAdjustable(parameters.getStepsAreAdjustable());
566+
csgStatusMessage.setSnappingToHeightmap(parameters.getRequestSnapToHeightmap());
567+
csgStatusMessage.setAccountingForGroundDrift(parameters.getAccountForGroundDrift());
566568

567569
if (csgStatusMessageOutputManager != null)
568570
csgStatusMessageOutputManager.reportStatusMessage(csgStatusMessage);
@@ -664,6 +666,11 @@ public void setFootstepsAreAdjustable(boolean footstepsAreAdjustable)
664666
parameters.setStepsAreAdjustable(footstepsAreAdjustable);
665667
}
666668

669+
public void setAccountForGroundDrift(boolean accountForGroundDrift)
670+
{
671+
parameters.setAccountForGroundDrift(accountForGroundDrift);
672+
}
673+
667674
public void setSwingHeight(double swingHeight)
668675
{
669676
parameters.setSwingHeight(swingHeight);

ihmc-common-walking-control-modules/src/main/java/us/ihmc/commonWalkingControlModules/desiredFootStep/footstepGenerator/ContinuousStepGeneratorParameters.java

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,8 @@ public class ContinuousStepGeneratorParameters implements ContinuousStepGenerato
1414
private double defaultStepWidth, minStepWidth, maxStepWidth;
1515
private double turnMaxAngleInward, turnMaxAngleOutward;
1616
private boolean stepsAreAdjustable = DEFAULT_STEPS_ARE_ADJUSTABLE;
17+
private boolean requestSnapToHeightMap = DEFAULT_REQUEST_SNAP_TO_HEIGHTMAP;
18+
private boolean accountForGroundDrift = DEFAULT_ACCOUNT_FOR_GROUND_DRIFT;
1719
private boolean shiftUpcomingStepsWithTouchdown = DEFAULT_SHIFT_UPCOMING_STEPS_WITH_TOUCHDOWN;
1820

1921
public ContinuousStepGeneratorParameters()
@@ -120,6 +122,18 @@ public void setTurnMaxAngleOutward(double turnMaxAngleOutward)
120122
this.turnMaxAngleOutward = turnMaxAngleOutward;
121123
}
122124

125+
@Override
126+
public void setRequestSnapToHeightmap(boolean requestSnapToHeightMap)
127+
{
128+
this.requestSnapToHeightMap = requestSnapToHeightMap;
129+
}
130+
131+
@Override
132+
public void setAccountForGroundDrift(boolean accountForGroundDrift)
133+
{
134+
this.accountForGroundDrift = accountForGroundDrift;
135+
}
136+
123137
@Override
124138
public int getNumberOfFootstepsToPlan()
125139
{
@@ -204,6 +218,18 @@ public boolean getStepsAreAdjustable()
204218
return stepsAreAdjustable;
205219
}
206220

221+
@Override
222+
public boolean getRequestSnapToHeightmap()
223+
{
224+
return requestSnapToHeightMap;
225+
}
226+
227+
@Override
228+
public boolean getAccountForGroundDrift()
229+
{
230+
return accountForGroundDrift;
231+
}
232+
207233
@Override
208234
public boolean getShiftUpcomingStepsWithTouchdown()
209235
{

ihmc-common-walking-control-modules/src/main/java/us/ihmc/commonWalkingControlModules/desiredFootStep/footstepGenerator/ContinuousStepGeneratorParametersBasics.java

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,8 @@ public interface ContinuousStepGeneratorParametersBasics
1010
public static final int DEFAULT_NUMBER_OF_FIXED_FOOTSTEPS = 0;
1111
public static final boolean DEFAULT_STEPS_ARE_ADJUSTABLE = true;
1212
public static final boolean DEFAULT_SHIFT_UPCOMING_STEPS_WITH_TOUCHDOWN = true;
13+
public static final boolean DEFAULT_REQUEST_SNAP_TO_HEIGHTMAP = false;
14+
public static final boolean DEFAULT_ACCOUNT_FOR_GROUND_DRIFT = false;
1315

1416
default void clear()
1517
{
@@ -25,6 +27,8 @@ default void clear()
2527
setTurnMaxAngleInward(-Math.PI / 2.0);
2628
setStepsAreAdjustable(DEFAULT_STEPS_ARE_ADJUSTABLE);
2729
setShiftUpcomingStepsWithTouchdown(DEFAULT_SHIFT_UPCOMING_STEPS_WITH_TOUCHDOWN);
30+
setRequestSnapToHeightmap(DEFAULT_REQUEST_SNAP_TO_HEIGHTMAP);
31+
setAccountForGroundDrift(DEFAULT_ACCOUNT_FOR_GROUND_DRIFT);
2832
}
2933

3034
default void set(ContinuousStepGeneratorParametersBasics other)
@@ -44,6 +48,8 @@ default void set(ContinuousStepGeneratorParametersBasics other)
4448
setTurnMaxAngleOutward(other.getTurnMaxAngleOutward());
4549
setStepsAreAdjustable(other.getStepsAreAdjustable());
4650
setShiftUpcomingStepsWithTouchdown(other.getShiftUpcomingStepsWithTouchdown());
51+
setRequestSnapToHeightmap(other.getRequestSnapToHeightmap());
52+
setAccountForGroundDrift(other.getAccountForGroundDrift());
4753
}
4854

4955
default void set(WalkingControllerParameters walkingControllerParameters)
@@ -53,6 +59,8 @@ default void set(WalkingControllerParameters walkingControllerParameters)
5359
setTicksToUpdateTheEnvironment(DEFAULT_TICKS_TO_UPDATE_ENVIRONMENT);
5460
setStepsAreAdjustable(DEFAULT_STEPS_ARE_ADJUSTABLE);
5561
setShiftUpcomingStepsWithTouchdown(DEFAULT_SHIFT_UPCOMING_STEPS_WITH_TOUCHDOWN);
62+
setRequestSnapToHeightmap(DEFAULT_REQUEST_SNAP_TO_HEIGHTMAP);
63+
setAccountForGroundDrift(DEFAULT_ACCOUNT_FOR_GROUND_DRIFT);
5664
setSwingDuration(walkingControllerParameters.getDefaultSwingTime());
5765
setTransferDuration(walkingControllerParameters.getDefaultTransferTime());
5866

@@ -97,6 +105,10 @@ default void set(WalkingControllerParameters walkingControllerParameters)
97105

98106
void setTurnMaxAngleOutward(double turnMaxAngleOutward);
99107

108+
void setRequestSnapToHeightmap(boolean requestSnapToHeightmap);
109+
110+
void setAccountForGroundDrift(boolean accountForGroundDrift);
111+
100112
int getNumberOfFootstepsToPlan();
101113

102114
int getNumberOfFixedFootsteps();
@@ -125,6 +137,10 @@ default void set(WalkingControllerParameters walkingControllerParameters)
125137

126138
boolean getStepsAreAdjustable();
127139

140+
boolean getRequestSnapToHeightmap();
141+
142+
boolean getAccountForGroundDrift();
143+
128144
boolean getShiftUpcomingStepsWithTouchdown();
129145

130146
default String getString()

ihmc-common-walking-control-modules/src/main/java/us/ihmc/commonWalkingControlModules/desiredFootStep/footstepGenerator/YoContinuousStepGeneratorParameters.java

Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,8 @@ public class YoContinuousStepGeneratorParameters implements ContinuousStepGenera
1616
private final YoDouble inPlaceWidth, minStepWidth, maxStepWidth;
1717
private final YoDouble turnMaxAngleInward, turnMaxAngleOutward;
1818
private final YoBoolean stepsAreAdjustable;
19+
private final YoBoolean requestSnapToHeightmap;
20+
private final YoBoolean accountForGroundDrift;
1921
private final YoBoolean shiftUpcomingStepsWithTouchdown;
2022
private final YoInteger ticksToUpdateTheEnvironment;
2123

@@ -34,6 +36,8 @@ public YoContinuousStepGeneratorParameters(String nameSuffix, YoRegistry registr
3436
turnMaxAngleOutward = new YoDouble("maxAngleTurnOutwards" + nameSuffix, registry);
3537
turnMaxAngleInward = new YoDouble("maxAngleTurnInwards" + nameSuffix, registry);
3638
stepsAreAdjustable = new YoBoolean("stepsAreAdjustable" + nameSuffix, registry);
39+
requestSnapToHeightmap = new YoBoolean("requestSnapToHeightmap" + nameSuffix, registry);
40+
accountForGroundDrift = new YoBoolean("accountForGroundDrift" + nameSuffix, registry);
3741
shiftUpcomingStepsWithTouchdown = new YoBoolean("shiftUpcomingStepsWithTouchdown" + nameSuffix, registry);
3842
ticksToUpdateTheEnvironment = new YoInteger("ticksToUpdateTheEnvironment" + nameSuffix, registry);
3943
}
@@ -44,6 +48,18 @@ public void setStepsAreAdjustable(boolean stepsAreAdjustable)
4448
this.stepsAreAdjustable.set(stepsAreAdjustable);
4549
}
4650

51+
@Override
52+
public void setRequestSnapToHeightmap(boolean requestSnapToHeightmap)
53+
{
54+
this.requestSnapToHeightmap.set(requestSnapToHeightmap);
55+
}
56+
57+
@Override
58+
public void setAccountForGroundDrift(boolean accountForGroundDrift)
59+
{
60+
this.accountForGroundDrift.set(accountForGroundDrift);
61+
}
62+
4763
@Override
4864
public void setShiftUpcomingStepsWithTouchdown(boolean shiftUpcomingStepsWithTouchdown)
4965
{
@@ -212,6 +228,18 @@ public boolean getStepsAreAdjustable()
212228
return stepsAreAdjustable.getBooleanValue();
213229
}
214230

231+
@Override
232+
public boolean getRequestSnapToHeightmap()
233+
{
234+
return requestSnapToHeightmap.getBooleanValue();
235+
}
236+
237+
@Override
238+
public boolean getAccountForGroundDrift()
239+
{
240+
return accountForGroundDrift.getBooleanValue();
241+
}
242+
215243
@Override
216244
public boolean getShiftUpcomingStepsWithTouchdown()
217245
{

ihmc-common-walking-control-modules/src/main/java/us/ihmc/commonWalkingControlModules/highLevelHumanoidControl/plugin/CSGROS2CommunicationHelper.java

Lines changed: 24 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
import us.ihmc.commonWalkingControlModules.configurations.SteppingParameters;
88
import us.ihmc.commonWalkingControlModules.configurations.WalkingControllerParameters;
99
import us.ihmc.commonWalkingControlModules.desiredFootStep.footstepGenerator.ContinuousStepGeneratorParametersBasics;
10+
import us.ihmc.commons.thread.Throttler;
1011
import us.ihmc.communication.HumanoidControllerAPI;
1112
import us.ihmc.communication.ROS2Tools;
1213
import us.ihmc.communication.ros2.ROS2Heartbeat;
@@ -19,6 +20,12 @@
1920

2021
public class CSGROS2CommunicationHelper
2122
{
23+
/**
24+
* This defines the update thread rate for information being sent over ROS2. The reason this is a very low frequency is because
25+
* we only have a limited amount of networking bandwidth when using WIFI.
26+
*/
27+
private static final double THROTTLER_THREAD_HERTZ = 11.0;
28+
2229
public static final ROS2Topic<Empty> CSG_HEARTBEAT_TOPIC = new ROS2Topic<>().withPrefix("ihmc")
2330
.withModule("continuous_step_generator")
2431
.withSuffix("heartbeat")
@@ -38,13 +45,17 @@ public class CSGROS2CommunicationHelper
3845
private final ROS2Publisher<ContinuousStepGeneratorInputMessage> csgInputCommandPublisher;
3946
private final ROS2Publisher<ContinuousStepGeneratorParametersMessage> csgParametersCommandPublisher;
4047

41-
// Heartbeat to ensure StepGeneratorCommandInputManager stops walking if connection is broken
48+
// Heartbeat and throttles to ensure StepGeneratorCommandInputManager stops walking if connection is broken
4249
private final ROS2Heartbeat heartbeat;
50+
private Throttler ros2Throttler;
4351

4452
public CSGROS2CommunicationHelper(String robotName, ROS2Node ros2Node, WalkingControllerParameters walkingControllerParameters)
4553
{
4654
this(robotName, ros2Node);
4755
initializeCSGParameters(walkingControllerParameters);
56+
57+
ros2Throttler = new Throttler();
58+
ros2Throttler.setFrequency(THROTTLER_THREAD_HERTZ);
4859
}
4960

5061
public CSGROS2CommunicationHelper(String robotName, ROS2Node ros2Node)
@@ -79,6 +90,18 @@ public void publish(ContinuousStepGeneratorParametersMessage continuousStepGener
7990
csgParametersCommandPublisher.publish(continuousStepGeneratorParametersMessage);
8091
}
8192

93+
public void publishAtThrottledRate(ContinuousStepGeneratorInputMessage continuousStepGeneratorInputMessage)
94+
{
95+
if (ros2Throttler.run())
96+
csgInputCommandPublisher.publish(continuousStepGeneratorInputMessage);
97+
}
98+
99+
public void publishAtThrottledRate(ContinuousStepGeneratorParametersMessage continuousStepGeneratorParametersMessage)
100+
{
101+
if (ros2Throttler.run())
102+
csgParametersCommandPublisher.publish(continuousStepGeneratorParametersMessage);
103+
}
104+
82105
public void addVolatileCSGStatusCallbackSubscription(Consumer<ContinuousStepGeneratorStatusMessage> callback)
83106
{
84107
ROS2Tools.createVolatileCallbackSubscription(ros2Node, HumanoidControllerAPI.getTopic(ContinuousStepGeneratorStatusMessage.class, robotName), callback);

ihmc-common-walking-control-modules/src/main/java/us/ihmc/commonWalkingControlModules/highLevelHumanoidControl/plugin/ContinuousStepGeneratorParametersCommand.java

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,8 @@ public void setFromMessage(ContinuousStepGeneratorParametersMessage message)
4444
parameters.setTurnMaxAngleInward(message.getTurnMaxAngleInward());
4545
parameters.setTurnMaxAngleOutward(message.getTurnMaxAngleOutward());
4646
parameters.setStepsAreAdjustable(message.getStepsAreAdjustable());
47+
parameters.setRequestSnapToHeightmap(message.getSnapToHeightmap());
48+
parameters.setAccountForGroundDrift(message.getAccountForGroundDrift());
4749
}
4850

4951
public ContinuousStepGeneratorParameters getParameters()

ihmc-common-walking-control-modules/src/main/java/us/ihmc/commonWalkingControlModules/highLevelHumanoidControl/plugin/JoystickBasedSteppingPlugin.java

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,6 @@ else if (latestHighLevelControllerStatus.getValue() == HighLevelControllerName.W
5353
public void setFootstepAdjustment(FootstepAdjustment footstepAdjustment)
5454
{
5555
stepGenerator.setFootstepAdjustment(footstepAdjustment);
56-
// fastWalkingJoystickPlugin.setFo
5756
}
5857

5958
public void setHighLevelStateChangeStatusListener(StatusMessageOutputManager statusMessageOutputManager)

ihmc-common-walking-control-modules/src/main/java/us/ihmc/commonWalkingControlModules/highLevelHumanoidControl/plugin/JoystickBasedSteppingPluginFactory.java

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -132,8 +132,6 @@ public JoystickBasedSteppingPlugin buildPlugin(FullHumanoidRobotModel robotModel
132132
commandInputManager::setWalkingStatus);
133133
walkingStatusMessageOutputManager.attachStatusMessageListener(FootstepStatusMessage.class, commandInputManager::consumeFootstepStatus);
134134

135-
updatables.add(commandInputManager);
136-
137135
//this is probably not the way the class was intended to be modified.
138136
commandInputManager.setCSG(csgFootstepGenerator.getContinuousStepGenerator());
139137

ihmc-common-walking-control-modules/src/main/java/us/ihmc/commonWalkingControlModules/highLevelHumanoidControl/plugin/StepGeneratorCommandInputManager.java

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
import us.ihmc.commonWalkingControlModules.controllers.Updatable;
77
import us.ihmc.commonWalkingControlModules.desiredFootStep.footstepGenerator.ContinuousStepGenerator;
88
import us.ihmc.commonWalkingControlModules.desiredFootStep.footstepGenerator.ContinuousStepGeneratorParameters;
9+
import us.ihmc.commonWalkingControlModules.desiredFootStep.footstepGenerator.ContinuousStepGeneratorParametersBasics;
910
import us.ihmc.commonWalkingControlModules.desiredFootStep.footstepGenerator.DesiredTurningVelocityProvider;
1011
import us.ihmc.commonWalkingControlModules.desiredFootStep.footstepGenerator.DesiredVelocityProvider;
1112
import us.ihmc.commonWalkingControlModules.highLevelHumanoidControl.factories.StepGeneratorAPIDefinition;
@@ -52,6 +53,7 @@ public class StepGeneratorCommandInputManager implements Updatable
5253
private ContinuousStepGenerator continuousStepGenerator;
5354

5455
private final List<Consumer<HeightMapCommand>> heightMapCommandConsumers = new ArrayList<>();
56+
private final List<Consumer<ContinuousStepGeneratorParametersBasics>> csgParametersConsumers = new ArrayList<>();
5557
private final AtomicReference<FootstepStatus> latestFootstepStatusReceived = new AtomicReference<>(null);
5658
private final AtomicReference<FootstepStatus> previousFootstepStatusReceived = new AtomicReference<>(null);
5759
private final AtomicReference<HeightMapCommand> latestHeightMap = new AtomicReference<>(null);
@@ -94,6 +96,11 @@ public void addHeightMapCommandConsumer(Consumer<HeightMapCommand> heightMapComm
9496
heightMapCommandConsumers.add(heightMapCommandConsumer);
9597
}
9698

99+
public void addCSGParametersCommandConsumer(Consumer<ContinuousStepGeneratorParametersBasics> csgParametersConsumer)
100+
{
101+
csgParametersConsumers.add(csgParametersConsumer);
102+
}
103+
97104
public CommandInputManager getCommandInputManager()
98105
{
99106
return commandInputManager;
@@ -187,6 +194,8 @@ else if (commandInputManager.isNewCommandAvailable(ContinuousStepGeneratorInputC
187194
continuousStepGenerator.setStepWidths(parameters.getDefaultStepWidth(), parameters.getMinStepWidth(), parameters.getMaxStepWidth());
188195
continuousStepGenerator.setMaxStepLengthForwards(parameters.getMaxStepLengthForwards());
189196
continuousStepGenerator.setMaxStepLengthBackwards(parameters.getMaxStepLengthBackwards());
197+
continuousStepGenerator.getCSGParameters().setRequestSnapToHeightmap(parameters.getRequestSnapToHeightmap());
198+
continuousStepGenerator.getCSGParameters().setAccountForGroundDrift(parameters.getAccountForGroundDrift());
190199
}
191200
}
192201
commandInputManager.clearCommands(ContinuousStepGeneratorParametersCommand.class);
@@ -227,6 +236,12 @@ else if (commandInputManager.isNewCommandAvailable(ContinuousStepGeneratorInputC
227236
}
228237
}
229238

239+
if (continuousStepGenerator != null)
240+
{
241+
for (int i = 0; i < csgParametersConsumers.size(); i++)
242+
csgParametersConsumers.get(i).accept(continuousStepGenerator.getCSGParameters());
243+
}
244+
230245
ticksSinceUpdatingTheEnvironment.incrementAndGet();
231246

232247
previousWalkingStatus.set(latestWalkingStatus.get());

0 commit comments

Comments
 (0)