Skip to content

Commit 5bd5767

Browse files
committed
add a goal pose subscriber in admittance controller
1 parent 3778da6 commit 5bd5767

File tree

2 files changed

+30
-10
lines changed

2 files changed

+30
-10
lines changed

admittance_controller/include/admittance_controller/admittance_controller.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -133,17 +133,22 @@ 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::Pose>::SharedPtr
137+
input_goal_pose_subscriber_;
136138
rclcpp::Publisher<control_msgs::msg::AdmittanceControllerState>::SharedPtr s_publisher_;
137139

138140
// admittance parameters
139141
std::shared_ptr<admittance_controller::ParamListener> parameter_handler_;
140142

141143
// ROS messages
142144
std::shared_ptr<trajectory_msgs::msg::JointTrajectoryPoint> joint_command_msg_;
145+
std::shared_ptr<geometry_msgs::msg::Pose> goal_pose_msg_;
143146

144147
// real-time buffer
145148
realtime_tools::RealtimeBuffer<std::shared_ptr<trajectory_msgs::msg::JointTrajectoryPoint>>
146149
input_joint_command_;
150+
realtime_tools::RealtimeBuffer<std::shared_ptr<geometry_msgs::msg::Pose>>
151+
input_goal_pose_;
147152
std::unique_ptr<realtime_tools::RealtimePublisher<ControllerStateMsg>> state_publisher_;
148153

149154
trajectory_msgs::msg::JointTrajectoryPoint last_commanded_;

admittance_controller/src/admittance_controller.cpp

Lines changed: 25 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -265,6 +265,14 @@ controller_interface::CallbackReturn AdmittanceController::on_configure(
265265
input_joint_command_subscriber_ =
266266
get_node()->create_subscription<trajectory_msgs::msg::JointTrajectoryPoint>(
267267
"~/joint_references", rclcpp::SystemDefaultsQoS(), joint_command_callback);
268+
269+
auto goal_pose_callback =
270+
[this](const std::shared_ptr<geometry_msgs::msg::Pose> msg)
271+
{ input_goal_pose_.writeFromNonRT(msg); };
272+
input_goal_pose_subscriber_ =
273+
get_node()->create_subscription<geometry_msgs::msg::Pose>(
274+
"~/goal_pose", rclcpp::SystemDefaultsQoS(), goal_pose_callback);
275+
268276
s_publisher_ = get_node()->create_publisher<control_msgs::msg::AdmittanceControllerState>(
269277
"~/status", rclcpp::SystemDefaultsQoS());
270278
state_publisher_ =
@@ -347,6 +355,14 @@ controller_interface::CallbackReturn AdmittanceController::on_activate(
347355
}
348356
}
349357

358+
goal_pose_msg_ = std::make_shared<geometry_msgs::msg::Pose>(
359+
admittance_->initialize_goal_pose(joint_state_)
360+
);
361+
if(!goal_pose_msg_){
362+
RCLCPP_ERROR(get_node()->get_logger(), "Failed to initialize goal_pose from current joint positions.\n");
363+
return controller_interface::CallbackReturn::ERROR;
364+
}
365+
350366
// Use current joint_state as a default reference
351367
last_reference_ = joint_state_;
352368
last_commanded_ = joint_state_;
@@ -380,6 +396,14 @@ controller_interface::return_type AdmittanceController::update_reference_from_su
380396
}
381397
}
382398

399+
// after initializing goal_pose_msg_, update it from subscribers only
400+
// if another message exists
401+
if(*input_goal_pose_.readFromRT())
402+
{
403+
goal_pose_msg_ = *input_goal_pose_.readFromRT();
404+
}
405+
406+
383407
return controller_interface::return_type::OK;
384408
}
385409

@@ -404,17 +428,8 @@ controller_interface::return_type AdmittanceController::update_and_write_command
404428
// get all controller inputs
405429
read_state_from_hardware(joint_state_, ft_values_);
406430

407-
auto goal_pose = geometry_msgs::msg::Pose();
408-
/* world-tool0*/
409-
goal_pose.position.x = 1.53;
410-
goal_pose.position.y = 0.9;
411-
goal_pose.position.z = 1.5;
412-
goal_pose.orientation.w = 0.0;
413-
goal_pose.orientation.x = 0.707;
414-
goal_pose.orientation.y = 0.0;
415-
goal_pose.orientation.z = 0.707;
416431
// apply admittance control to reference to determine desired state
417-
admittance_->update(joint_state_, ft_values_, goal_pose, reference_, period, reference_admittance_);
432+
admittance_->update(joint_state_, ft_values_, *goal_pose_msg_, reference_, period, reference_admittance_);
418433

419434
// write calculated values to joint interfaces
420435
write_state_to_hardware(reference_admittance_);

0 commit comments

Comments
 (0)