Skip to content

Commit

Permalink
Updates trajectory_msgs::JointTrajectory to trajectory_msgs::msg::Joi…
Browse files Browse the repository at this point in the history
…ntTrajectory.
  • Loading branch information
rr-mark committed Jan 30, 2025
1 parent 683b4af commit d761ed5
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions moveit_core/robot_state/test/robot_state_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -762,7 +762,7 @@ TEST_F(OneRobot, rigidlyConnectedParent)
// attach "object" with "subframe" to link_b
state.attachBody(std::make_unique<moveit::core::AttachedBody>(
link_b, "object", Eigen::Isometry3d(Eigen::Translation3d(1, 0, 0)), std::vector<shapes::ShapeConstPtr>{},
EigenSTL::vector_Isometry3d{}, std::set<std::string>{}, trajectory_msgs::JointTrajectory{},
EigenSTL::vector_Isometry3d{}, std::set<std::string>{}, trajectory_msgs::msg::JointTrajectory{},
moveit::core::FixedTransformsMap{ { "subframe", Eigen::Isometry3d(Eigen::Translation3d(0, 0, 1)) } }));

// RobotState's version should resolve these too
Expand Down Expand Up @@ -791,7 +791,7 @@ TEST_F(OneRobot, rigidlyConnectedParent)
state.attachBody(std::make_unique<moveit::core::AttachedBody>(
link_with_slash, "object/with/slash", Eigen::Isometry3d(Eigen::Translation3d(1, 0, 0)),
std::vector<shapes::ShapeConstPtr>{}, EigenSTL::vector_Isometry3d{}, std::set<std::string>{},
trajectory_msgs::JointTrajectory{},
trajectory_msgs::msg::JointTrajectory{},
moveit::core::FixedTransformsMap{ { "sub/frame", Eigen::Isometry3d(Eigen::Translation3d(0, 0, 1)) } }));
const moveit::core::LinkModel* rigid_parent_of_object =
state.getRigidlyConnectedParentLinkModel("object/with/slash/sub/frame");
Expand Down

0 comments on commit d761ed5

Please sign in to comment.