Skip to content

Commit a6c1c0c

Browse files
authored
Add wrench offset for admittance controller (ros-controls#1249)
1 parent 2c7047e commit a6c1c0c

File tree

4 files changed

+46
-1
lines changed

4 files changed

+46
-1
lines changed

admittance_controller/doc/userdoc.rst

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,9 @@ Topics
3232
~/joint_references (input topic) [trajectory_msgs::msg::JointTrajectoryPoint]
3333
Target joint commands when controller is not in chained mode.
3434

35+
~/wrench_reference (input topic) [geometry_msgs::msg::WrenchStamped]
36+
Target wrench offset (WrenchStamped has to be in the frame of the FT-sensor).
37+
3538
~/state (output topic) [control_msgs::msg::AdmittanceControllerState]
3639
Topic publishing internal states.
3740

admittance_controller/include/admittance_controller/admittance_controller.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -133,6 +133,8 @@ class AdmittanceController : public controller_interface::ChainableControllerInt
133133
// ROS subscribers
134134
rclcpp::Subscription<trajectory_msgs::msg::JointTrajectoryPoint>::SharedPtr
135135
input_joint_command_subscriber_;
136+
rclcpp::Subscription<geometry_msgs::msg::WrenchStamped>::SharedPtr
137+
input_wrench_command_subscriber_;
136138
rclcpp::Publisher<control_msgs::msg::AdmittanceControllerState>::SharedPtr s_publisher_;
137139

138140
// admittance parameters
@@ -144,6 +146,7 @@ class AdmittanceController : public controller_interface::ChainableControllerInt
144146
// real-time buffer
145147
realtime_tools::RealtimeBuffer<std::shared_ptr<trajectory_msgs::msg::JointTrajectoryPoint>>
146148
input_joint_command_;
149+
realtime_tools::RealtimeBuffer<geometry_msgs::msg::WrenchStamped> input_wrench_command_;
147150
std::unique_ptr<realtime_tools::RealtimePublisher<ControllerStateMsg>> state_publisher_;
148151

149152
trajectory_msgs::msg::JointTrajectoryPoint last_commanded_;

admittance_controller/src/admittance_controller.cpp

Lines changed: 39 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,23 @@
2727

2828
namespace admittance_controller
2929
{
30+
31+
geometry_msgs::msg::Wrench add_wrenches(
32+
const geometry_msgs::msg::Wrench & a, const geometry_msgs::msg::Wrench & b)
33+
{
34+
geometry_msgs::msg::Wrench res;
35+
36+
res.force.x = a.force.x + b.force.x;
37+
res.force.y = a.force.y + b.force.y;
38+
res.force.z = a.force.z + b.force.z;
39+
40+
res.torque.x = a.torque.x + b.torque.x;
41+
res.torque.y = a.torque.y + b.torque.y;
42+
res.torque.z = a.torque.z + b.torque.z;
43+
44+
return res;
45+
}
46+
3047
controller_interface::CallbackReturn AdmittanceController::on_init()
3148
{
3249
// initialize controller config
@@ -116,6 +133,7 @@ AdmittanceController::on_export_reference_interfaces()
116133
reference_interfaces_.resize(num_chainable_interfaces, std::numeric_limits<double>::quiet_NaN());
117134
position_reference_ = {};
118135
velocity_reference_ = {};
136+
input_wrench_command_.reset();
119137

120138
// assign reference interfaces
121139
auto index = 0ul;
@@ -265,6 +283,24 @@ controller_interface::CallbackReturn AdmittanceController::on_configure(
265283
input_joint_command_subscriber_ =
266284
get_node()->create_subscription<trajectory_msgs::msg::JointTrajectoryPoint>(
267285
"~/joint_references", rclcpp::SystemDefaultsQoS(), joint_command_callback);
286+
287+
input_wrench_command_subscriber_ =
288+
get_node()->create_subscription<geometry_msgs::msg::WrenchStamped>(
289+
"~/wrench_reference", rclcpp::SystemDefaultsQoS(),
290+
[&](const geometry_msgs::msg::WrenchStamped & msg)
291+
{
292+
if (
293+
msg.header.frame_id != admittance_->parameters_.ft_sensor.frame.id &&
294+
!msg.header.frame_id.empty())
295+
{
296+
RCLCPP_ERROR_STREAM(
297+
get_node()->get_logger(), "Ignoring wrench reference as it is on the wrong frame: "
298+
<< msg.header.frame_id << ". Expected reference frame: "
299+
<< admittance_->parameters_.ft_sensor.frame.id);
300+
return;
301+
}
302+
input_wrench_command_.writeFromNonRT(msg);
303+
});
268304
s_publisher_ = get_node()->create_publisher<control_msgs::msg::AdmittanceControllerState>(
269305
"~/status", rclcpp::SystemDefaultsQoS());
270306
state_publisher_ =
@@ -398,8 +434,10 @@ controller_interface::return_type AdmittanceController::update_and_write_command
398434
// get all controller inputs
399435
read_state_from_hardware(joint_state_, ft_values_);
400436

437+
auto offsetted_ft_values = add_wrenches(ft_values_, input_wrench_command_.readFromRT()->wrench);
438+
401439
// apply admittance control to reference to determine desired state
402-
admittance_->update(joint_state_, ft_values_, reference_, period, reference_admittance_);
440+
admittance_->update(joint_state_, offsetted_ft_values, reference_, period, reference_admittance_);
403441

404442
// write calculated values to joint interfaces
405443
write_state_to_hardware(reference_admittance_);

doc/release_notes.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@ This list summarizes the changes between Iron (previous) and Jazzy (current) rel
77
admittance_controller
88
************************
99
* Remove ``robot_description`` parameter from parameter YAML, because it is not used at all (`#963 <https://github.com/ros-controls/ros2_controllers/pull/963>`_).
10+
* Added ``~/wrench_reference`` input topic which allows to provide a force-torque offset as WrenchStamped (`#1249 <https://github.com/ros-controls/ros2_controllers/pull/1249>`_).
1011

1112
diff_drive_controller
1213
*****************************

0 commit comments

Comments
 (0)