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);
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();