call_benchmark.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 <planning_scene_monitor/planning_scene_monitor.h>
00038 #include <moveit_msgs/ComputePlanningBenchmark.h>
00039 #include <kinematic_constraints/utils.h>
00040 
00041 static const std::string ROBOT_DESCRIPTION="robot_description";
00042 static const std::string BENCHMARK_SERVICE_NAME="benchmark_planning_problem"; // name of the advertised service (within the ~ namespace)
00043 
00044 int main(int argc, char **argv)
00045 {
00046   ros::init(argc, argv, "call_moveit_benchmark", ros::init_options::AnonymousName);
00047 
00048   ros::AsyncSpinner spinner(1);
00049   spinner.start();
00050 
00051   // fill a benchmark request
00052   moveit_msgs::ComputePlanningBenchmark::Request req;
00053   moveit_msgs::ComputePlanningBenchmark::Request res;
00054 
00055   // fill planning scene
00056   boost::shared_ptr<tf::TransformListener> tf(new tf::TransformListener());
00057   planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION, tf);
00058 
00059   Eigen::Affine3d t;
00060   t = Eigen::Translation3d(0.45, -0.45, 0.7);
00061   psm.getPlanningScene()->getWorldNonConst()->addToObject("pole", shapes::ShapePtr(new shapes::Box(0.1, 0.1, 1.4)), t);
00062 
00063   if (psm.getPlanningScene()->isConfigured())
00064     psm.getPlanningScene()->getPlanningSceneMsg(req.scene);
00065   req.motion_plan_request.start_state = req.scene.robot_state;
00066 
00067   // average over 3 runs
00068   req.default_average_count = 10;
00069   req.filename = "benchmark_results.log";
00070 
00071   // fill in a goal
00072   req.motion_plan_request.group_name = "right_arm";
00073   req.motion_plan_request.num_planning_attempts = 1;
00074   req.motion_plan_request.allowed_planning_time = ros::Duration(5.0);
00075 
00076   const std::vector<std::string>& joint_names = psm.getPlanningScene()->getRobotModel()->getJointModelGroup("right_arm")->getJointModelNames();
00077   req.motion_plan_request.goal_constraints.resize(1);
00078   req.motion_plan_request.goal_constraints[0].joint_constraints.resize(joint_names.size());
00079   for(unsigned int i = 0; i < joint_names.size(); i++)
00080   {
00081       req.motion_plan_request.goal_constraints[0].joint_constraints[i].joint_name = joint_names[i];
00082       req.motion_plan_request.goal_constraints[0].joint_constraints[i].position = 0.0;
00083       req.motion_plan_request.goal_constraints[0].joint_constraints[i].tolerance_above = 0.001;
00084       req.motion_plan_request.goal_constraints[0].joint_constraints[i].tolerance_below = 0.001;
00085       req.motion_plan_request.goal_constraints[0].joint_constraints[i].weight = 1.0;
00086   }
00087   req.motion_plan_request.goal_constraints[0].joint_constraints[0].position = -2.0;
00088   req.motion_plan_request.goal_constraints[0].joint_constraints[3].position = -.2;
00089   req.motion_plan_request.goal_constraints[0].joint_constraints[5].position = -.2;
00090   /*
00091 
00092   geometry_msgs::PoseStamped pose;
00093   pose.header.frame_id = psm.getPlanningScene()->getRobotModel()->getModelFrame();
00094   pose.pose.position.x = 0.55;
00095   pose.pose.position.y = 0.2;
00096   pose.pose.position.z = 1.25;
00097   pose.pose.orientation.x = 0.0;
00098   pose.pose.orientation.y = 0.0;
00099   pose.pose.orientation.z = 0.0;
00100   pose.pose.orientation.w = 1.0;
00101   moveit_msgs::Constraints goal = kinematic_constraints::constructGoalConstraints("r_wrist_roll_link", pose);
00102   req.motion_plan_request.goal_constraints.push_back(goal);
00103   */
00104 
00105   req.planner_interfaces.resize(1);
00106   req.planner_interfaces[0].name = "ompl_interface_ros/OMPLPlanner";
00107 
00108   ros::NodeHandle nh;
00109   ros::service::waitForService(BENCHMARK_SERVICE_NAME);
00110   ros::ServiceClient benchmark_service_client = nh.serviceClient<moveit_msgs::ComputePlanningBenchmark>(BENCHMARK_SERVICE_NAME);
00111   if (!benchmark_service_client.call(req, res))
00112       ROS_ERROR("Error calling benchmark service");
00113 
00114   ros::waitForShutdown();
00115 
00116   return 0;
00117 }


pr2_simple_benchmark_test
Author(s): Ioan Sucan
autogenerated on Mon Sep 14 2015 14:18:08