Skip to content

Commit

Permalink
Fix Windows build (#1033)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina authored Sep 16, 2021
1 parent 1e1d0ba commit 7ffcf4c
Showing 1 changed file with 6 additions and 5 deletions.
11 changes: 6 additions & 5 deletions src/systems/joint_position_controller/JointPositionController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -66,12 +66,13 @@ class ignition::gazebo::systems::JointPositionControllerPrivate
public: unsigned int jointIndex = 0u;

/// \brief Operation modes
enum OperationMode {
enum OperationMode
{
/// \brief Use PID to achieve positional control
PID,
/// \brief Bypass PID completely. This means the joint will move to that
/// position bypassing the physics engine.
ABSOLUTE
ABS
};

/// \brief Joint position mode
Expand Down Expand Up @@ -162,7 +163,7 @@ void JointPositionController::Configure(const Entity &_entity,
if (useVelocityCommands)
{
this->dataPtr->mode =
JointPositionControllerPrivate::OperationMode::ABSOLUTE;
JointPositionControllerPrivate::OperationMode::ABS;
}
}

Expand Down Expand Up @@ -270,9 +271,9 @@ void JointPositionController::PreUpdate(
this->dataPtr->jointPosCmd;
}

// Check if the mode is ABSOLUTE
// Check if the mode is ABS
if (this->dataPtr->mode ==
JointPositionControllerPrivate::OperationMode::ABSOLUTE)
JointPositionControllerPrivate::OperationMode::ABS)
{
// Calculate target velcity
double targetVel = 0;
Expand Down

0 comments on commit 7ffcf4c

Please sign in to comment.