Skip to content

Commit

Permalink
Merge branch 'master' into filter/joints/joint_state_broadcaster
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Aug 1, 2024
2 parents fc8baa3 + 9ab8205 commit a9d5ba8
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 8 deletions.
4 changes: 2 additions & 2 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ repos:

# Python hooks
- repo: https://github.com/asottile/pyupgrade
rev: v3.16.0
rev: v3.17.0
hooks:
- id: pyupgrade
args: [--py36-plus]
Expand Down Expand Up @@ -133,7 +133,7 @@ repos:
exclude: CHANGELOG\.rst|\.(svg|pyc|drawio)$

- repo: https://github.com/python-jsonschema/check-jsonschema
rev: 0.28.6
rev: 0.29.1
hooks:
- id: check-github-workflows
args: ["--verbose"]
Expand Down
12 changes: 6 additions & 6 deletions admittance_controller/src/admittance_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -476,13 +476,13 @@ void AdmittanceController::read_state_from_hardware(
state_interfaces_[pos_ind * num_joints_ + joint_ind].get_value();
nan_position |= std::isnan(state_current.positions[joint_ind]);
}
else if (has_velocity_state_interface_)
if (has_velocity_state_interface_)
{
state_current.velocities[joint_ind] =
state_interfaces_[vel_ind * num_joints_ + joint_ind].get_value();
nan_velocity |= std::isnan(state_current.velocities[joint_ind]);
}
else if (has_acceleration_state_interface_)
if (has_acceleration_state_interface_)
{
state_current.accelerations[joint_ind] =
state_interfaces_[acc_ind * num_joints_ + joint_ind].get_value();
Expand Down Expand Up @@ -528,15 +528,15 @@ void AdmittanceController::write_state_to_hardware(
command_interfaces_[pos_ind * num_joints_ + joint_ind].set_value(
state_commanded.positions[joint_ind]);
}
else if (has_velocity_command_interface_)
if (has_velocity_command_interface_)
{
command_interfaces_[vel_ind * num_joints_ + joint_ind].set_value(
state_commanded.positions[joint_ind]);
state_commanded.velocities[joint_ind]);
}
else if (has_acceleration_command_interface_)
if (has_acceleration_command_interface_)
{
command_interfaces_[acc_ind * num_joints_ + joint_ind].set_value(
state_commanded.positions[joint_ind]);
state_commanded.accelerations[joint_ind]);
}
}
last_commanded_ = state_commanded;
Expand Down

0 comments on commit a9d5ba8

Please sign in to comment.