Skip to content

Commit

Permalink
Use drake_ros_core conversions
Browse files Browse the repository at this point in the history
  • Loading branch information
sloretz committed Nov 28, 2022
1 parent 8de9eb8 commit de58267
Showing 1 changed file with 2 additions and 14 deletions.
16 changes: 2 additions & 14 deletions drake_ros_examples/examples/ufo/ufo.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
#include <drake/systems/framework/diagram_builder.h>
#include <drake/systems/framework/leaf_system.h>
#include <drake_ros_core/drake_ros.h>
#include <drake_ros_core/geometry_conversions.h>
#include <drake_ros_core/ros_interface_system.h>
#include <drake_ros_core/ros_subscriber_system.h>
#include <drake_ros_tf2/scene_tf_broadcaster_system.h>
Expand Down Expand Up @@ -284,20 +285,7 @@ class RosPoseGlue : public LeafSystemd {
const auto& goal_pose =
input_port.Eval<geometry_msgs::msg::PoseStamped>(context);

Vector3d translation{
goal_pose.pose.position.x,
goal_pose.pose.position.y,
goal_pose.pose.position.z,
};
Quaterniond rotation{
goal_pose.pose.orientation.w,
goal_pose.pose.orientation.x,
goal_pose.pose.orientation.y,
goal_pose.pose.orientation.z,
};

output->set_translation(translation);
output->set_rotation(rotation);
*output = drake_ros_core::RosPoseToRigidTransform(goal_pose.pose);
}
};

Expand Down

0 comments on commit de58267

Please sign in to comment.