test_app.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
40 
41 int main(int argc, char** argv)
42 {
43  ros::init(argc, argv, "test_trajectory_execution_manager");
44 
46  spinner.start();
47 
48  robot_model_loader::RobotModelLoaderPtr rml(new robot_model_loader::RobotModelLoader);
51 
52  std::cout << "1:\n";
53  if (!tem.ensureActiveControllersForJoints(std::vector<std::string>(1, "basej")))
54  ROS_ERROR("Fail!");
55 
56  std::cout << "2:\n";
57  if (!tem.ensureActiveController("arms"))
58  ROS_ERROR("Fail!");
59 
60  std::cout << "3:\n";
61  if (!tem.ensureActiveControllersForJoints(std::vector<std::string>(1, "rj2")))
62  ROS_ERROR("Fail!");
63 
64  std::cout << "4:\n";
65  if (!tem.ensureActiveControllersForJoints(std::vector<std::string>(1, "lj1")))
66  ROS_ERROR("Fail!");
67 
68  std::cout << "5:\n";
69  if (!tem.ensureActiveController("left_arm_head"))
70  ROS_ERROR("Fail!");
71  std::cout << "6:\n";
72  if (!tem.ensureActiveController("arms"))
73  ROS_ERROR("Fail!");
74 
75  // execute with empty set of trajectories
76  tem.execute();
77  if (!tem.waitForExecution())
78  ROS_ERROR("Fail!");
79 
80  moveit_msgs::RobotTrajectory traj1;
81  traj1.joint_trajectory.joint_names.push_back("rj1");
82  traj1.joint_trajectory.points.resize(1);
83  traj1.joint_trajectory.points[0].positions.push_back(0.0);
84  if (!tem.push(traj1))
85  ROS_ERROR("Fail!");
86 
87  moveit_msgs::RobotTrajectory traj2 = traj1;
88  traj2.joint_trajectory.joint_names.push_back("lj2");
89  traj2.joint_trajectory.points[0].positions.push_back(1.0);
90  traj2.multi_dof_joint_trajectory.joint_names.push_back("basej");
91  traj2.multi_dof_joint_trajectory.points.resize(1);
92  traj2.multi_dof_joint_trajectory.points[0].transforms.resize(1);
93 
94  if (!tem.push(traj2))
95  ROS_ERROR("Fail!");
96 
97  traj1.multi_dof_joint_trajectory = traj2.multi_dof_joint_trajectory;
98  if (!tem.push(traj1))
99  ROS_ERROR("Fail!");
100 
101  if (!tem.executeAndWait())
102  ROS_ERROR("Fail!");
103 
105 
106  return 0;
107 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void spinner()
const CurrentStateMonitorPtr & getStateMonitor() const
Get the stored instance of the stored current state monitor.
PlanningSceneMonitor Subscribes to the topic planning_scene.
int main(int argc, char **argv)
Definition: test_app.cpp:41
#define ROS_ERROR(...)
ROSCPP_DECL void waitForShutdown()


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Wed Jul 10 2019 04:03:32