Skip to content

Commit

Permalink
Avoid updating ros_control controllers on pipeline timeout
Browse files Browse the repository at this point in the history
  • Loading branch information
miguelprada committed Oct 16, 2018
1 parent c4b2c73 commit 35001e6
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 12 deletions.
9 changes: 4 additions & 5 deletions include/ur_modern_driver/pipeline.h
Original file line number Diff line number Diff line change
Expand Up @@ -159,11 +159,10 @@ class Pipeline
unique_ptr<T> product;
while (running_)
{
// timeout was chosen because we should receive messages
// at roughly 125hz (every 8ms) and have to update
// the controllers (i.e. the consumer) with *at least* 125Hz
// So we update the consumer more frequently via onTimeout
if (!queue_.wait_dequeue_timed(product, std::chrono::milliseconds(8)))
// 16000us timeout was chosen because we should
// roughly recieve messages at 125hz which is every
// 8ms so double it for some error margin
if (!queue_.wait_dequeue_timed(product, std::chrono::milliseconds(16)))
{
consumer_.onTimeout();
continue;
Expand Down
2 changes: 0 additions & 2 deletions include/ur_modern_driver/ros/controller.h
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,5 @@ class ROSController : private hardware_interface::RobotHW, public URRTPacketCons
return update();
}

virtual void onTimeout();

virtual void onRobotStateChange(RobotState state);
};
5 changes: 0 additions & 5 deletions src/ros/controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,11 +109,6 @@ bool ROSController::update()
return write();
}

void ROSController::onTimeout()
{
update();
}

void ROSController::onRobotStateChange(RobotState state)
{
bool next = (state == RobotState::Running);
Expand Down

0 comments on commit 35001e6

Please sign in to comment.