Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -178,6 +178,8 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
urcl::vector6d_t urcl_joint_efforts_;
urcl::vector6d_t urcl_ft_sensor_measurements_;
urcl::vector6d_t urcl_tcp_pose_;
urcl::vector6d_t urcl_target_tcp_pose_;
urcl::vector6d_t tcp_offset_;
tf2::Quaternion tcp_rotation_quat_;
Quaternion tcp_rotation_buffer;

Expand Down Expand Up @@ -205,10 +207,6 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
std::bitset<4> robot_status_bits_;
std::bitset<11> safety_status_bits_;

// transform stuff
tf2::Vector3 tcp_force_;
tf2::Vector3 tcp_torque_;

// asynchronous commands
std::array<double, 18> standard_dig_out_bits_cmd_;
std::array<double, 2> standard_analog_output_cmd_;
Expand Down
2 changes: 2 additions & 0 deletions ur_robot_driver/resources/rtde_output_recipe.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ target_speed_fraction
runtime_state
actual_TCP_force
actual_TCP_pose
target_TCP_pose
actual_digital_input_bits
actual_digital_output_bits
standard_analog_input0
Expand All @@ -25,3 +26,4 @@ safety_mode
robot_status_bits
safety_status_bits
actual_current
tcp_offset
46 changes: 35 additions & 11 deletions ur_robot_driver/src/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -676,6 +676,7 @@
readData(data_pkg, "runtime_state", runtime_state_);
readData(data_pkg, "actual_TCP_force", urcl_ft_sensor_measurements_);
readData(data_pkg, "actual_TCP_pose", urcl_tcp_pose_);
readData(data_pkg, "target_TCP_pose", urcl_target_tcp_pose_);

Check warning on line 679 in ur_robot_driver/src/hardware_interface.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/hardware_interface.cpp#L679

Added line #L679 was not covered by tests
readData(data_pkg, "standard_analog_input0", standard_analog_input_[0]);
readData(data_pkg, "standard_analog_input1", standard_analog_input_[1]);
readData(data_pkg, "standard_analog_output0", standard_analog_output_[0]);
Expand All @@ -694,6 +695,7 @@
readBitsetData<uint64_t>(data_pkg, "actual_digital_output_bits", actual_dig_out_bits_);
readBitsetData<uint32_t>(data_pkg, "analog_io_types", analog_io_types_);
readBitsetData<uint32_t>(data_pkg, "tool_analog_input_types", tool_analog_input_types_);
readData(data_pkg, "tcp_offset", tcp_offset_);

Check warning on line 698 in ur_robot_driver/src/hardware_interface.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/hardware_interface.cpp#L698

Added line #L698 was not covered by tests

// required transforms
extractToolPose();
Expand Down Expand Up @@ -934,17 +936,39 @@

void URPositionHardwareInterface::transformForceTorque()
{
// imported from ROS1 driver - hardware_interface.cpp#L867-L876
tcp_force_.setValue(urcl_ft_sensor_measurements_[0], urcl_ft_sensor_measurements_[1],
urcl_ft_sensor_measurements_[2]);
tcp_torque_.setValue(urcl_ft_sensor_measurements_[3], urcl_ft_sensor_measurements_[4],
urcl_ft_sensor_measurements_[5]);

tcp_force_ = tf2::quatRotate(tcp_rotation_quat_.inverse(), tcp_force_);
tcp_torque_ = tf2::quatRotate(tcp_rotation_quat_.inverse(), tcp_torque_);

urcl_ft_sensor_measurements_ = { tcp_force_.x(), tcp_force_.y(), tcp_force_.z(),
tcp_torque_.x(), tcp_torque_.y(), tcp_torque_.z() };
KDL::Wrench ft(
KDL::Vector(urcl_ft_sensor_measurements_[0], urcl_ft_sensor_measurements_[1], urcl_ft_sensor_measurements_[2]),
KDL::Vector(urcl_ft_sensor_measurements_[3], urcl_ft_sensor_measurements_[4], urcl_ft_sensor_measurements_[5]));

Check warning on line 941 in ur_robot_driver/src/hardware_interface.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/hardware_interface.cpp#L939-L941

Added lines #L939 - L941 were not covered by tests
if (ur_driver_->getVersion().major >= 5) // e-Series
{
// Setup necessary frames
KDL::Vector vec = KDL::Vector(tcp_offset_[3], tcp_offset_[4], tcp_offset_[5]);
double angle = vec.Normalize();
KDL::Rotation rotation = KDL::Rotation::Rot(vec, angle);
KDL::Frame flange_to_tcp = KDL::Frame(rotation, KDL::Vector(tcp_offset_[0], tcp_offset_[1], tcp_offset_[2]));

Check warning on line 948 in ur_robot_driver/src/hardware_interface.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/hardware_interface.cpp#L945-L948

Added lines #L945 - L948 were not covered by tests

vec = KDL::Vector(urcl_target_tcp_pose_[3], urcl_target_tcp_pose_[4], urcl_target_tcp_pose_[5]);
angle = vec.Normalize();
rotation = KDL::Rotation::Rot(vec, angle);
KDL::Frame base_to_tcp =
KDL::Frame(rotation, KDL::Vector(urcl_target_tcp_pose_[0], urcl_target_tcp_pose_[1], urcl_target_tcp_pose_[2]));

Check warning on line 954 in ur_robot_driver/src/hardware_interface.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/hardware_interface.cpp#L950-L954

Added lines #L950 - L954 were not covered by tests
// Calculate transformation from base to flange, see calculation details below
// `base_to_tcp = base_to_flange*flange_to_tcp -> base_to_flange = base_to_tcp * inv(flange_to_tcp)`
KDL::Frame base_to_flange = base_to_tcp * flange_to_tcp.Inverse();

Check warning on line 957 in ur_robot_driver/src/hardware_interface.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/hardware_interface.cpp#L957

Added line #L957 was not covered by tests
// rotate f/t sensor output back to the flange frame
ft = base_to_flange.M.Inverse() * ft;

Check warning on line 959 in ur_robot_driver/src/hardware_interface.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/hardware_interface.cpp#L959

Added line #L959 was not covered by tests

// Transform the wrench to the tcp frame
ft = flange_to_tcp * ft;

Check warning on line 962 in ur_robot_driver/src/hardware_interface.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/hardware_interface.cpp#L962

Added line #L962 was not covered by tests
} else { // CB3
KDL::Vector vec = KDL::Vector(urcl_target_tcp_pose_[3], urcl_target_tcp_pose_[4], urcl_target_tcp_pose_[5]);
double angle = vec.Normalize();
KDL::Rotation base_to_tcp_rot = KDL::Rotation::Rot(vec, angle);

Check warning on line 966 in ur_robot_driver/src/hardware_interface.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/hardware_interface.cpp#L964-L966

Added lines #L964 - L966 were not covered by tests

// rotate f/t sensor output back to the tcp frame
ft = base_to_tcp_rot.Inverse() * ft;

Check warning on line 969 in ur_robot_driver/src/hardware_interface.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/hardware_interface.cpp#L969

Added line #L969 was not covered by tests
}
urcl_ft_sensor_measurements_ = { ft[0], ft[1], ft[2], ft[3], ft[4], ft[5] };

Check warning on line 971 in ur_robot_driver/src/hardware_interface.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/hardware_interface.cpp#L971

Added line #L971 was not covered by tests
}

void URPositionHardwareInterface::extractToolPose()
Expand Down
Loading