#include <moveit/move_group_interface/move_group_interface.h> #include <moveit/planning_scene_interface/planning_scene_interface.h> #include <moveit_msgs/DisplayRobotState.h> #include <moveit_msgs/DisplayTrajectory.h> #include <trajectory_msgs/JointTrajectoryPoint.h> /** * minimal demo of constraint aware planning */ int main(int argc, char** argv) { ros::init(argc, argv, "SIMPLE PLANNER"); ros::NodeHandle node_handle; ros::AsyncSpinner spinner(1); spinner.start(); // wait for robot init of robot_state_initializer ROS_INFO_NAMED("simple_planner", ">>>>>>>>>>>>>>>>> WAITING FOR ROBOT INIT <<<<<<<<<<<<<<<<"); ros::Duration(5.0).sleep(); ROS_INFO_NAMED("simple_planner", ">>>>>>>>>>>>>>>>> WAKING UP AFTER INIT <<<<<<<<<<<<<<<<"); static const std::string PLANNING_GROUP = "panda_arm"; moveit::planning_interface::MoveGroupInterface move_group(PLANNING_GROUP); moveit::planning_interface::PlanningSceneInterface planning_scene_interface; const robot_state::JointModelGroup* joint_model_group = move_group.getCurrentState()->getJointModelGroup(PLANNING_GROUP); Eigen::Isometry3d text_pose = Eigen::Isometry3d::Identity(); text_pose.translation().z() = 1.75; // Getting Basic Information ROS_INFO_NAMED("simple_planner", "Planning frame: %s", move_group.getPlanningFrame().c_str()); ROS_INFO_NAMED("simple_planner", "End effector link: %s", move_group.getEndEffectorLink().c_str()); ROS_INFO_NAMED("simple_planner", "Available Planning Groups:"); std::copy(move_group.getJointModelGroupNames().begin(), move_group.getJointModelGroupNames().end(), std::ostream_iterator<std::string>(std::cout, ", ")); move_group.setStartState(*move_group.getCurrentState()); geometry_msgs::Pose another_pose; another_pose.orientation.w = 1.0; another_pose.position.x = 0.4; another_pose.position.y = -0.4; another_pose.position.z = 0.9; move_group.setPoseTarget(another_pose); moveit::planning_interface::MoveGroupInterface::Plan my_plan; bool success = (move_group.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS); ROS_INFO_NAMED("simple_planner", "Visualizing constraint plan %s", success ? "" : "FAILED"); // Move the simulated robot in gazebo move_group.move(); ros::shutdown(); return 0; }