43 #include <gtest/gtest.h>
49 #include <geometry_msgs/PointStamped.h>
53 class MoveItCppTest :
public ::testing::Test
58 nh_ = ros::NodeHandle();
62 traj1.joint_trajectory.joint_names.push_back(
"panda_joint1");
63 traj1.joint_trajectory.points.resize(1);
64 traj1.joint_trajectory.points[0].positions.push_back(0.0);
67 traj2.joint_trajectory.joint_names.push_back(
"panda_joint2");
68 traj2.joint_trajectory.points[0].positions.push_back(1.0);
69 traj2.multi_dof_joint_trajectory.joint_names.push_back(
"panda_joint3");
70 traj2.multi_dof_joint_trajectory.points.resize(1);
71 traj2.multi_dof_joint_trajectory.points[0].transforms.resize(1);
79 moveit_msgs::RobotTrajectory
traj1;
80 moveit_msgs::RobotTrajectory
traj2;
85 ASSERT_TRUE(trajectory_execution_manager_ptr->ensureActiveControllersForJoints({
"panda_joint1" }));
90 ASSERT_TRUE(trajectory_execution_manager_ptr->ensureActiveController(
"fake_panda_arm_controller"));
96 trajectory_execution_manager_ptr->execute();
97 auto last_execution_status = trajectory_execution_manager_ptr->waitForExecution();
103 ASSERT_TRUE(trajectory_execution_manager_ptr->push(traj1));
104 ASSERT_TRUE(trajectory_execution_manager_ptr->push(traj2));
105 traj1.multi_dof_joint_trajectory = traj2.multi_dof_joint_trajectory;
106 ASSERT_TRUE(trajectory_execution_manager_ptr->push(traj1));
107 auto last_execution_status = trajectory_execution_manager_ptr->executeAndWait();
113 int main(
int argc,
char** argv)
115 testing::InitGoogleTest(&argc, argv);
116 ros::init(argc, argv,
"test_execution_manager");
118 int result = RUN_ALL_TESTS();
PlanningComponentPtr planning_component_ptr
moveit_msgs::RobotTrajectory traj2
moveit_msgs::RobotTrajectory traj1
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_ptr
MoveItCppPtr moveit_cpp_ptr
TEST_F(MoveItCppTest, GetCurrentStateTest)
int main(int argc, char **argv)