Skip to content

Commit b7dde30

Browse files
authored
Merge pull request #32 from PickNikRobotics/livanov/use_only_position_interface
Use only position command interface for Beta driver
2 parents eb2a01a + 4aad523 commit b7dde30

File tree

2 files changed

+20
-27
lines changed

2 files changed

+20
-27
lines changed

ur_robot_driver/include/ur_robot_driver/hardware_interface.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -108,7 +108,6 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
108108
urcl::vector6d_t urcl_position_commands_;
109109
urcl::vector6d_t urcl_position_commands_old_;
110110
urcl::vector6d_t urcl_velocity_commands_;
111-
urcl::vector6d_t urcl_velocity_commands_old_;
112111
urcl::vector6d_t urcl_joint_positions_;
113112
urcl::vector6d_t urcl_joint_velocities_;
114113
urcl::vector6d_t urcl_joint_efforts_;
@@ -139,6 +138,7 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
139138

140139
bool robot_program_running_;
141140
bool non_blocking_read_;
141+
bool position_interface_in_use_;
142142

143143
std::unique_ptr<urcl::UrDriver> ur_driver_;
144144
};

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 19 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -150,6 +150,8 @@ return_type URPositionHardwareInterface::start()
150150
{
151151
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Starting ...please wait...");
152152

153+
position_interface_in_use_ = false;
154+
153155
std::this_thread::sleep_for(std::chrono::seconds(2));
154156

155157
// The robot's IP address.
@@ -288,6 +290,8 @@ return_type URPositionHardwareInterface::stop()
288290
{
289291
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Stopping ...please wait...");
290292

293+
position_interface_in_use_ = false;
294+
291295
std::this_thread::sleep_for(std::chrono::seconds(2));
292296

293297
ur_driver_.reset();
@@ -325,8 +329,6 @@ void URPositionHardwareInterface::readBitsetData(const std::unique_ptr<rtde::Dat
325329

326330
return_type URPositionHardwareInterface::read()
327331
{
328-
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Reading ...");
329-
330332
std::unique_ptr<rtde::DataPackage> data_pkg = ur_driver_->getDataPackage();
331333

332334
if (data_pkg)
@@ -374,36 +376,28 @@ return_type URPositionHardwareInterface::write()
374376
runtime_state_ == static_cast<uint32_t>(rtde::RUNTIME_STATE::PAUSING)) &&
375377
robot_program_running_ && (!non_blocking_read_ || packet_read_))
376378
{
377-
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Writing ...");
378-
379-
// create a lambda substract functor
380-
std::function<double(double, double)> substractor = [](double a, double b) { return std::abs(a - b); };
379+
if (!position_interface_in_use_)
380+
{
381+
// create a lambda substract functor
382+
std::function<double(double, double)> substractor = [](double a, double b) { return std::abs(a - b); };
381383

382-
// create a position difference vector
383-
std::vector<double> pos_diff;
384-
pos_diff.resize(urcl_position_commands_.size());
385-
std::transform(urcl_position_commands_.begin(), urcl_position_commands_.end(), urcl_position_commands_old_.begin(),
386-
pos_diff.begin(), substractor);
384+
// create a position difference vector
385+
std::vector<double> pos_diff;
386+
pos_diff.resize(urcl_position_commands_.size());
387+
std::transform(urcl_position_commands_.begin(), urcl_position_commands_.end(),
388+
urcl_position_commands_old_.begin(), pos_diff.begin(), substractor);
387389

388-
// create a velocity difference vector
389-
std::vector<double> vel_diff;
390-
vel_diff.resize(urcl_velocity_commands_.size());
391-
std::transform(urcl_velocity_commands_.begin(), urcl_velocity_commands_.end(), urcl_velocity_commands_old_.begin(),
392-
vel_diff.begin(), substractor);
390+
double pos_diff_sum = 0.0;
391+
std::for_each(pos_diff.begin(), pos_diff.end(), [&pos_diff_sum](double a) { return pos_diff_sum += a; });
393392

394-
double pos_diff_sum = 0.0;
395-
double vel_diff_sum = 0.0;
396-
std::for_each(pos_diff.begin(), pos_diff.end(), [&pos_diff_sum](double a) { return pos_diff_sum += a; });
397-
std::for_each(vel_diff.begin(), vel_diff.end(), [&vel_diff_sum](double a) { return vel_diff_sum += a; });
393+
if (pos_diff_sum != 0.0)
394+
position_interface_in_use_ = true;
395+
}
398396

399-
if (pos_diff_sum != 0.0)
397+
if (position_interface_in_use_)
400398
{
401399
ur_driver_->writeJointCommand(urcl_position_commands_, urcl::comm::ControlMode::MODE_SERVOJ);
402400
}
403-
else if (vel_diff_sum != 0.0)
404-
{
405-
ur_driver_->writeJointCommand(urcl_velocity_commands_, urcl::comm::ControlMode::MODE_SPEEDJ);
406-
}
407401
else
408402
{
409403
ur_driver_->writeKeepalive();
@@ -413,7 +407,6 @@ return_type URPositionHardwareInterface::write()
413407

414408
// remember old values
415409
urcl_position_commands_old_ = urcl_position_commands_;
416-
urcl_velocity_commands_old_ = urcl_velocity_commands_;
417410

418411
return return_type::OK;
419412
}

0 commit comments

Comments
 (0)