|
27 | 27 |
|
28 | 28 | namespace admittance_controller |
29 | 29 | { |
| 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 | + |
30 | 47 | controller_interface::CallbackReturn AdmittanceController::on_init() |
31 | 48 | { |
32 | 49 | // initialize controller config |
@@ -116,6 +133,7 @@ AdmittanceController::on_export_reference_interfaces() |
116 | 133 | reference_interfaces_.resize(num_chainable_interfaces, std::numeric_limits<double>::quiet_NaN()); |
117 | 134 | position_reference_ = {}; |
118 | 135 | velocity_reference_ = {}; |
| 136 | + input_wrench_command_.reset(); |
119 | 137 |
|
120 | 138 | // assign reference interfaces |
121 | 139 | auto index = 0ul; |
@@ -265,6 +283,24 @@ controller_interface::CallbackReturn AdmittanceController::on_configure( |
265 | 283 | input_joint_command_subscriber_ = |
266 | 284 | get_node()->create_subscription<trajectory_msgs::msg::JointTrajectoryPoint>( |
267 | 285 | "~/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 | + }); |
268 | 304 | s_publisher_ = get_node()->create_publisher<control_msgs::msg::AdmittanceControllerState>( |
269 | 305 | "~/status", rclcpp::SystemDefaultsQoS()); |
270 | 306 | state_publisher_ = |
@@ -398,8 +434,10 @@ controller_interface::return_type AdmittanceController::update_and_write_command |
398 | 434 | // get all controller inputs |
399 | 435 | read_state_from_hardware(joint_state_, ft_values_); |
400 | 436 |
|
| 437 | + auto offsetted_ft_values = add_wrenches(ft_values_, input_wrench_command_.readFromRT()->wrench); |
| 438 | + |
401 | 439 | // 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_); |
403 | 441 |
|
404 | 442 | // write calculated values to joint interfaces |
405 | 443 | write_state_to_hardware(reference_admittance_); |
|
0 commit comments