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
10 changes: 10 additions & 0 deletions ur_robot_driver/config/ur_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,9 @@ controller_manager:
forward_position_controller:
type: position_controllers/JointGroupPositionController

tcp_pose_broadcaster:
type: pose_broadcaster/PoseBroadcaster

ur_configuration_controller:
type: ur_controllers/URConfigurationController

Expand Down Expand Up @@ -130,3 +133,10 @@ forward_position_controller:
- $(var tf_prefix)wrist_1_joint
- $(var tf_prefix)wrist_2_joint
- $(var tf_prefix)wrist_3_joint

tcp_pose_broadcaster:
ros__parameters:
frame_id: $(var tf_prefix)base
pose_name: $(var tf_prefix)tcp_pose
tf:
child_frame_id: $(var tf_prefix)tool0_controller
25 changes: 24 additions & 1 deletion ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,28 @@ enum StoppingInterface
STOP_VELOCITY
};

// We define our own quaternion to use it as a buffer, since we need to pass pointers to the state
// interfaces.
struct Quaternion
{
Quaternion() : x(0), y(0), z(0), w(0)
{
}

void set(const tf2::Quaternion& q)
{
x = q.x();
y = q.y();
z = q.z();
w = q.w();
}

double x;
double y;
double z;
double w;
};

/*!
* \brief The HardwareInterface class handles the interface between the ROS system and the main
* driver. It contains the read and write methods of the main control loop and registers various ROS
Expand Down Expand Up @@ -144,6 +166,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_;
tf2::Quaternion tcp_rotation_quat_;
Quaternion tcp_rotation_buffer;

bool packet_read_;

Expand Down Expand Up @@ -172,7 +196,6 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
// transform stuff
tf2::Vector3 tcp_force_;
tf2::Vector3 tcp_torque_;
geometry_msgs::msg::TransformStamped tcp_transform_;

// asynchronous commands
std::array<double, 18> standard_dig_out_bits_cmd_;
Expand Down
2 changes: 2 additions & 0 deletions ur_robot_driver/launch/ur_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -295,6 +295,7 @@ def launch_setup(context, *args, **kwargs):
"force_torque_sensor_broadcaster",
"joint_state_broadcaster",
"speed_scaling_state_broadcaster",
"tcp_pose_broadcaster",
"ur_configuration_controller",
]
},
Expand Down Expand Up @@ -338,6 +339,7 @@ def controller_spawner(controllers, active=True):
"io_and_status_controller",
"speed_scaling_state_broadcaster",
"force_torque_sensor_broadcaster",
"tcp_pose_broadcaster",
"ur_configuration_controller",
]
controllers_inactive = ["forward_position_controller"]
Expand Down
1 change: 1 addition & 0 deletions ur_robot_driver/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@
<exec_depend>joint_trajectory_controller</exec_depend>
<exec_depend>launch</exec_depend>
<exec_depend>launch_ros</exec_depend>
<exec_depend>pose_broadcaster</exec_depend>
<exec_depend>position_controllers</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>ros2_controllers_test_nodes</exec_depend>
Expand Down
43 changes: 28 additions & 15 deletions ur_robot_driver/src/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,9 +170,14 @@ std::vector<hardware_interface::StateInterface> URPositionHardwareInterface::exp
&speed_scaling_combined_));

for (auto& sensor : info_.sensors) {
for (uint j = 0; j < sensor.state_interfaces.size(); ++j) {
state_interfaces.emplace_back(hardware_interface::StateInterface(sensor.name, sensor.state_interfaces[j].name,
&urcl_ft_sensor_measurements_[j]));
if (sensor.name == tf_prefix + "tcp_fts_sensor") {
const std::vector<std::string> fts_names = {
"force.x", "force.y", "force.z", "torque.x", "torque.y", "torque.z"
};
for (uint j = 0; j < 6; ++j) {
state_interfaces.emplace_back(
hardware_interface::StateInterface(sensor.name, fts_names[j], &urcl_ft_sensor_measurements_[j]));
}
}
}

Expand Down Expand Up @@ -232,6 +237,21 @@ std::vector<hardware_interface::StateInterface> URPositionHardwareInterface::exp
state_interfaces.emplace_back(
hardware_interface::StateInterface(tf_prefix + "gpio", "program_running", &robot_program_running_copy_));

state_interfaces.emplace_back(
hardware_interface::StateInterface(tf_prefix + "tcp_pose", "position.x", &urcl_tcp_pose_[0]));
state_interfaces.emplace_back(
hardware_interface::StateInterface(tf_prefix + "tcp_pose", "position.y", &urcl_tcp_pose_[1]));
state_interfaces.emplace_back(
hardware_interface::StateInterface(tf_prefix + "tcp_pose", "position.z", &urcl_tcp_pose_[2]));
state_interfaces.emplace_back(
hardware_interface::StateInterface(tf_prefix + "tcp_pose", "orientation.x", &tcp_rotation_buffer.x));
state_interfaces.emplace_back(
hardware_interface::StateInterface(tf_prefix + "tcp_pose", "orientation.y", &tcp_rotation_buffer.y));
state_interfaces.emplace_back(
hardware_interface::StateInterface(tf_prefix + "tcp_pose", "orientation.z", &tcp_rotation_buffer.z));
state_interfaces.emplace_back(
hardware_interface::StateInterface(tf_prefix + "tcp_pose", "orientation.w", &tcp_rotation_buffer.w));

state_interfaces.emplace_back(hardware_interface::StateInterface(
tf_prefix + "get_robot_software_version", "get_version_major", &get_robot_software_version_major_));

Expand Down Expand Up @@ -796,10 +816,8 @@ void URPositionHardwareInterface::transformForceTorque()
tcp_torque_.setValue(urcl_ft_sensor_measurements_[3], urcl_ft_sensor_measurements_[4],
urcl_ft_sensor_measurements_[5]);

tf2::Quaternion rotation_quat;
tf2::fromMsg(tcp_transform_.transform.rotation, rotation_quat);
tcp_force_ = tf2::quatRotate(rotation_quat.inverse(), tcp_force_);
tcp_torque_ = tf2::quatRotate(rotation_quat.inverse(), tcp_torque_);
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() };
Expand All @@ -812,17 +830,12 @@ void URPositionHardwareInterface::extractToolPose()
std::sqrt(std::pow(urcl_tcp_pose_[3], 2) + std::pow(urcl_tcp_pose_[4], 2) + std::pow(urcl_tcp_pose_[5], 2));

tf2::Vector3 rotation_vec(urcl_tcp_pose_[3], urcl_tcp_pose_[4], urcl_tcp_pose_[5]);
tf2::Quaternion rotation;
if (tcp_angle > 1e-16) {
rotation.setRotation(rotation_vec.normalized(), tcp_angle);
tcp_rotation_quat_.setRotation(rotation_vec.normalized(), tcp_angle);
} else {
rotation.setValue(0.0, 0.0, 0.0, 1.0); // default Quaternion is 0,0,0,0 which is invalid
tcp_rotation_quat_.setValue(0.0, 0.0, 0.0, 1.0); // default Quaternion is 0,0,0,0 which is invalid
}
tcp_transform_.transform.translation.x = urcl_tcp_pose_[0];
tcp_transform_.transform.translation.y = urcl_tcp_pose_[1];
tcp_transform_.transform.translation.z = urcl_tcp_pose_[2];

tcp_transform_.transform.rotation = tf2::toMsg(rotation);
tcp_rotation_buffer.set(tcp_rotation_quat_);
}

hardware_interface::return_type URPositionHardwareInterface::prepare_command_mode_switch(
Expand Down
Loading