43 #include <gtest/gtest.h> 
   49 #include <geometry_msgs/PointStamped.h> 
   53 class MoveItCppTest : 
public ::testing::Test
 
   62     traj1.joint_trajectory.joint_names.push_back(
"panda_joint1");
 
   63     traj1.joint_trajectory.points.resize(2);
 
   64     traj1.joint_trajectory.points[0].positions.push_back(0.0);
 
   65     traj1.joint_trajectory.points[1].positions.push_back(0.5);
 
   66     traj1.joint_trajectory.points[1].time_from_start.fromSec(0.5);
 
   69     traj2.joint_trajectory.joint_names.push_back(
"panda_joint2");
 
   70     traj2.joint_trajectory.points[0].positions.push_back(1.0);
 
   71     traj2.joint_trajectory.points[1].positions.push_back(1.5);
 
   72     traj2.multi_dof_joint_trajectory.joint_names.push_back(
"panda_joint3");
 
   73     traj2.multi_dof_joint_trajectory.points.resize(2);
 
   74     traj2.multi_dof_joint_trajectory.points[0].transforms.resize(1);
 
   75     traj2.multi_dof_joint_trajectory.points[1].transforms.resize(1);
 
   77     ros::param::del(
"~/trajectory_execution/joints_allowed_start_tolerance");
 
   85   moveit_msgs::RobotTrajectory 
traj1;
 
   86   moveit_msgs::RobotTrajectory 
traj2;
 
   89 TEST_F(MoveItCppTest, EnsureActiveControllersForJointsTest)
 
   91   ASSERT_TRUE(trajectory_execution_manager_ptr->ensureActiveControllersForJoints({ 
"panda_joint1" }));
 
   94 TEST_F(MoveItCppTest, ensureActiveControllerTest)
 
   96   ASSERT_TRUE(trajectory_execution_manager_ptr->ensureActiveController(
"fake_panda_arm_controller"));
 
   99 TEST_F(MoveItCppTest, ExecuteEmptySetOfTrajectoriesTest)
 
  102   trajectory_execution_manager_ptr->execute();
 
  103   auto last_execution_status = trajectory_execution_manager_ptr->waitForExecution();
 
  107 TEST_F(MoveItCppTest, PushExecuteAndWaitTest)
 
  109   ASSERT_TRUE(trajectory_execution_manager_ptr->push(traj1));
 
  110   ASSERT_TRUE(trajectory_execution_manager_ptr->push(traj2));
 
  111   traj1.multi_dof_joint_trajectory = traj2.multi_dof_joint_trajectory;
 
  112   ASSERT_TRUE(trajectory_execution_manager_ptr->push(traj1));
 
  113   auto last_execution_status = trajectory_execution_manager_ptr->executeAndWait();
 
  117 TEST_F(MoveItCppTest, RejectTooFarFromStart)
 
  119   moveit_msgs::RobotTrajectory traj = traj1;
 
  120   traj.joint_trajectory.points[0].positions[0] = 0.3;
 
  122   trajectory_execution_manager_ptr->setAllowedStartTolerance(0.01);
 
  123   ASSERT_TRUE(trajectory_execution_manager_ptr->push(traj));
 
  124   auto last_execution_status = trajectory_execution_manager_ptr->executeAndWait();
 
  128 TEST_F(MoveItCppTest, AcceptAllowedJointStartTolerance)
 
  130   moveit_msgs::RobotTrajectory traj = traj1;
 
  131   traj.joint_trajectory.points[0].positions[0] = 0.3;
 
  133   trajectory_execution_manager_ptr->setAllowedStartTolerance(0.01);
 
  134   ros::param::set(
"~/trajectory_execution/joints_allowed_start_tolerance/panda_joint1", 0.5);
 
  135   ASSERT_TRUE(trajectory_execution_manager_ptr->push(traj));
 
  136   auto last_execution_status = trajectory_execution_manager_ptr->executeAndWait();
 
  142   moveit_msgs::RobotTrajectory traj = traj1;
 
  143   traj.joint_trajectory.points[0].positions[0] = 0.3;
 
  145   trajectory_execution_manager_ptr->setAllowedStartTolerance(0);
 
  146   ASSERT_TRUE(trajectory_execution_manager_ptr->push(traj));
 
  147   auto last_execution_status = trajectory_execution_manager_ptr->executeAndWait();
 
  150   trajectory_execution_manager_ptr->setAllowedStartTolerance(0.1);
 
  151   ASSERT_TRUE(trajectory_execution_manager_ptr->push(traj));
 
  152   last_execution_status = trajectory_execution_manager_ptr->executeAndWait();
 
  155   ros::param::set(
"~/trajectory_execution/joints_allowed_start_tolerance/panda_joint1", 0);
 
  156   ASSERT_TRUE(trajectory_execution_manager_ptr->push(traj));
 
  157   last_execution_status = trajectory_execution_manager_ptr->executeAndWait();
 
  163 int main(
int argc, 
char** argv)
 
  165   testing::InitGoogleTest(&argc, argv);
 
  166   ros::init(argc, argv, 
"test_execution_manager");
 
  168   int result = RUN_ALL_TESTS();