File tree Expand file tree Collapse file tree 4 files changed +13
-14
lines changed
include/admittance_controller Expand file tree Collapse file tree 4 files changed +13
-14
lines changed Original file line number Diff line number Diff line change @@ -133,7 +133,7 @@ class AdmittanceController : public controller_interface::ChainableControllerInt
133
133
// ROS subscribers
134
134
rclcpp::Subscription<trajectory_msgs::msg::JointTrajectoryPoint>::SharedPtr
135
135
input_joint_command_subscriber_;
136
- rclcpp::Subscription<geometry_msgs::msg::Pose >::SharedPtr
136
+ rclcpp::Subscription<geometry_msgs::msg::PoseStamped >::SharedPtr
137
137
input_goal_pose_subscriber_;
138
138
rclcpp::Publisher<control_msgs::msg::AdmittanceControllerState>::SharedPtr s_publisher_;
139
139
@@ -142,12 +142,12 @@ class AdmittanceController : public controller_interface::ChainableControllerInt
142
142
143
143
// ROS messages
144
144
std::shared_ptr<trajectory_msgs::msg::JointTrajectoryPoint> joint_command_msg_;
145
- std::shared_ptr<geometry_msgs::msg::Pose > goal_pose_msg_;
145
+ std::shared_ptr<geometry_msgs::msg::PoseStamped > goal_pose_msg_;
146
146
147
147
// real-time buffer
148
148
realtime_tools::RealtimeBuffer<std::shared_ptr<trajectory_msgs::msg::JointTrajectoryPoint>>
149
149
input_joint_command_;
150
- realtime_tools::RealtimeBuffer<std::shared_ptr<geometry_msgs::msg::Pose >>
150
+ realtime_tools::RealtimeBuffer<std::shared_ptr<geometry_msgs::msg::PoseStamped >>
151
151
input_goal_pose_;
152
152
std::unique_ptr<realtime_tools::RealtimePublisher<ControllerStateMsg>> state_publisher_;
153
153
Original file line number Diff line number Diff line change 30
30
#include " pluginlib/class_loader.hpp"
31
31
#include " trajectory_msgs/msg/joint_trajectory_point.hpp"
32
32
#include " geometry_msgs/msg/pose.hpp"
33
+ #include " geometry_msgs/msg/pose_stamped.hpp"
33
34
34
35
namespace admittance_controller
35
36
{
@@ -119,7 +120,7 @@ class AdmittanceRule
119
120
*/
120
121
bool get_all_transforms (
121
122
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
122
- const geometry_msgs::msg::Pose & reference_pose);
123
+ const geometry_msgs::msg::PoseStamped & reference_pose);
123
124
124
125
/* *
125
126
* Updates parameter_ struct if any parameters have changed since last update. Parameter dependent
@@ -142,7 +143,7 @@ class AdmittanceRule
142
143
controller_interface::return_type update (
143
144
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
144
145
const geometry_msgs::msg::Wrench & measured_wrench,
145
- const geometry_msgs::msg::Pose & reference_pose,
146
+ const geometry_msgs::msg::PoseStamped & reference_pose,
146
147
const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
147
148
const rclcpp::Duration & period,
148
149
trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states);
Original file line number Diff line number Diff line change @@ -148,11 +148,11 @@ void AdmittanceRule::apply_parameters_update()
148
148
149
149
bool AdmittanceRule::get_all_transforms (
150
150
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
151
- const geometry_msgs::msg::Pose & reference_pose)
151
+ const geometry_msgs::msg::PoseStamped & reference_pose)
152
152
{
153
153
// get reference transforms
154
154
bool success=true ;
155
- tf2::fromMsg (reference_pose, admittance_transforms_.ref_base_ft_ );
155
+ tf2::fromMsg (reference_pose. pose , admittance_transforms_.ref_base_ft_ );
156
156
157
157
// get transforms at current configuration
158
158
success &= kinematics_->calculate_link_transform (
@@ -176,7 +176,7 @@ bool AdmittanceRule::get_all_transforms(
176
176
controller_interface::return_type AdmittanceRule::update (
177
177
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
178
178
const geometry_msgs::msg::Wrench & measured_wrench,
179
- const geometry_msgs::msg::Pose & reference_pose,
179
+ const geometry_msgs::msg::PoseStamped & reference_pose,
180
180
const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
181
181
const rclcpp::Duration & period, trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_state)
182
182
{
Original file line number Diff line number Diff line change @@ -267,10 +267,10 @@ controller_interface::CallbackReturn AdmittanceController::on_configure(
267
267
" ~/joint_references" , rclcpp::SystemDefaultsQoS (), joint_command_callback);
268
268
269
269
auto goal_pose_callback =
270
- [this ](const std::shared_ptr<geometry_msgs::msg::Pose > msg)
270
+ [this ](const std::shared_ptr<geometry_msgs::msg::PoseStamped > msg)
271
271
{ input_goal_pose_.writeFromNonRT (msg); };
272
272
input_goal_pose_subscriber_ =
273
- get_node ()->create_subscription <geometry_msgs::msg::Pose >(
273
+ get_node ()->create_subscription <geometry_msgs::msg::PoseStamped >(
274
274
" ~/goal_pose" , rclcpp::SystemDefaultsQoS (), goal_pose_callback);
275
275
276
276
s_publisher_ = get_node ()->create_publisher <control_msgs::msg::AdmittanceControllerState>(
@@ -354,10 +354,8 @@ controller_interface::CallbackReturn AdmittanceController::on_activate(
354
354
return controller_interface::CallbackReturn::ERROR;
355
355
}
356
356
}
357
-
358
- goal_pose_msg_ = std::make_shared<geometry_msgs::msg::Pose>(
359
- admittance_->initialize_goal_pose (joint_state_)
360
- );
357
+ goal_pose_msg_ = std::make_shared<geometry_msgs::msg::PoseStamped>();
358
+ goal_pose_msg_->pose = admittance_->initialize_goal_pose (joint_state_);
361
359
if (!goal_pose_msg_){
362
360
RCLCPP_ERROR (get_node ()->get_logger (), " Failed to initialize goal_pose from current joint positions.\n " );
363
361
return controller_interface::CallbackReturn::ERROR;
You can’t perform that action at this time.
0 commit comments