-
Notifications
You must be signed in to change notification settings - Fork 451
Add wrench offset for admittance controller #1249
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from 2 commits
30b4407
8335398
64eaea4
e260c69
9bb9435
86115e5
f9a3087
06ff415
45f5315
280b339
015decf
2162875
7640e19
7aa9691
9509e53
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -27,6 +27,23 @@ | |
|
|
||
| namespace admittance_controller | ||
| { | ||
|
|
||
| static geometry_msgs::msg::Wrench add_wrenches( | ||
| const geometry_msgs::msg::Wrench & a, const geometry_msgs::msg::Wrench & b) | ||
| { | ||
| geometry_msgs::msg::Wrench res; | ||
|
|
||
| res.force.x = a.force.x + b.force.x; | ||
| res.force.y = a.force.y + b.force.y; | ||
| res.force.z = a.force.z + b.force.z; | ||
|
|
||
| res.torque.x = a.torque.x + b.torque.x; | ||
| res.torque.y = a.torque.y + b.torque.y; | ||
| res.torque.z = a.torque.z + b.torque.z; | ||
|
|
||
| return res; | ||
| } | ||
|
|
||
firesurfer marked this conversation as resolved.
Show resolved
Hide resolved
|
||
| controller_interface::CallbackReturn AdmittanceController::on_init() | ||
| { | ||
| // initialize controller config | ||
|
|
@@ -116,6 +133,7 @@ AdmittanceController::on_export_reference_interfaces() | |
| reference_interfaces_.resize(num_chainable_interfaces, std::numeric_limits<double>::quiet_NaN()); | ||
| position_reference_ = {}; | ||
| velocity_reference_ = {}; | ||
| input_wrench_command_.reset(); | ||
|
|
||
| // assign reference interfaces | ||
| auto index = 0ul; | ||
|
|
@@ -265,6 +283,20 @@ controller_interface::CallbackReturn AdmittanceController::on_configure( | |
| input_joint_command_subscriber_ = | ||
| get_node()->create_subscription<trajectory_msgs::msg::JointTrajectoryPoint>( | ||
| "~/joint_references", rclcpp::SystemDefaultsQoS(), joint_command_callback); | ||
|
|
||
| input_wrench_command_subscriber_ = | ||
| get_node()->create_subscription<geometry_msgs::msg::WrenchStamped>( | ||
| "~/wrench_reference", rclcpp::SystemDefaultsQoS(), | ||
| [&](const geometry_msgs::msg::WrenchStamped & msg) | ||
| { | ||
| if (msg.header.frame_id != admittance_->parameters_.ft_sensor.frame.id) | ||
firesurfer marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| { | ||
| RCLCPP_ERROR_STREAM( | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Why don't we transform the wrench if it is in another frame to the sensor frame?
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I had some very weird results in the past when transforming wrenches with TF (e.g. non zero torques afterwards when only forces where given). Additionally I don't think we have a tf buffer/listener in the controller at the moment and why add this additional overhead? |
||
| get_node()->get_logger(), "Ignoring wrench reference as it is on the wrong frame"); | ||
firesurfer marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| return; | ||
firesurfer marked this conversation as resolved.
Show resolved
Hide resolved
|
||
| } | ||
| input_wrench_command_.writeFromNonRT(msg); | ||
| }); | ||
| s_publisher_ = get_node()->create_publisher<control_msgs::msg::AdmittanceControllerState>( | ||
| "~/status", rclcpp::SystemDefaultsQoS()); | ||
| state_publisher_ = | ||
|
|
@@ -396,8 +428,10 @@ controller_interface::return_type AdmittanceController::update_and_write_command | |
| // get all controller inputs | ||
| read_state_from_hardware(joint_state_, ft_values_); | ||
|
|
||
| auto offsetted_ft_values = add_wrenches(ft_values_, input_wrench_command_.readFromRT()->wrench); | ||
|
|
||
| // apply admittance control to reference to determine desired state | ||
| admittance_->update(joint_state_, ft_values_, reference_, period, reference_admittance_); | ||
| admittance_->update(joint_state_, offsetted_ft_values, reference_, period, reference_admittance_); | ||
|
|
||
| // write calculated values to joint interfaces | ||
| write_state_to_hardware(reference_admittance_); | ||
|
|
||
Uh oh!
There was an error while loading. Please reload this page.