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


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