Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <moveit/trajectory_execution_manager/trajectory_execution_manager.h>
00036 #include <moveit/robot_model_loader/robot_model_loader.h>
00037
00038 int main(int argc, char **argv)
00039 {
00040 ros::init(argc, argv, "test_trajectory_execution_manager");
00041
00042 ros::AsyncSpinner spinner(1);
00043 spinner.start();
00044
00045 robot_model_loader::RobotModelLoader rml;
00046 trajectory_execution_manager::TrajectoryExecutionManager tem(rml.getModel(), true);
00047
00048 std::cout << "1:\n";
00049 if (!tem.ensureActiveControllersForJoints(std::vector<std::string>(1, "basej")))
00050 ROS_ERROR("Fail!");
00051
00052 std::cout << "2:\n";
00053 if (!tem.ensureActiveController("arms"))
00054 ROS_ERROR("Fail!");
00055
00056 std::cout << "3:\n";
00057 if (!tem.ensureActiveControllersForJoints(std::vector<std::string>(1, "rj2")))
00058 ROS_ERROR("Fail!");
00059
00060 std::cout << "4:\n";
00061 if (!tem.ensureActiveControllersForJoints(std::vector<std::string>(1, "lj1")))
00062 ROS_ERROR("Fail!");
00063
00064 std::cout << "5:\n";
00065 if (!tem.ensureActiveController("left_arm_head"))
00066 ROS_ERROR("Fail!");
00067 std::cout << "6:\n";
00068 if (!tem.ensureActiveController("arms"))
00069 ROS_ERROR("Fail!");
00070
00071
00072 tem.execute();
00073 if (!tem.waitForExecution())
00074 ROS_ERROR("Fail!");
00075
00076 moveit_msgs::RobotTrajectory traj1;
00077 traj1.joint_trajectory.joint_names.push_back("rj1");
00078 traj1.joint_trajectory.points.resize(1);
00079 traj1.joint_trajectory.points[0].positions.push_back(0.0);
00080 if (!tem.push(traj1))
00081 ROS_ERROR("Fail!");
00082
00083 moveit_msgs::RobotTrajectory traj2 = traj1;
00084 traj2.joint_trajectory.joint_names.push_back("lj2");
00085 traj2.joint_trajectory.points[0].positions.push_back(1.0);
00086 traj2.multi_dof_joint_trajectory.joint_names.push_back("basej");
00087 traj2.multi_dof_joint_trajectory.points.resize(1);
00088 traj2.multi_dof_joint_trajectory.points[0].transforms.resize(1);
00089
00090 if (!tem.push(traj2))
00091 ROS_ERROR("Fail!");
00092
00093 traj1.multi_dof_joint_trajectory = traj2.multi_dof_joint_trajectory;
00094 if (!tem.push(traj1))
00095 ROS_ERROR("Fail!");
00096
00097 if (!tem.executeAndWait())
00098 ROS_ERROR("Fail!");
00099
00100 ros::waitForShutdown();
00101
00102 return 0;
00103 }