40 #include <gtest/gtest.h>
43 #include <rclcpp/rclcpp.hpp>
44 #include <tf2/LinearMath/Quaternion.h>
45 #include <tf2_eigen/tf2_eigen.hpp>
51 #include <moveit_msgs/msg/constraints.hpp>
54 static const double EPSILON = 1e-2;
56 static const std::string PLANNING_GROUP =
"panda_arm";
60 static const double PLANNING_ATTEMPTS = 5.0;
68 move_group_ = std::make_shared<moveit::planning_interface::MoveGroupInterface>(
node_, PLANNING_GROUP);
70 move_group_->setNumPlanningAttempts(PLANNING_ATTEMPTS);
83 :
node_(std::make_shared<
rclcpp::Node>(
"ompl_constrained_planning_testing"))
84 ,
executor_(std::make_shared<
rclcpp::executors::SingleThreadedExecutor>())
97 void planAndMove(
const geometry_msgs::msg::PoseStamped& pose_goal_stamped,
98 const moveit_msgs::msg::Constraints& path_constraint)
100 SCOPED_TRACE(
"planAndMove");
102 ASSERT_TRUE(
move_group_->setPoseTarget(pose_goal_stamped));
106 ASSERT_EQ(
move_group_->plan(
plan), moveit::core::MoveItErrorCode::SUCCESS);
107 ASSERT_EQ(
move_group_->move(), moveit::core::MoveItErrorCode::SUCCESS);
110 void testPose(
const geometry_msgs::msg::PoseStamped& pose_goal_stamped)
112 SCOPED_TRACE(
"testPose");
114 const geometry_msgs::msg::PoseStamped actual_pose_stamped =
move_group_->getCurrentPose();
115 Eigen::Isometry3d goal_pose, actual_pose;
117 tf2::fromMsg(pose_goal_stamped.pose, goal_pose);
118 tf2::fromMsg(actual_pose_stamped.pose, actual_pose);
120 std::stringstream ss;
121 ss <<
"expected: \n" << goal_pose.matrix() <<
"\nactual: \n" << actual_pose.matrix();
122 EXPECT_TRUE(actual_pose.isApprox(goal_pose,
EPSILON)) << ss.str();
136 SCOPED_TRACE(
"PositionConstraint");
139 move_group_->setStartStateToCurrentState();
140 const geometry_msgs::msg::PoseStamped eef_pose = move_group_->getCurrentPose();
143 geometry_msgs::msg::PoseStamped pose_goal = eef_pose;
144 pose_goal.pose.position.y += 0.3;
145 pose_goal.pose.position.z -= 0.3;
148 moveit_msgs::msg::PositionConstraint position_constraint;
149 position_constraint.header.frame_id = ref_link_;
150 position_constraint.link_name = ee_link_;
151 position_constraint.weight = 1.0;
153 shape_msgs::msg::SolidPrimitive cbox;
154 cbox.type = shape_msgs::msg::SolidPrimitive::BOX;
155 cbox.dimensions = { 0.1, 0.4, 0.4 };
156 position_constraint.constraint_region.primitives.emplace_back(cbox);
158 geometry_msgs::msg::Pose cbox_pose;
159 cbox_pose.position.x = eef_pose.pose.position.x;
160 cbox_pose.position.y = 0.15;
161 cbox_pose.position.z = 0.45;
162 cbox_pose.orientation.w = 1.0;
163 position_constraint.constraint_region.primitive_poses.emplace_back(cbox_pose);
166 moveit_msgs::msg::Constraints path_constraint;
167 path_constraint.name =
"position constraint";
168 path_constraint.position_constraints.emplace_back(position_constraint);
170 planAndMove(pose_goal, path_constraint);
175 int main(
int argc,
char** argv)
177 rclcpp::init(argc, argv);
178 ::testing::InitGoogleTest(&argc, argv);
180 int ret = RUN_ALL_TESTS();
rclcpp::Executor::SharedPtr executor_
moveit::planning_interface::MoveGroupInterfacePtr move_group_
std::thread executor_thread_
void testPose(const geometry_msgs::msg::PoseStamped &pose_goal_stamped)
void planAndMove(const geometry_msgs::msg::PoseStamped &pose_goal_stamped, const moveit_msgs::msg::Constraints &path_constraint)
rclcpp::Node::SharedPtr node_
ConstrainedPlanningTestFixture()
constexpr double PLANNING_TIME_S
constexpr double MAX_ACCELERATION_SCALE
constexpr double GOAL_TOLERANCE
constexpr double MAX_VELOCITY_SCALE
int main(int argc, char **argv)
TEST_F(ConstrainedPlanningTestFixture, PositionConstraint)
The representation of a motion plan (as ROS messasges)