mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-12 19:10:47 +02:00
send keepalive signal when no (commanding) controller is active
Otherwise the hardware disconnects as soon as we stop a controller by hand.
This commit is contained in:
@@ -292,6 +292,10 @@ void HardwareInterface ::write(const ros::Time& time, const ros::Duration& perio
|
||||
{
|
||||
ur_driver_->writeJointCommand(joint_position_command_);
|
||||
}
|
||||
else
|
||||
{
|
||||
ur_driver_->writeKeepalive();
|
||||
}
|
||||
}
|
||||
|
||||
bool HardwareInterface ::prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
|
||||
|
||||
@@ -138,14 +138,19 @@ bool UrDriver::writeJointCommand(const vector6d_t& values)
|
||||
{
|
||||
if (reverse_interface_active_)
|
||||
{
|
||||
reverse_interface_->write(values);
|
||||
}
|
||||
else
|
||||
{
|
||||
return false;
|
||||
return reverse_interface_->write(&values);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
bool UrDriver::writeKeepalive()
|
||||
{
|
||||
if (reverse_interface_active_)
|
||||
{
|
||||
vector6d_t* fake = nullptr;
|
||||
return reverse_interface_->write(fake, 1);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void UrDriver::startWatchdog()
|
||||
|
||||
Reference in New Issue
Block a user