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

added ur_controllers package

This commit is contained in:
Felix Mauch
2019-04-17 17:04:01 +02:00
parent be5553648d
commit f38ec92389
16 changed files with 1022 additions and 11 deletions

View File

@@ -30,7 +30,8 @@ speed_scaling_state_controller:
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
pos_based_pos_traj_controller:
type: position_controllers/JointTrajectoryController
#type: position_controllers/JointTrajectoryController
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint

View File

@@ -34,6 +34,7 @@
#include <algorithm>
#include <ur_controllers/speed_scaling_interface.h>
#include <ur_controllers/scaled_joint_command_interface.h>
#include "ur_rtde_driver/ur/ur_driver.h"
@@ -58,6 +59,7 @@ protected:
std::unique_ptr<UrDriver> ur_driver_;
hardware_interface::JointStateInterface js_interface_;
ur_controllers::ScaledPositionJointInterface spj_interface_;
hardware_interface::PositionJointInterface pj_interface_;
ur_controllers::SpeedScalingInterface speedsc_interface_;
// hardware_interface::VelocityJointInterface vj_interface_;
@@ -67,7 +69,9 @@ protected:
vector6d_t joint_positions_;
vector6d_t joint_velocities_;
vector6d_t joint_efforts_;
double speed_scaling_value_;
double speed_scaling_;
double target_speed_fraction_;
double speed_scaling_combined_;
std::vector<std::string> joint_names_;
bool position_controller_running_;

View File

@@ -16,7 +16,7 @@
<arg name="base_frame" default="$(arg prefix)base" />
<arg name="tool_frame" default="$(arg prefix)tool0_controller" />
<arg name="shutdown_on_disconnect" default="true" />
<arg name="controllers" default="joint_state_controller pos_based_pos_traj_controller speed_scaling_state_controller"/>
<arg name="controllers" default="joint_state_controller pos_based_pos_traj_controller"/>
<arg name="stopped_controllers" default=""/>
<!-- robot model -->
<include file="$(find ur_description)/launch/ur10_upload.launch">

View File

@@ -60,22 +60,26 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
// Create ros_control interfaces
for (std::size_t i = 0; i < joint_positions_.size(); ++i)
{
ROS_INFO_STREAM("Registing handles for joint " << joint_names_[i]);
// Create joint state interface for all joints
js_interface_.registerHandle(hardware_interface::JointStateHandle(joint_names_[i], &joint_positions_[i],
&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_));
}
speedsc_interface_.registerHandle(
ur_controllers::SpeedScalingHandle("speed_scaling_factor", &speed_scaling_combined_));
// speedsc_interface_.registerHandle(
// ur_controllers::SpeedScalingHandle("speed_scaling_factor", &speed_scaling_combined_));
// Register interfaces
registerInterface(&js_interface_);
registerInterface(&pj_interface_);
registerInterface(&speedsc_interface_);
registerInterface(&spj_interface_);
// registerInterface(&pj_interface_);
// registerInterface(&speedsc_interface_);
ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_rtde_driver hardware_interface");
@@ -97,11 +101,18 @@ void HardwareInterface ::read(const ros::Time& time, const ros::Duration& period
// This throwing should never happen unless misconfigured
throw std::runtime_error("Did not find joint velocity in data sent from robot. This should not happen!");
}
if (!data_pkg->getData("target_speed_fraction", speed_scaling_value_))
if (!data_pkg->getData("target_speed_fraction", target_speed_fraction_))
{
// This throwing should never happen unless misconfigured
throw std::runtime_error("Did not find target_speed_fraction_ in data sent from robot. This should not happen!");
}
if (!data_pkg->getData("speed_scaling", speed_scaling_))
{
// This throwing should never happen unless misconfigured
throw std::runtime_error("Did not find speed_scaling in data sent from robot. This should not happen!");
}
speed_scaling_combined_ = speed_scaling_ * target_speed_fraction_;
}
else
{
@@ -113,6 +124,7 @@ void HardwareInterface ::write(const ros::Time& time, const ros::Duration& perio
{
if (position_controller_running_)
{
// ROS_INFO_STREAM("Writing command: " << joint_position_command_);
ur_driver_->writeJointCommand(joint_position_command_);
}
}
@@ -132,7 +144,7 @@ void HardwareInterface ::doSwitch(const std::list<hardware_interface::Controller
{
for (auto& resource_it : controller_it.claimed_resources)
{
if (resource_it.hardware_interface == "hardware_interface::PositionJointInterface")
if (resource_it.hardware_interface == "ur_controllers::ScaledPositionJointInterface")
{
position_controller_running_ = true;
}