37 #include <gtest/gtest.h> 
   57   move_group_.setStartState(*(move_group_.getCurrentState()));
 
   58   move_group_.setJointValueTarget(std::vector<double>({ 1.0, 1.0 }));
 
   61   EXPECT_GT(my_plan_.trajectory_.joint_trajectory.points.size(), 0u);
 
   62   EXPECT_EQ(error_code.val, moveit::core::MoveItErrorCode::SUCCESS);
 
   67   move_group_.setStartState(*(move_group_.getCurrentState()));
 
   69   move_group_.setJointValueTarget(std::vector<double>({ 100.0, 2 * M_PI / 3.0 }));
 
   72   EXPECT_EQ(error_code.val, moveit::core::MoveItErrorCode::INVALID_ROBOT_STATE);
 
   77   move_group_.setStartState(*(move_group_.getCurrentState()));
 
   78   geometry_msgs::Pose target_pose1;
 
   79   target_pose1.orientation.w = 1.0;
 
   80   target_pose1.position.x = 10000.;
 
   81   target_pose1.position.y = 10000.;
 
   82   target_pose1.position.z = 10000.;
 
   83   move_group_.setPoseTarget(target_pose1);
 
   87   EXPECT_EQ(error_code.val, moveit::core::MoveItErrorCode::INVALID_GOAL_CONSTRAINTS);
 
   92   move_group_.setJointValueTarget(std::vector<double>({ 0.2, 0.2 }));
 
   95   EXPECT_EQ(error_code.val, moveit::core::MoveItErrorCode::SUCCESS);
 
  100   move_group_.setStartState(*(move_group_.getCurrentState()));
 
  101   move_group_.setJointValueTarget(std::vector<double>({ M_PI / 2.0, 0 }));
 
  104   EXPECT_EQ(error_code.val, moveit::core::MoveItErrorCode::INVALID_MOTION_PLAN);
 
  107 int main(
int argc, 
char** argv)
 
  109   testing::InitGoogleTest(&argc, argv);
 
  110   ros::init(argc, argv, 
"chomp_moveit_test");
 
  112   ros::AsyncSpinner spinner(1);
 
  114   int ret = RUN_ALL_TESTS();
 
int main(int argc, char **argv)
 
TEST_F(CHOMPMoveitTest, jointSpaceGoodGoal)
 
moveit::planning_interface::MoveGroupInterface::Plan my_plan_
 
moveit::planning_interface::MoveGroupInterface move_group_
 
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
 
Client class to conveniently use the ROS interfaces provided by the move_group node.
 
The representation of a motion plan (as ROS messasges)