Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix Windows build #1033

Merged
merged 1 commit into from
Sep 16, 2021
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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