Skip to content

Commit

Permalink
Merge branch 'master' into ci/clang
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored Dec 9, 2024
2 parents 4016e26 + 330b9e4 commit 7fad712
Show file tree
Hide file tree
Showing 6 changed files with 51 additions and 2 deletions.
3 changes: 2 additions & 1 deletion .github/mergify.yml
Original file line number Diff line number Diff line change
Expand Up @@ -23,14 +23,15 @@ pull_request_rules:
- author=mergify[bot]
actions:
comment:
message: This pull request is in conflict. Could you fix it @bmagyar @destogl @christophfroehlich?
message: This pull request is in conflict. Could you fix it @bmagyar @destogl @christophfroehlich @saikishor?

- name: development targets master branch
conditions:
- base!=master
- author!=bmagyar
- author!=destogl
- author!=christophfroehlich
- author!=saikishor
- author!=mergify[bot]
- author!=dependabot[bot]
actions:
Expand Down
3 changes: 3 additions & 0 deletions admittance_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,9 @@ Topics
~/joint_references (input topic) [trajectory_msgs::msg::JointTrajectoryPoint]
Target joint commands when controller is not in chained mode.

~/wrench_reference (input topic) [geometry_msgs::msg::WrenchStamped]
Target wrench offset (WrenchStamped has to be in the frame of the FT-sensor).

~/state (output topic) [control_msgs::msg::AdmittanceControllerState]
Topic publishing internal states.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,8 @@ class AdmittanceController : public controller_interface::ChainableControllerInt
// ROS subscribers
rclcpp::Subscription<trajectory_msgs::msg::JointTrajectoryPoint>::SharedPtr
input_joint_command_subscriber_;
rclcpp::Subscription<geometry_msgs::msg::WrenchStamped>::SharedPtr
input_wrench_command_subscriber_;
rclcpp::Publisher<control_msgs::msg::AdmittanceControllerState>::SharedPtr s_publisher_;

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

trajectory_msgs::msg::JointTrajectoryPoint last_commanded_;
Expand Down
40 changes: 39 additions & 1 deletion admittance_controller/src/admittance_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,23 @@

namespace admittance_controller
{

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;
}

controller_interface::CallbackReturn AdmittanceController::on_init()
{
// initialize controller config
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -265,6 +283,24 @@ 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 &&
!msg.header.frame_id.empty())
{
RCLCPP_ERROR_STREAM(
get_node()->get_logger(), "Ignoring wrench reference as it is on the wrong frame: "
<< msg.header.frame_id << ". Expected reference frame: "
<< admittance_->parameters_.ft_sensor.frame.id);
return;
}
input_wrench_command_.writeFromNonRT(msg);
});
s_publisher_ = get_node()->create_publisher<control_msgs::msg::AdmittanceControllerState>(
"~/status", rclcpp::SystemDefaultsQoS());
state_publisher_ =
Expand Down Expand Up @@ -398,8 +434,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_);
Expand Down
1 change: 1 addition & 0 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ This list summarizes the changes between Iron (previous) and Jazzy (current) rel
admittance_controller
************************
* Remove ``robot_description`` parameter from parameter YAML, because it is not used at all (`#963 <https://github.com/ros-controls/ros2_controllers/pull/963>`_).
* 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>`_).

diff_drive_controller
*****************************
Expand Down
3 changes: 3 additions & 0 deletions ros2_controllers/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,14 @@
<exec_depend>force_torque_sensor_broadcaster</exec_depend>
<exec_depend>forward_command_controller</exec_depend>
<exec_depend>gpio_controllers</exec_depend>
<exec_depend>gripper_controllers</exec_depend>
<exec_depend>imu_sensor_broadcaster</exec_depend>
<exec_depend>joint_state_broadcaster</exec_depend>
<exec_depend>joint_trajectory_controller</exec_depend>
<exec_depend>mecanum_drive_controller</exec_depend>
<exec_depend>parallel_gripper_controller</exec_depend>
<exec_depend>pid_controller</exec_depend>
<exec_depend>pose_broadcaster</exec_depend>
<exec_depend>position_controllers</exec_depend>
<exec_depend>range_sensor_broadcaster</exec_depend>
<exec_depend>steering_controllers_library</exec_depend>
Expand Down

0 comments on commit 7fad712

Please sign in to comment.