diff --git a/ur_rtde_driver/src/ros/hardware_interface.cpp b/ur_rtde_driver/src/ros/hardware_interface.cpp index e65edf6..ac33cdb 100644 --- a/ur_rtde_driver/src/ros/hardware_interface.cpp +++ b/ur_rtde_driver/src/ros/hardware_interface.cpp @@ -287,15 +287,17 @@ void HardwareInterface ::read(const ros::Time& time, const ros::Duration& period void HardwareInterface ::write(const ros::Time& time, const ros::Duration& period) { - if (position_controller_running_ && - (runtime_state_ == static_cast(rtde_interface::RUNTIME_STATE::PLAYING) || - runtime_state_ == static_cast(rtde_interface::RUNTIME_STATE::PAUSING))) + if (runtime_state_ == static_cast(rtde_interface::RUNTIME_STATE::PLAYING) || + runtime_state_ == static_cast(rtde_interface::RUNTIME_STATE::PAUSING)) { - ur_driver_->writeJointCommand(joint_position_command_); - } - else - { - ur_driver_->writeKeepalive(); + if (position_controller_running_) + { + ur_driver_->writeJointCommand(joint_position_command_); + } + else + { + ur_driver_->writeKeepalive(); + } } }