From 7ffcf4cd677855717b8e7fa508aefc33e1b4e9ee Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Wed, 15 Sep 2021 19:18:05 -0700 Subject: [PATCH] Fix Windows build (#1033) Signed-off-by: Louise Poubel --- .../JointPositionController.cc | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/src/systems/joint_position_controller/JointPositionController.cc b/src/systems/joint_position_controller/JointPositionController.cc index 8692d9b8db..00d3cdced6 100644 --- a/src/systems/joint_position_controller/JointPositionController.cc +++ b/src/systems/joint_position_controller/JointPositionController.cc @@ -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 @@ -162,7 +163,7 @@ void JointPositionController::Configure(const Entity &_entity, if (useVelocityCommands) { this->dataPtr->mode = - JointPositionControllerPrivate::OperationMode::ABSOLUTE; + JointPositionControllerPrivate::OperationMode::ABS; } } @@ -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;