clik_valgrind.cpp
Go to the documentation of this file.
00001 
00026 #include <kdl_parser/kdl_parser.hpp>
00027 #include <ros/ros.h>
00028 #include <ros/package.h>
00029 #include <ros/console.h>
00030 #include <string.h>
00031 #include <moveit/robot_model_loader/robot_model_loader.h>
00032 #include <moveit/robot_model/joint_model_group.h>
00033 #include <moveit/robot_state/conversions.h>
00034 #include <moveit/kinematic_constraints/kinematic_constraint.h>
00035 #include <moveit/kinematic_constraints/utils.h>
00036 #include <moveit/collision_plugin_loader/collision_plugin_loader.h>
00037 #include <constrained_ik/moveit_interface/joint_interpolation_planner.h>
00038 #include <constrained_ik/CLIKPlannerDynamicConfig.h>
00039 #include <fstream>
00040 #include <time.h>
00041 #include <constrained_ik/moveit_interface/cartesian_planner.h>
00042 
00043 
00044 using namespace ros;
00045 using namespace constrained_ik;
00046 using namespace Eigen;
00047 using namespace moveit::core;
00048 using namespace std;
00049 
00050 typedef boost::shared_ptr<collision_detection::CollisionPlugin> CollisionPluginPtr;
00051 
00052 int main (int argc, char *argv[])
00053 {
00054   ros::init(argc,argv,"stomp_valgrid");
00055   ros::NodeHandle pnh;
00056 
00057 
00058   if (ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug))
00059      ros::console::notifyLoggerLevelsChanged();
00060 
00061   sleep(1);
00062   robot_model_loader::RobotModelLoaderPtr loader;
00063   robot_model::RobotModelPtr robot_model;
00064   string urdf_file_path, srdf_file_path;
00065 
00066   urdf_file_path = package::getPath("stomp_test_support") + "/urdf/test_kr210l150_500K.urdf";
00067   srdf_file_path = package::getPath("stomp_test_kr210_moveit_config") + "/config/test_kr210.srdf";
00068 
00069   ifstream ifs1 (urdf_file_path.c_str());
00070   string urdf_string((istreambuf_iterator<char>(ifs1)), (istreambuf_iterator<char>()));
00071 
00072   ifstream ifs2 (srdf_file_path.c_str());
00073   string srdf_string((istreambuf_iterator<char>(ifs2)), (istreambuf_iterator<char>()));
00074 
00075   robot_model_loader::RobotModelLoader::Options opts(urdf_string, srdf_string);
00076   loader.reset(new robot_model_loader::RobotModelLoader(opts));
00077   robot_model = loader->getModel();
00078 
00079   if (!robot_model)
00080   {
00081     ROS_ERROR_STREAM("Unable to load robot model from urdf and srdf.");
00082     return false;
00083   }
00084 
00085   collision_detection::CollisionPluginLoader cd_loader;
00086   CLIKPlannerDynamicConfig config;
00087   config.joint_discretization_step = 0.02;
00088   config.translational_discretization_step = 0.02;
00089   config.orientational_discretization_step = 0.02;
00090   planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model));
00091 
00092   //Now assign collision detection plugin
00093   std::string class_name = "IndustrialFCL";
00094   cd_loader.setupScene(pnh, planning_scene);
00095   cd_loader.activate(class_name, planning_scene, true);
00096 
00097   planning_interface::MotionPlanRequest req;
00098   planning_interface::MotionPlanResponse res;
00099   string group_name = "manipulator_rail";
00100   CartesianPlanner cart_planner("", group_name);
00101   cart_planner.setPlannerConfiguration(config);
00102 
00103   req.allowed_planning_time = 100;
00104   req.num_planning_attempts = 1;
00105   req.group_name = group_name;
00106 
00107   robot_state::RobotState start = planning_scene->getCurrentState();
00108   map<string, double> jstart;
00109   jstart.insert(make_pair("joint_1", 1.4149));
00110   jstart.insert(make_pair("joint_2", 0.5530));
00111   jstart.insert(make_pair("joint_3", 0.1098));
00112   jstart.insert(make_pair("joint_4", -1.0295));
00113   jstart.insert(make_pair("joint_5", 0.0000));
00114   jstart.insert(make_pair("joint_6", 0.0000));
00115   jstart.insert(make_pair("rail_to_base", 1.3933));
00116 
00117   start.setVariablePositions(jstart);
00118   robotStateToRobotStateMsg(start, req.start_state);
00119   req.start_state.is_diff = true;
00120 
00121   robot_state::RobotState goal = planning_scene->getCurrentState();
00122   map<string, double> jgoal;
00123   jgoal.insert(make_pair("joint_1", 1.3060));
00124   jgoal.insert(make_pair("joint_2", -0.2627));
00125   jgoal.insert(make_pair("joint_3", 0.2985));
00126   jgoal.insert(make_pair("joint_4", -0.8236));
00127   jgoal.insert(make_pair("joint_5", 0.0000));
00128   jgoal.insert(make_pair("joint_6", 0.0000));
00129   jgoal.insert(make_pair("rail_to_base", -1.2584));
00130 
00131   goal.setVariablePositions(jgoal);
00132 
00133   vector<double> dist(7);
00134   dist[0] = 0.05;
00135   dist[1] = 0.05;
00136   dist[2] = 0.05;
00137   dist[3] = 0.05;
00138   dist[4] = 0.05;
00139   dist[5] = 0.05;
00140   dist[6] = 0.05;
00141 
00142   ros::Time t1, t2;
00143   t1 = ros::Time::now();
00144   const robot_state::JointModelGroup *jmg = goal.getJointModelGroup(group_name);
00145   int test_runs = 10;
00146   for (int i = 0; i < test_runs; i++)
00147   {
00148     if (jmg)
00149     {
00150       robot_state::RobotState new_goal = goal;
00151       new_goal.setToRandomPositionsNearBy(jmg, goal, dist);
00152       req.goal_constraints.resize(1);
00153       req.goal_constraints[0] = kinematic_constraints::constructGoalConstraints(new_goal, jmg);
00154     }
00155 
00156     cart_planner.clear();
00157     cart_planner.setPlanningScene(planning_scene);
00158     cart_planner.setMotionPlanRequest(req);
00159 
00160     if (!cart_planner.solve(res))
00161       ROS_ERROR("Cartesian Solver failed (%d): %d", i, res.error_code_.val);
00162 
00163   }
00164   t2 = ros::Time::now();
00165 
00166   ROS_ERROR("Average time spent calculating trajectory: %4.10f seconds", (t2-t1).toSec()/test_runs);
00167   return 0;
00168 }


industrial_moveit_benchmarking
Author(s): Levi Armstrong
autogenerated on Sat Jun 8 2019 19:24:11