1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 10:00:48 +02:00

Only write position commands if a position controller is active.

Fixes #19
This commit is contained in:
Felix Mauch
2019-04-16 09:04:28 +02:00
parent d7f065a22d
commit 639da94588
2 changed files with 18 additions and 2 deletions

View File

@@ -65,6 +65,8 @@ protected:
vector6d_t joint_velocities_; vector6d_t joint_velocities_;
vector6d_t joint_efforts_; vector6d_t joint_efforts_;
std::vector<std::string> joint_names_; std::vector<std::string> joint_names_;
bool position_controller_running_;
}; };
} // namespace ur_driver } // namespace ur_driver

View File

@@ -35,6 +35,7 @@ HardwareInterface::HardwareInterface()
, joint_velocities_{ 0, 0, 0, 0, 0, 0 } , joint_velocities_{ 0, 0, 0, 0, 0, 0 }
, joint_efforts_{ 0, 0, 0, 0, 0, 0 } , joint_efforts_{ 0, 0, 0, 0, 0, 0 }
, joint_names_(6) , joint_names_(6)
, position_controller_running_(false)
{ {
} }
@@ -100,9 +101,12 @@ void HardwareInterface ::read(const ros::Time& time, const ros::Duration& period
} }
void HardwareInterface ::write(const ros::Time& time, const ros::Duration& period) void HardwareInterface ::write(const ros::Time& time, const ros::Duration& period)
{
if (position_controller_running_)
{ {
ur_driver_->writeJointCommand(joint_position_command_); ur_driver_->writeJointCommand(joint_position_command_);
} }
}
bool HardwareInterface ::prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list, bool HardwareInterface ::prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list) const std::list<hardware_interface::ControllerInfo>& stop_list)
@@ -114,7 +118,17 @@ bool HardwareInterface ::prepareSwitch(const std::list<hardware_interface::Contr
void HardwareInterface ::doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list, void HardwareInterface ::doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list) const std::list<hardware_interface::ControllerInfo>& stop_list)
{ {
// TODO: Implement position_controller_running_ = false;
for (auto& controller_it : start_list)
{
for (auto& resource_it : controller_it.claimed_resources)
{
if (resource_it.hardware_interface == "hardware_interface::PositionJointInterface")
{
position_controller_running_ = true;
}
}
}
} }
const uint32_t HardwareInterface ::getControlFrequency() const const uint32_t HardwareInterface ::getControlFrequency() const