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

Adding reset revolution counter service (#325) #343

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
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
4 changes: 4 additions & 0 deletions ur_robot_driver/doc/ROS_INTERFACE.md
Original file line number Diff line number Diff line change
Expand Up @@ -760,6 +760,10 @@ Setup the mounted payload through a ROS service

Calling this service will zero the robot's ftsensor. Note: On e-Series robots this will only work when the robot is in remote-control mode.

##### reset_revolution_counter ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html))

Calling this service will reset the revolution counter for the robot's wrist_3_link. Note: On e-Series robots this will only work when the robot is in remote-control mode.
Copy link
Member

Choose a reason for hiding this comment

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

Just want to clarify for the future reader that it is only the UR3 that will benefits from this.

Suggested change
Calling this service will reset the revolution counter for the robot's wrist_3_link. Note: On e-Series robots this will only work when the robot is in remote-control mode.
The UR3 and UR3e's wrist 3 can do infinite rotations and are therefore not limited to ±2Pi.
Calling this service will reset the revolution counter for the robot's wrist_3_link. Note: On e-Series robots this will only work when the robot is in remote-control mode.
This is handy to avoid rotating back after e.g. a screwing task, and thereby avoid compensating for this in the program.

Copy link
Contributor

Choose a reason for hiding this comment

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

Might be nice to make this even stronger and have the service fail if the robot is not a UR3.

Copy link
Author

Choose a reason for hiding this comment

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

I suppose something like this:

bool HardwareInterface::resetRevolutionCounter(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res)
{
  if (ur_driver_->getName() == 'UR3e' || ur_driver_->getName() == 'UR3')
  {
    std::mutex mtx;
    handleRobotProgramState(false);
    mtx.lock();
    res.success = this->ur_driver_->sendScript(R"(sec resetRevolutionCounter():
    reset_revolution_counter()
  end
  )");
    mtx.unlock();
    handleRobotProgramState(true);
  }
  else
  {
    std::stringstream ss;
    ss << "Resetting the revolution counter is only available for UR3/e robots. This robot is "
       << ur_driver_->getName();
    ROS_ERROR_STREAM(ss.str());
    res.message = ss.str();
    res.success = false;
  }
  return true;
}

Though, I don't know where to get the robot's name...

Copy link
Collaborator

@fmauch fmauch Mar 26, 2021

Choose a reason for hiding this comment

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

Out of my head I am not sure whether there's something predefined to get the robot model through the API. But that would have been my next point on the list.

Edit: Currently, this is not available through the API. Receiving it through the dashboard client would be a workaround to not further postpone this PR. Alternatively it could be received through the primary interface, but that is currently not implemented.

@gavanderhoorn wrote:

Might be nice to make this even stronger and have the service fail if the robot is not a UR3.

I would even have supposed to advertise it only for UR3(e) robots. But that might be more confusing than simply letting the service fail...


#### Parameters

##### dashboard/receive_timeout (Required)
Expand Down
2 changes: 2 additions & 0 deletions ur_robot_driver/include/ur_robot_driver/hardware_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -200,6 +200,7 @@ class HardwareInterface : public hardware_interface::RobotHW
bool setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse& res);
bool resendRobotProgram(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res);
bool zeroFTSensor(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res);
bool resetRevolutionCounter(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res);
void commandCallback(const std_msgs::StringConstPtr& msg);

std::unique_ptr<urcl::UrDriver> ur_driver_;
Expand All @@ -215,6 +216,7 @@ class HardwareInterface : public hardware_interface::RobotHW

ros::ServiceServer deactivate_srv_;
ros::ServiceServer tare_sensor_srv_;
ros::ServiceServer reset_revolution_counter_srv_;
ros::ServiceServer set_payload_srv_;

hardware_interface::JointStateInterface js_interface_;
Expand Down
22 changes: 22 additions & 0 deletions ur_robot_driver/src/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,8 @@

#include <Eigen/Geometry>

#include <mutex>

using industrial_robot_status_interface::RobotMode;
using industrial_robot_status_interface::TriState;
// using namespace urcl::rtde_interface;
Expand Down Expand Up @@ -384,6 +386,11 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
// work when the robot is in remote-control mode.
tare_sensor_srv_ = robot_hw_nh.advertiseService("zero_ftsensor", &HardwareInterface::zeroFTSensor, this);

// Calling this service will reset the revolution counter for the robot's wrist_3_link. Note: On e-Series robots this
// will only work when the robot is in remote-control mode.
reset_revolution_counter_srv_ =
robot_hw_nh.advertiseService("reset_revolution_counter", &HardwareInterface::resetRevolutionCounter, this);

ur_driver_->startRTDECommunication();
ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_robot_driver hardware_interface");

Expand Down Expand Up @@ -912,6 +919,21 @@ end
return true;
}

bool HardwareInterface::resetRevolutionCounter(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res)
{
std::mutex mtx;
mtx.lock();
handleRobotProgramState(false);
res.success = this->ur_driver_->sendScript(R"(sec resetRevolutionCounter():
reset_revolution_counter()
end
)");
ros::Duration(0.1).sleep(); // wait for the reset to be done
handleRobotProgramState(true);
mtx.unlock();
return true;
}

void HardwareInterface::commandCallback(const std_msgs::StringConstPtr& msg)
{
std::string str = msg->data;
Expand Down