mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 01:50:46 +02:00
re-added a non-scaled position interface for position controllers
As this interface uses the same joint names as the scaled interface, resourced conflicts are already managed by ros_control's resource claim mechanisms.
This commit is contained in:
@@ -171,8 +171,8 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
|
||||
&joint_velocities_[i], &joint_efforts_[i]));
|
||||
|
||||
// Create joint position control interface
|
||||
// pj_interface_.registerHandle(
|
||||
// hardware_interface::JointHandle(js_interface_.getHandle(joint_names_[i]), &joint_position_command_[i]));
|
||||
pj_interface_.registerHandle(
|
||||
hardware_interface::JointHandle(js_interface_.getHandle(joint_names_[i]), &joint_position_command_[i]));
|
||||
spj_interface_.registerHandle(ur_controllers::ScaledJointHandle(
|
||||
js_interface_.getHandle(joint_names_[i]), &joint_position_command_[i], &speed_scaling_combined_));
|
||||
}
|
||||
@@ -186,7 +186,7 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
|
||||
// Register interfaces
|
||||
registerInterface(&js_interface_);
|
||||
registerInterface(&spj_interface_);
|
||||
// registerInterface(&pj_interface_);
|
||||
registerInterface(&pj_interface_);
|
||||
registerInterface(&speedsc_interface_);
|
||||
registerInterface(&fts_interface_);
|
||||
|
||||
@@ -317,6 +317,10 @@ void HardwareInterface ::doSwitch(const std::list<hardware_interface::Controller
|
||||
{
|
||||
position_controller_running_ = true;
|
||||
}
|
||||
if (resource_it.hardware_interface == "hardware_interface::PositionJointInterface")
|
||||
{
|
||||
position_controller_running_ = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user