evaluate_state_operations_speed.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2013, 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 the 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/robot_model_loader/robot_model_loader.h>
00038 #include <moveit/robot_state/robot_state.h>
00039 #include <moveit/profiler/profiler.h>
00040 #include <ros/ros.h>
00041 
00042 static const std::string ROBOT_DESCRIPTION = "robot_description";
00043 
00044 int main(int argc, char **argv)
00045 {
00046     ros::init(argc, argv, "evaluate_state_operations_speed");
00047 
00048     ros::AsyncSpinner spinner(1);
00049     spinner.start();
00050 
00051     robot_model_loader::RobotModelLoader rml(ROBOT_DESCRIPTION);
00052     ros::Duration(0.5).sleep();
00053 
00054     robot_model::RobotModelConstPtr robot_model = rml.getModel();
00055     if (robot_model)
00056     {
00057       static const int N = 10000;
00058       robot_state::RobotState state(robot_model);
00059 
00060       printf("Evaluating model '%s' using %d trials for each test\n", robot_model->getName().c_str(), N);
00061 
00062       moveit::Profiler::Clear();
00063       moveit::Profiler::Start();
00064 
00065       printf("Evaluating FK Default ...\n");
00066       for (int i = 0 ; i < N ; ++i)
00067       {
00068         moveit::Profiler::Begin("FK Default");
00069         state.setToDefaultValues();
00070         moveit::Profiler::End("FK Default");
00071       }
00072 
00073       printf("Evaluating FK Random ...\n");
00074       for (int i = 0 ; i < N ; ++i)
00075       {
00076         moveit::Profiler::Begin("FK Random");
00077         state.setToRandomValues();
00078         moveit::Profiler::End("FK Random");
00079       }
00080       std::vector<robot_state::RobotState*> copies(N, (robot_state::RobotState*)NULL);
00081       printf("Evaluating Copy State ...\n");
00082       for (int i = 0 ; i < N ; ++i)
00083       {
00084         moveit::Profiler::Begin("Copy State");
00085         copies[i] = new robot_state::RobotState(state);
00086         moveit::Profiler::End("Copy State");
00087       }
00088 
00089       printf("Evaluating Free State ...\n");
00090       for (int i = 0 ; i < N ; ++i)
00091       {
00092         moveit::Profiler::Begin("Free State");
00093         delete copies[i];
00094         moveit::Profiler::End("Free State");
00095       }
00096 
00097       const std::vector<std::string> &groups = robot_model->getJointModelGroupNames();
00098       for (std::size_t j = 0 ; j < groups.size() ; ++j)
00099       {
00100         printf("\n");
00101         robot_state::JointStateGroup *jsg = state.getJointStateGroup(groups[j]);
00102         printf("%s: Evaluating FK Default ...\n", groups[j].c_str());
00103         std::string pname = groups[j] + ":FK Default";
00104         for (int i = 0 ; i < N ; ++i)
00105         {
00106           moveit::Profiler::Begin(pname);
00107           jsg->setToDefaultValues();
00108           moveit::Profiler::End(pname);
00109         }
00110 
00111         printf("%s: Evaluating FK Random ...\n", groups[j].c_str());
00112         pname = groups[j] + ":FK Random";
00113         for (int i = 0 ; i < N ; ++i)
00114         {
00115           moveit::Profiler::Begin(pname);
00116           jsg->setToRandomValues();
00117           moveit::Profiler::End(pname);
00118         }
00119       }
00120 
00121       moveit::Profiler::Stop();
00122       moveit::Profiler::Status();
00123     }
00124     else
00125       ROS_ERROR("Unable to initialize robot model.");
00126 
00127     ros::shutdown();
00128     return 0;
00129 }


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:31:39