mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-12 11:00:47 +02:00
send keepalive signals only if the program is running
when no program is running, we do not want to fill the buffer anyway.
This commit is contained in:
committed by
Tristan Schnell
parent
6aa2670eba
commit
6979ec35e0
@@ -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)
|
void HardwareInterface ::write(const ros::Time& time, const ros::Duration& period)
|
||||||
{
|
{
|
||||||
if (position_controller_running_ &&
|
if (runtime_state_ == static_cast<uint32_t>(rtde_interface::RUNTIME_STATE::PLAYING) ||
|
||||||
(runtime_state_ == static_cast<uint32_t>(rtde_interface::RUNTIME_STATE::PLAYING) ||
|
runtime_state_ == static_cast<uint32_t>(rtde_interface::RUNTIME_STATE::PAUSING))
|
||||||
runtime_state_ == static_cast<uint32_t>(rtde_interface::RUNTIME_STATE::PAUSING)))
|
|
||||||
{
|
{
|
||||||
ur_driver_->writeJointCommand(joint_position_command_);
|
if (position_controller_running_)
|
||||||
}
|
{
|
||||||
else
|
ur_driver_->writeJointCommand(joint_position_command_);
|
||||||
{
|
}
|
||||||
ur_driver_->writeKeepalive();
|
else
|
||||||
|
{
|
||||||
|
ur_driver_->writeKeepalive();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user