mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
Added boundary check for setting payload
This commit is contained in:
@@ -12,8 +12,10 @@
|
||||
#include "ur_modern_driver/ur_driver.h"
|
||||
|
||||
UrDriver::UrDriver(std::condition_variable& msg_cond, std::string host,
|
||||
unsigned int safety_count_max, double max_time_step, double max_vel, double min_payload, double max_payload ) :
|
||||
maximum_time_step_(max_time_step), maximum_velocity_(max_vel), minimum_payload_(min_payload), maximum_payload_(max_payload) {
|
||||
unsigned int safety_count_max, double max_time_step, double max_vel,
|
||||
double min_payload, double max_payload) :
|
||||
maximum_time_step_(max_time_step), maximum_velocity_(max_vel), minimum_payload_(
|
||||
min_payload), maximum_payload_(max_payload) {
|
||||
rt_interface_ = new UrRealtimeCommunication(msg_cond, host,
|
||||
safety_count_max);
|
||||
|
||||
@@ -142,12 +144,15 @@ void UrDriver::setAnalogOut(unsigned int n, double f) {
|
||||
rt_interface_->addCommandToQueue(buf);
|
||||
}
|
||||
|
||||
void UrDriver::setPayload(double m) {
|
||||
char buf[256];
|
||||
sprintf(buf, "sec setOut():\n\tset_payload(%1.3f)\nend\n", m);
|
||||
printf("%s", buf);
|
||||
rt_interface_->addCommandToQueue(buf);
|
||||
|
||||
bool UrDriver::setPayload(double m) {
|
||||
if ((m < maximum_payload_) && (m > minimum_payload_)) {
|
||||
char buf[256];
|
||||
sprintf(buf, "sec setOut():\n\tset_payload(%1.3f)\nend\n", m);
|
||||
printf("%s", buf);
|
||||
rt_interface_->addCommandToQueue(buf);
|
||||
return true;
|
||||
} else
|
||||
return false;
|
||||
}
|
||||
|
||||
void UrDriver::setMaxVel(double vel) {
|
||||
|
||||
@@ -68,7 +68,7 @@ public:
|
||||
{ //Using a very high value in order to not limit execution of trajectories being sent from MoveIt!
|
||||
double max_velocity = 10.;
|
||||
if (ros::param::get("~max_velocity", max_velocity)) {
|
||||
ROS_INFO(
|
||||
ROS_DEBUG(
|
||||
"Max velocity accepted by ur_driver: %f [rad/s]", max_velocity);
|
||||
robot_.setMaxVel(max_velocity);
|
||||
}
|
||||
@@ -79,11 +79,11 @@ public:
|
||||
double min_payload = 0.;
|
||||
double max_payload = 1.;
|
||||
if (ros::param::get("~min_payload", min_payload)) {
|
||||
ROS_INFO(
|
||||
ROS_DEBUG(
|
||||
"Min payload accepted by ur_driver: %f [kg]", min_payload);
|
||||
}
|
||||
if (ros::param::get("~max_payload", max_payload)) {
|
||||
ROS_INFO(
|
||||
ROS_DEBUG(
|
||||
"Max payload accepted by ur_driver: %f [kg]", max_payload);
|
||||
}
|
||||
robot_.setMinPayload(min_payload);
|
||||
@@ -189,9 +189,11 @@ private:
|
||||
|
||||
bool setPayload(ur_msgs::SetPayloadRequest& req,
|
||||
ur_msgs::SetPayloadResponse& resp) {
|
||||
robot_.setPayload(req.payload);
|
||||
resp.success = true;
|
||||
return true;
|
||||
if (robot_.setPayload(req.payload))
|
||||
resp.success = true;
|
||||
else
|
||||
resp.success = true;
|
||||
return resp.success;
|
||||
}
|
||||
|
||||
bool validateJointNames() {
|
||||
|
||||
Reference in New Issue
Block a user