evaluate_state_operations_speed.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, 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 #include <ros/ros.h>
41 
42 static const std::string ROBOT_DESCRIPTION = "robot_description";
43 
44 int main(int argc, char** argv)
45 {
46  ros::init(argc, argv, "evaluate_state_operations_speed");
47 
49  spinner.start();
50 
52  ros::Duration(0.5).sleep();
53 
54  robot_model::RobotModelConstPtr robot_model = rml.getModel();
55  if (robot_model)
56  {
57  static const int N = 10000;
58  robot_state::RobotState state(robot_model);
59 
60  printf("Evaluating model '%s' using %d trials for each test\n", robot_model->getName().c_str(), N);
61 
64 
65  printf("Evaluating FK Default ...\n");
66  for (int i = 0; i < N; ++i)
67  {
68  moveit::tools::Profiler::Begin("FK Default");
69  state.setToDefaultValues();
70  state.update();
71  moveit::tools::Profiler::End("FK Default");
72  }
73 
74  printf("Evaluating FK Random ...\n");
75  for (int i = 0; i < N; ++i)
76  {
77  moveit::tools::Profiler::Begin("FK Random");
78  state.setToRandomPositions();
79  state.update();
80  moveit::tools::Profiler::End("FK Random");
81  }
82 
83  std::vector<robot_state::RobotState*> copies(N, (robot_state::RobotState*)NULL);
84  printf("Evaluating Copy State ...\n");
85  for (int i = 0; i < N; ++i)
86  {
87  moveit::tools::Profiler::Begin("Copy State");
88  copies[i] = new robot_state::RobotState(state);
89  moveit::tools::Profiler::End("Copy State");
90  }
91 
92  printf("Evaluating Free State ...\n");
93  for (int i = 0; i < N; ++i)
94  {
95  moveit::tools::Profiler::Begin("Free State");
96  delete copies[i];
97  moveit::tools::Profiler::End("Free State");
98  }
99 
100  const std::vector<std::string>& groups = robot_model->getJointModelGroupNames();
101  for (std::size_t j = 0; j < groups.size(); ++j)
102  {
103  printf("\n");
104  const robot_model::JointModelGroup* jmg = robot_model->getJointModelGroup(groups[j]);
105 
106  printf("%s: Evaluating FK Random ...\n", groups[j].c_str());
107  std::string pname = groups[j] + ":FK Random";
108  for (int i = 0; i < N; ++i)
109  {
111  state.setToRandomPositions(jmg);
112  state.update();
114  }
115  }
116 
119  }
120  else
121  ROS_ERROR("Unable to initialize robot model.");
122 
123  ros::shutdown();
124  return 0;
125 }
static void Stop(void)
static void Start(void)
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static void Begin(const std::string &name)
void spinner()
static void End(const std::string &name)
static const std::string ROBOT_DESCRIPTION
ROSCPP_DECL void shutdown()
const robot_model::RobotModelPtr & getModel() const
Get the constructed planning_models::RobotModel.
static void Clear(void)
static void Status(std::ostream &out=std::cout, bool merge=true)
#define ROS_ERROR(...)
int main(int argc, char **argv)


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sun Oct 18 2020 13:17:33