00001 #include "constrained_ik/constrained_ik.h" 00002 #include "constrained_ik/enum_types.h" 00003 #include "constrained_ik/constraints/goal_minimize_change.h" 00004 #include "example_utils.h" 00005 #include <moveit/robot_model_loader/robot_model_loader.h> 00006 #include <moveit/planning_scene/planning_scene.h> 00007 00008 using namespace constrained_ik; 00009 using namespace constrained_ik::basic_kin; 00010 using namespace Eigen; 00011 00016 int main(int argc, char *argv[]) 00017 { 00018 ros::init(argc, argv, "goal_minimize_change_example"); 00019 Constrained_IK ik; 00020 BasicKin kin; 00021 robot_model_loader::RobotModelLoaderPtr loader; 00022 00023 // Load example robot model 00024 getExampleRobotData(loader); 00025 00026 // Initialize kinematic model 00027 kin.init(loader->getModel()->getJointModelGroup("manipulator")); 00028 00029 // Create constraint 00030 constraints::GoalMinimizeChange *constraint = new constraints::GoalMinimizeChange; 00031 constraint->setDebug(false); 00032 constraint->setWeight(1.0); 00033 00034 // Add constraint to solver 00035 ik.addConstraint(constraint, constraint_types::Primary); 00036 00037 // Initialize Solver 00038 ik.init(kin); 00039 00040 // Calculate IK for sample case 00041 evaluteExampleIK(kin, ik); 00042 00043 return 0; 00044 }