38 #include <gtest/gtest.h> 40 #include <moveit/move_group_interface/move_group_interface.h> 41 #include <moveit/planning_scene_interface/planning_scene_interface.h> 47 moveit::planning_interface::MoveGroupInterface::Plan
my_plan_;
59 move_group_.setJointValueTarget(std::vector<double>({ 1.0, 1.0 }));
62 EXPECT_GT(
my_plan_.trajectory_.joint_trajectory.points.size(), 0);
63 EXPECT_EQ(error_code.val, moveit::planning_interface::MoveItErrorCode::SUCCESS);
70 move_group_.setJointValueTarget(std::vector<double>({ 100.0, 2 *
M_PI / 3.0 }));
73 EXPECT_EQ(error_code.val, moveit::planning_interface::MoveItErrorCode::INVALID_ROBOT_STATE);
79 geometry_msgs::Pose target_pose1;
80 target_pose1.orientation.w = 1.0;
81 target_pose1.position.x = 10000.;
82 target_pose1.position.y = 10000.;
83 target_pose1.position.z = 10000.;
88 EXPECT_EQ(error_code.val, moveit::planning_interface::MoveItErrorCode::INVALID_GOAL_CONSTRAINTS);
93 move_group_.setJointValueTarget(std::vector<double>({ 0.2, 0.2 }));
96 EXPECT_EQ(error_code.val, moveit::planning_interface::MoveItErrorCode::INVALID_ROBOT_STATE);
102 move_group_.setJointValueTarget(std::vector<double>({
M_PI / 2.0, 0 }));
105 EXPECT_EQ(error_code.val, moveit::planning_interface::MoveItErrorCode::INVALID_MOTION_PLAN);
108 int main(
int argc,
char** argv)
110 testing::InitGoogleTest(&argc, argv);
111 ros::init(argc, argv,
"chomp_moveit_test");
115 int ret = RUN_ALL_TESTS();
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
moveit::planning_interface::MoveGroupInterface move_group_
TEST_F(CHOMPMoveitTest, jointSpaceGoodGoal)
ROSCPP_DECL void shutdown()
moveit::planning_interface::MoveGroupInterface::Plan my_plan_