test_app.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #include <moveit/trajectory_execution_manager/trajectory_execution_manager.h>
00038 #include <moveit/robot_model_loader/robot_model_loader.h>
00039 
00040 int main(int argc, char **argv)
00041 {
00042   ros::init(argc, argv, "test_trajectory_execution_manager");
00043 
00044   ros::AsyncSpinner spinner(1);
00045   spinner.start();
00046 
00047   robot_model_loader::RobotModelLoader rml;
00048   trajectory_execution_manager::TrajectoryExecutionManager tem(rml.getModel(), true);
00049 
00050   std::cout << "1:\n";
00051   if (!tem.ensureActiveControllersForJoints(std::vector<std::string>(1, "basej")))
00052     ROS_ERROR("Fail!");
00053 
00054   std::cout << "2:\n";
00055   if (!tem.ensureActiveController("arms"))
00056     ROS_ERROR("Fail!");
00057 
00058   std::cout << "3:\n";
00059   if (!tem.ensureActiveControllersForJoints(std::vector<std::string>(1, "rj2")))
00060     ROS_ERROR("Fail!");
00061 
00062   std::cout << "4:\n";
00063   if (!tem.ensureActiveControllersForJoints(std::vector<std::string>(1, "lj1")))
00064     ROS_ERROR("Fail!");
00065 
00066   std::cout << "5:\n";
00067   if (!tem.ensureActiveController("left_arm_head"))
00068     ROS_ERROR("Fail!");
00069   std::cout << "6:\n";
00070   if (!tem.ensureActiveController("arms"))
00071     ROS_ERROR("Fail!");
00072 
00073   // execute with empty set of trajectories
00074   tem.execute();
00075   if (!tem.waitForExecution())
00076     ROS_ERROR("Fail!");
00077 
00078   moveit_msgs::RobotTrajectory traj1;
00079   traj1.joint_trajectory.joint_names.push_back("rj1");
00080   traj1.joint_trajectory.points.resize(1);
00081   traj1.joint_trajectory.points[0].positions.push_back(0.0);
00082   if (!tem.push(traj1))
00083     ROS_ERROR("Fail!");
00084 
00085   moveit_msgs::RobotTrajectory traj2 = traj1;
00086   traj2.joint_trajectory.joint_names.push_back("lj2");
00087   traj2.joint_trajectory.points[0].positions.push_back(1.0);
00088   traj2.multi_dof_joint_trajectory.joint_names.push_back("basej");
00089   traj2.multi_dof_joint_trajectory.points.resize(1);
00090   traj2.multi_dof_joint_trajectory.points[0].transforms.resize(1);
00091 
00092   if (!tem.push(traj2))
00093     ROS_ERROR("Fail!");
00094 
00095   traj1.multi_dof_joint_trajectory = traj2.multi_dof_joint_trajectory;
00096   if (!tem.push(traj1))
00097     ROS_ERROR("Fail!");
00098 
00099   if (!tem.executeAndWait())
00100     ROS_ERROR("Fail!");
00101 
00102   ros::waitForShutdown();
00103 
00104   return 0;
00105 }


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Wed Aug 26 2015 12:43:30