@@ -484,13 +484,13 @@ void AdmittanceController::read_state_from_hardware(
484
484
state_interfaces_[pos_ind * num_joints_ + joint_ind].get_value ();
485
485
nan_position |= std::isnan (state_current.positions [joint_ind]);
486
486
}
487
- else if (has_velocity_state_interface_)
487
+ if (has_velocity_state_interface_)
488
488
{
489
489
state_current.velocities [joint_ind] =
490
490
state_interfaces_[vel_ind * num_joints_ + joint_ind].get_value ();
491
491
nan_velocity |= std::isnan (state_current.velocities [joint_ind]);
492
492
}
493
- else if (has_acceleration_state_interface_)
493
+ if (has_acceleration_state_interface_)
494
494
{
495
495
state_current.accelerations [joint_ind] =
496
496
state_interfaces_[acc_ind * num_joints_ + joint_ind].get_value ();
@@ -536,12 +536,12 @@ void AdmittanceController::write_state_to_hardware(
536
536
command_interfaces_[pos_ind * num_joints_ + joint_ind].set_value (
537
537
state_commanded.positions [joint_ind]);
538
538
}
539
- else if (has_velocity_command_interface_)
539
+ if (has_velocity_command_interface_)
540
540
{
541
541
command_interfaces_[vel_ind * num_joints_ + joint_ind].set_value (
542
542
state_commanded.velocities [joint_ind]);
543
543
}
544
- else if (has_acceleration_command_interface_)
544
+ if (has_acceleration_command_interface_)
545
545
{
546
546
command_interfaces_[acc_ind * num_joints_ + joint_ind].set_value (
547
547
state_commanded.accelerations [joint_ind]);
0 commit comments