40 #include <rclcpp/rclcpp.hpp>
43 #include <gtest/gtest.h>
49 #include <geometry_msgs/PointStamped.h>
60 rclcpp::NodeOptions node_options;
65 node_options.automatically_declare_parameters_from_overrides(
true);
66 node_ = rclcpp::Node::make_shared(
"/moveit_cpp_test");
104 ros::Duration(1.0).sleep();
105 auto robot_model = moveit_cpp_ptr->getRobotModel();
106 auto robot_state = std::make_shared<moveit::core::RobotState>(robot_model);
107 EXPECT_TRUE(moveit_cpp_ptr->getCurrentState(robot_state, 0.0));
109 std::vector<double> joints_vals;
110 robot_state->copyJointGroupPositions(PLANNING_GROUP, joints_vals);
111 EXPECT_NEAR(joints_vals[0], 0.0, 0.001);
112 EXPECT_NEAR(joints_vals[1], -0.785, 0.001);
113 EXPECT_NEAR(joints_vals[2], 0.0, 0.001);
114 EXPECT_NEAR(joints_vals[3], -2.356, 0.001);
115 EXPECT_NEAR(joints_vals[4], 0.0, 0.001);
116 EXPECT_NEAR(joints_vals[5], 1.571, 0.001);
117 EXPECT_NEAR(joints_vals[6], 0.785, 0.001);
123 EXPECT_STREQ(planning_component_ptr->getPlanningGroupName().c_str(),
"panda_arm");
129 planning_component_ptr->setStartStateToCurrentState();
130 planning_component_ptr->setGoal(target_pose1,
"panda_link8");
132 ASSERT_TRUE(
static_cast<bool>(planning_component_ptr->plan()));
139 planning_component_ptr->setGoal(target_pose1,
"panda_link8");
141 ASSERT_TRUE(
static_cast<bool>(planning_component_ptr->plan()));
147 auto start_state = *(moveit_cpp_ptr->getCurrentState());
148 start_state.setFromIK(jmg_ptr, start_pose);
150 planning_component_ptr->setStartState(start_state);
151 planning_component_ptr->setGoal(target_pose1,
"panda_link8");
153 ASSERT_TRUE(
static_cast<bool>(planning_component_ptr->plan()));
159 auto target_state = *(moveit_cpp_ptr->getCurrentState());
161 target_state.setFromIK(jmg_ptr, target_pose2);
163 planning_component_ptr->setGoal(target_state);
165 ASSERT_TRUE(
static_cast<bool>(planning_component_ptr->plan()));
170 int main(
int argc,
char** argv)
172 testing::InitGoogleTest(&argc, argv);
173 ros::init(argc, argv,
"moveit_cpp_test");
175 ros::AsyncSpinner spinner(4);
178 int result = RUN_ALL_TESTS();
PlanningComponentPtr planning_component_ptr
moveit::core::RobotModelConstPtr robot_model_ptr
const moveit::core::JointModelGroup * jmg_ptr
const std::string PLANNING_GROUP
geometry_msgs::Pose target_pose2
geometry_msgs::Pose start_pose
MoveItCppPtr moveit_cpp_ptr
geometry_msgs::PoseStamped target_pose1
int main(int argc, char **argv)
TEST_F(MoveItCppTest, GetCurrentStateTest)
Main namespace for MoveIt.
This namespace includes the base class for MoveIt planners.