@@ -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
326330return_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,35 +376,26 @@ 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); };
381-
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);
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); };
387383
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);
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);
393389
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; });
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; });
398392
399- if (pos_diff_sum != 0.0 )
400- {
401- ur_driver_->writeJointCommand (urcl_position_commands_, urcl::comm::ControlMode::MODE_SERVOJ);
393+ if (pos_diff_sum != 0.0 )
394+ position_interface_in_use_ = true ;
402395 }
403- else if (vel_diff_sum != 0.0 )
396+ else if (position_interface_in_use_ )
404397 {
405- ur_driver_->writeJointCommand (urcl_velocity_commands_ , urcl::comm::ControlMode::MODE_SPEEDJ );
398+ ur_driver_->writeJointCommand (urcl_position_commands_ , urcl::comm::ControlMode::MODE_SERVOJ );
406399 }
407400 else
408401 {
@@ -413,7 +406,6 @@ return_type URPositionHardwareInterface::write()
413406
414407 // remember old values
415408 urcl_position_commands_old_ = urcl_position_commands_;
416- urcl_velocity_commands_old_ = urcl_velocity_commands_;
417409
418410 return return_type::OK;
419411 }
0 commit comments