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

Added interface for force-torque sensor

Closes #20
This commit is contained in:
Felix Mauch
2019-06-05 13:29:45 +02:00
parent 38f1661617
commit 45430ec0e7
4 changed files with 17 additions and 1 deletions

View File

@@ -70,12 +70,14 @@ protected:
hardware_interface::PositionJointInterface pj_interface_; hardware_interface::PositionJointInterface pj_interface_;
ur_controllers::SpeedScalingInterface speedsc_interface_; ur_controllers::SpeedScalingInterface speedsc_interface_;
// hardware_interface::VelocityJointInterface vj_interface_; // hardware_interface::VelocityJointInterface vj_interface_;
hardware_interface::ForceTorqueSensorInterface fts_interface_;
vector6d_t joint_position_command_; vector6d_t joint_position_command_;
// std::vector<double> joint_velocity_command_; // std::vector<double> joint_velocity_command_;
vector6d_t joint_positions_; vector6d_t joint_positions_;
vector6d_t joint_velocities_; vector6d_t joint_velocities_;
vector6d_t joint_efforts_; vector6d_t joint_efforts_;
vector6d_t fts_measurements_;
double speed_scaling_; double speed_scaling_;
double target_speed_fraction_; double target_speed_fraction_;
double speed_scaling_combined_; double speed_scaling_combined_;
@@ -86,6 +88,8 @@ protected:
PausingState pausing_state_; PausingState pausing_state_;
double pausing_ramp_up_increment_; double pausing_ramp_up_increment_;
std::string tcp_link_;
}; };
} // namespace ur_driver } // namespace ur_driver

View File

@@ -16,7 +16,7 @@
<arg name="base_frame" default="$(arg prefix)base" /> <arg name="base_frame" default="$(arg prefix)base" />
<arg name="tool_frame" default="$(arg prefix)tool0_controller" /> <arg name="tool_frame" default="$(arg prefix)tool0_controller" />
<arg name="shutdown_on_disconnect" default="true" /> <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 speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default=""/> <arg name="stopped_controllers" default=""/>
<arg name="urscript_file" default="$(find ur_rtde_driver)/resources/servoj.urscript"/> <arg name="urscript_file" default="$(find ur_rtde_driver)/resources/servoj.urscript"/>
<arg name="rtde_recipe_file" default="$(find ur_rtde_driver)/resources/rtde_recipe.txt"/> <arg name="rtde_recipe_file" default="$(find ur_rtde_driver)/resources/rtde_recipe.txt"/>

View File

@@ -4,3 +4,4 @@ actual_qd
speed_scaling speed_scaling
target_speed_fraction target_speed_fraction
runtime_state runtime_state
actual_TCP_force

View File

@@ -61,6 +61,8 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
return false; return false;
} }
tcp_link_ = robot_hw_nh.param<std::string>("tcp_link", "tool0");
ROS_INFO_STREAM("Initializing urdriver"); ROS_INFO_STREAM("Initializing urdriver");
ur_driver_.reset(new UrDriver(robot_ip, script_filename, recipe_filename)); ur_driver_.reset(new UrDriver(robot_ip, script_filename, recipe_filename));
@@ -90,11 +92,15 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
speedsc_interface_.registerHandle( speedsc_interface_.registerHandle(
ur_controllers::SpeedScalingHandle("speed_scaling_factor", &speed_scaling_combined_)); ur_controllers::SpeedScalingHandle("speed_scaling_factor", &speed_scaling_combined_));
fts_interface_.registerHandle(hardware_interface::ForceTorqueSensorHandle(
"wrench", tcp_link_, fts_measurements_.begin(), fts_measurements_.begin() + 3));
// Register interfaces // Register interfaces
registerInterface(&js_interface_); registerInterface(&js_interface_);
registerInterface(&spj_interface_); registerInterface(&spj_interface_);
// registerInterface(&pj_interface_); // registerInterface(&pj_interface_);
registerInterface(&speedsc_interface_); registerInterface(&speedsc_interface_);
registerInterface(&fts_interface_);
ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_rtde_driver hardware_interface"); ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_rtde_driver hardware_interface");
@@ -131,6 +137,11 @@ void HardwareInterface ::read(const ros::Time& time, const ros::Duration& period
// This throwing should never happen unless misconfigured // 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!"); throw std::runtime_error("Did not find speed_scaling in data sent from robot. This should not happen!");
} }
if (!data_pkg->getData("actual_TCP_force", fts_measurements_))
{
// This throwing should never happen unless misconfigured
throw std::runtime_error("Did not find actual_TCP_force in data sent from robot. This should not happen!");
}
// pausing state follows runtime state when pausing // pausing state follows runtime state when pausing
if (runtime_state_ == static_cast<uint32_t>(rtde_interface::RUNTIME_STATE::PAUSED)) if (runtime_state_ == static_cast<uint32_t>(rtde_interface::RUNTIME_STATE::PAUSED))