Skip to content

Commit 71bab65

Browse files
committed
Fix naming of isControlMode methods
1 parent daed243 commit 71bab65

File tree

2 files changed

+4
-4
lines changed

2 files changed

+4
-4
lines changed

include/ur_client_library/comm/control_mode.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,7 @@ class ControlModeTypes
8383
*
8484
* \returns true if the control mode is realtime, false otherwise
8585
*/
86-
static bool is_control_mode_realtime(ControlMode control_mode)
86+
static bool isControlModeRealtime(ControlMode control_mode)
8787
{
8888
return (std::find(ControlModeTypes::REALTIME_CONTROL_MODES.begin(), ControlModeTypes::REALTIME_CONTROL_MODES.end(),
8989
control_mode) != ControlModeTypes::REALTIME_CONTROL_MODES.end());
@@ -96,7 +96,7 @@ class ControlModeTypes
9696
*
9797
* \returns true if the control mode is non realtime, false otherwise
9898
*/
99-
static bool is_control_mode_non_realtime(ControlMode control_mode)
99+
static bool isControlModeNonRealtime(ControlMode control_mode)
100100
{
101101
return (std::find(ControlModeTypes::NON_REALTIME_CONTROL_MODES.begin(),
102102
ControlModeTypes::NON_REALTIME_CONTROL_MODES.end(),

src/ur/robot_receive_timeout.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,7 @@ RobotReceiveTimeout RobotReceiveTimeout::off()
6464
int RobotReceiveTimeout::verifyRobotReceiveTimeout(const comm::ControlMode control_mode,
6565
const std::chrono::milliseconds step_time) const
6666
{
67-
if (comm::ControlModeTypes::is_control_mode_non_realtime(control_mode))
67+
if (comm::ControlModeTypes::isControlModeNonRealtime(control_mode))
6868
{
6969
if (timeout_ < step_time && timeout_ > std::chrono::milliseconds(0))
7070
{
@@ -79,7 +79,7 @@ int RobotReceiveTimeout::verifyRobotReceiveTimeout(const comm::ControlMode contr
7979
return timeout_.count();
8080
}
8181
}
82-
else if (comm::ControlModeTypes::is_control_mode_realtime(control_mode))
82+
else if (comm::ControlModeTypes::isControlModeRealtime(control_mode))
8383
{
8484
if (timeout_ < step_time)
8585
{

0 commit comments

Comments
 (0)