Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Notify users when no packets are received #322

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions include/ur_modern_driver/ros/controller.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,13 +31,18 @@
#include "ur_modern_driver/ur/consumer.h"
#include "ur_modern_driver/ur/rt_state.h"

// If no packet is received for this time, a warning is issued to the user
// CB2 and 3 cycle times are 0.008, adding some margin
static const double PACKET_RECEIVE_WARN_TIME = 0.01;

class ROSController : private hardware_interface::RobotHW, public URRTPacketConsumer, public Service
{
private:
ros::NodeHandle nh_;
ros::Time lastUpdate_;
controller_manager::ControllerManager controller_;
bool robot_state_received_;
ros::Time most_recent_packet_time_;
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I feel that you could reuse the lastUpdate_ member variable

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

since lastUpdate_ is updated each time the update function is called and that function is also called, when no new package has been read, it does not quite fit the requirements.


// state interfaces
JointInterface joint_interface_;
Expand Down
9 changes: 9 additions & 0 deletions src/ros/controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,18 +101,27 @@ void ROSController::read(RTShared& packet)
joint_interface_.update(packet);
wrench_interface_.update(packet);
robot_state_received_ = true;
most_recent_packet_time_ = ros::Time::now();
}

bool ROSController::update()
{
// don't run controllers if we haven't received robot state yet
if (!robot_state_received_)
{
ROS_INFO_THROTTLE(1.0, "No messages received from the robot so far.");
return true;
}

auto time = ros::Time::now();
auto diff = time - lastUpdate_;
lastUpdate_ = time;

if ((time - most_recent_packet_time_).toSec() > PACKET_RECEIVE_WARN_TIME)
{
ROS_WARN_THROTTLE(1.0, "No new packets received from robot. Connection is probably lost");
}

controller_.update(time, diff, !service_enabled_);

// emergency stop and such should not kill the pipeline
Expand Down