Skip to content

Commit 0b25655

Browse files
committed
move from Pose to PoseStamped
1 parent 5bd5767 commit 0b25655

File tree

4 files changed

+13
-14
lines changed

4 files changed

+13
-14
lines changed

admittance_controller/include/admittance_controller/admittance_controller.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,7 @@ 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
136+
rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr
137137
input_goal_pose_subscriber_;
138138
rclcpp::Publisher<control_msgs::msg::AdmittanceControllerState>::SharedPtr s_publisher_;
139139

@@ -142,12 +142,12 @@ class AdmittanceController : public controller_interface::ChainableControllerInt
142142

143143
// ROS messages
144144
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_;
146146

147147
// real-time buffer
148148
realtime_tools::RealtimeBuffer<std::shared_ptr<trajectory_msgs::msg::JointTrajectoryPoint>>
149149
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>>
151151
input_goal_pose_;
152152
std::unique_ptr<realtime_tools::RealtimePublisher<ControllerStateMsg>> state_publisher_;
153153

admittance_controller/include/admittance_controller/admittance_rule.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030
#include "pluginlib/class_loader.hpp"
3131
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
3232
#include "geometry_msgs/msg/pose.hpp"
33+
#include "geometry_msgs/msg/pose_stamped.hpp"
3334

3435
namespace admittance_controller
3536
{
@@ -119,7 +120,7 @@ class AdmittanceRule
119120
*/
120121
bool get_all_transforms(
121122
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
122-
const geometry_msgs::msg::Pose & reference_pose);
123+
const geometry_msgs::msg::PoseStamped & reference_pose);
123124

124125
/**
125126
* Updates parameter_ struct if any parameters have changed since last update. Parameter dependent
@@ -142,7 +143,7 @@ class AdmittanceRule
142143
controller_interface::return_type update(
143144
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
144145
const geometry_msgs::msg::Wrench & measured_wrench,
145-
const geometry_msgs::msg::Pose & reference_pose,
146+
const geometry_msgs::msg::PoseStamped & reference_pose,
146147
const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
147148
const rclcpp::Duration & period,
148149
trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states);

admittance_controller/include/admittance_controller/admittance_rule_impl.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -148,11 +148,11 @@ void AdmittanceRule::apply_parameters_update()
148148

149149
bool AdmittanceRule::get_all_transforms(
150150
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
151-
const geometry_msgs::msg::Pose & reference_pose)
151+
const geometry_msgs::msg::PoseStamped & reference_pose)
152152
{
153153
// get reference transforms
154154
bool success=true;
155-
tf2::fromMsg(reference_pose, admittance_transforms_.ref_base_ft_);
155+
tf2::fromMsg(reference_pose.pose, admittance_transforms_.ref_base_ft_);
156156

157157
// get transforms at current configuration
158158
success &= kinematics_->calculate_link_transform(
@@ -176,7 +176,7 @@ bool AdmittanceRule::get_all_transforms(
176176
controller_interface::return_type AdmittanceRule::update(
177177
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
178178
const geometry_msgs::msg::Wrench & measured_wrench,
179-
const geometry_msgs::msg::Pose & reference_pose,
179+
const geometry_msgs::msg::PoseStamped & reference_pose,
180180
const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
181181
const rclcpp::Duration & period, trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_state)
182182
{

admittance_controller/src/admittance_controller.cpp

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -267,10 +267,10 @@ controller_interface::CallbackReturn AdmittanceController::on_configure(
267267
"~/joint_references", rclcpp::SystemDefaultsQoS(), joint_command_callback);
268268

269269
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)
271271
{ input_goal_pose_.writeFromNonRT(msg); };
272272
input_goal_pose_subscriber_ =
273-
get_node()->create_subscription<geometry_msgs::msg::Pose>(
273+
get_node()->create_subscription<geometry_msgs::msg::PoseStamped>(
274274
"~/goal_pose", rclcpp::SystemDefaultsQoS(), goal_pose_callback);
275275

276276
s_publisher_ = get_node()->create_publisher<control_msgs::msg::AdmittanceControllerState>(
@@ -354,10 +354,8 @@ controller_interface::CallbackReturn AdmittanceController::on_activate(
354354
return controller_interface::CallbackReturn::ERROR;
355355
}
356356
}
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_);
361359
if(!goal_pose_msg_){
362360
RCLCPP_ERROR(get_node()->get_logger(), "Failed to initialize goal_pose from current joint positions.\n");
363361
return controller_interface::CallbackReturn::ERROR;

0 commit comments

Comments
 (0)