40 #include <gtest/gtest.h>
43 #include <rclcpp/rclcpp.hpp>
45 #if __has_include(<tf2/LinearMath/Quaternion.hpp>)
46 #include <tf2/LinearMath/Quaternion.hpp>
48 #include <tf2/LinearMath/Quaternion.h>
50 #include <tf2_eigen/tf2_eigen.hpp>
56 #include <moveit_msgs/msg/constraints.hpp>
59 static const double EPSILON = 1e-2;
61 static const std::string PLANNING_GROUP =
"panda_arm";
65 static const double PLANNING_ATTEMPTS = 5.0;
73 move_group_ = std::make_shared<moveit::planning_interface::MoveGroupInterface>(
node_, PLANNING_GROUP);
75 move_group_->setNumPlanningAttempts(PLANNING_ATTEMPTS);
88 :
node_(std::make_shared<
rclcpp::Node>(
"ompl_constrained_planning_testing"))
89 ,
executor_(std::make_shared<
rclcpp::executors::SingleThreadedExecutor>())
102 void planAndMove(
const geometry_msgs::msg::PoseStamped& pose_goal_stamped,
103 const moveit_msgs::msg::Constraints& path_constraint)
105 SCOPED_TRACE(
"planAndMove");
107 ASSERT_TRUE(
move_group_->setPoseTarget(pose_goal_stamped));
111 ASSERT_EQ(
move_group_->plan(
plan), moveit::core::MoveItErrorCode::SUCCESS);
112 ASSERT_EQ(
move_group_->move(), moveit::core::MoveItErrorCode::SUCCESS);
115 void testPose(
const geometry_msgs::msg::PoseStamped& pose_goal_stamped)
117 SCOPED_TRACE(
"testPose");
119 const geometry_msgs::msg::PoseStamped actual_pose_stamped =
move_group_->getCurrentPose();
120 Eigen::Isometry3d goal_pose, actual_pose;
122 tf2::fromMsg(pose_goal_stamped.pose, goal_pose);
123 tf2::fromMsg(actual_pose_stamped.pose, actual_pose);
125 std::stringstream ss;
126 ss <<
"expected: \n" << goal_pose.matrix() <<
"\nactual: \n" << actual_pose.matrix();
127 EXPECT_TRUE(actual_pose.isApprox(goal_pose,
EPSILON)) << ss.str();
141 SCOPED_TRACE(
"PositionConstraint");
144 move_group_->setStartStateToCurrentState();
145 const geometry_msgs::msg::PoseStamped eef_pose = move_group_->getCurrentPose();
148 geometry_msgs::msg::PoseStamped pose_goal = eef_pose;
149 pose_goal.pose.position.y += 0.3;
150 pose_goal.pose.position.z -= 0.3;
153 moveit_msgs::msg::PositionConstraint position_constraint;
154 position_constraint.header.frame_id = ref_link_;
155 position_constraint.link_name = ee_link_;
156 position_constraint.weight = 1.0;
158 shape_msgs::msg::SolidPrimitive cbox;
159 cbox.type = shape_msgs::msg::SolidPrimitive::BOX;
160 cbox.dimensions = { 0.1, 0.4, 0.4 };
161 position_constraint.constraint_region.primitives.emplace_back(cbox);
163 geometry_msgs::msg::Pose cbox_pose;
164 cbox_pose.position.x = eef_pose.pose.position.x;
165 cbox_pose.position.y = 0.15;
166 cbox_pose.position.z = 0.45;
167 cbox_pose.orientation.w = 1.0;
168 position_constraint.constraint_region.primitive_poses.emplace_back(cbox_pose);
171 moveit_msgs::msg::Constraints path_constraint;
172 path_constraint.name =
"position constraint";
173 path_constraint.position_constraints.emplace_back(position_constraint);
175 planAndMove(pose_goal, path_constraint);
180 int main(
int argc,
char** argv)
182 rclcpp::init(argc, argv);
183 ::testing::InitGoogleTest(&argc, argv);
185 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)