Skip to content

Commit 7ffcf4c

Browse files
authored
Fix Windows build (#1033)
Signed-off-by: Louise Poubel <[email protected]>
1 parent 1e1d0ba commit 7ffcf4c

File tree

1 file changed

+6
-5
lines changed

1 file changed

+6
-5
lines changed

src/systems/joint_position_controller/JointPositionController.cc

+6-5
Original file line numberDiff line numberDiff line change
@@ -66,12 +66,13 @@ class ignition::gazebo::systems::JointPositionControllerPrivate
6666
public: unsigned int jointIndex = 0u;
6767

6868
/// \brief Operation modes
69-
enum OperationMode {
69+
enum OperationMode
70+
{
7071
/// \brief Use PID to achieve positional control
7172
PID,
7273
/// \brief Bypass PID completely. This means the joint will move to that
7374
/// position bypassing the physics engine.
74-
ABSOLUTE
75+
ABS
7576
};
7677

7778
/// \brief Joint position mode
@@ -162,7 +163,7 @@ void JointPositionController::Configure(const Entity &_entity,
162163
if (useVelocityCommands)
163164
{
164165
this->dataPtr->mode =
165-
JointPositionControllerPrivate::OperationMode::ABSOLUTE;
166+
JointPositionControllerPrivate::OperationMode::ABS;
166167
}
167168
}
168169

@@ -270,9 +271,9 @@ void JointPositionController::PreUpdate(
270271
this->dataPtr->jointPosCmd;
271272
}
272273

273-
// Check if the mode is ABSOLUTE
274+
// Check if the mode is ABS
274275
if (this->dataPtr->mode ==
275-
JointPositionControllerPrivate::OperationMode::ABSOLUTE)
276+
JointPositionControllerPrivate::OperationMode::ABS)
276277
{
277278
// Calculate target velcity
278279
double targetVel = 0;

0 commit comments

Comments
 (0)