Skip to content
Snippets Groups Projects
Select Git revision
  • 64243a07cc3428daa5e3818578ae04a882770b6e
  • master default protected
  • grasping_sample
3 results

BasicJointSpacePlanner.cpp

Blame
  • Forked from CeTI / ROS / ROS Packages / sample_applications
    Source project has a limited visibility.
    BasicJointSpacePlanner.cpp 3.03 KiB
    #include <moveit/move_group_interface/move_group_interface.h>
    #include <moveit/planning_scene_interface/planning_scene_interface.h>
    
    #include <moveit_msgs/CollisionObject.h>
    
    #include <moveit_visual_tools/moveit_visual_tools.h>
    #include <moveit/trajectory_processing/iterative_time_parameterization.h>
    #include <trajectory_msgs/JointTrajectoryPoint.h>
    
    /**
     * simple demo of a robotic motion
     */
    int main(int argc, char **argv) {
        // init the node
        ros::init(argc, argv, "basic_joint_space_planner");
        ros::NodeHandle node_handle;
        ros::AsyncSpinner spinner(1);
        spinner.start();
    
        // setup the planning environment
        static const std::string PLANNING_GROUP = "panda_arm";
        moveit::planning_interface::MoveGroupInterface move_group(PLANNING_GROUP);
        moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
    
        // visualization setup
        // MoveIts visual tools provide capabilities for visualizing objects, robots, and trajectories in RViz
        namespace rvt = rviz_visual_tools;
        moveit_visual_tools::MoveItVisualTools visual_tools("panda_link0");
    
        // Batch publishing is used to reduce the number of messages being sent to RViz for large visualizations
        visual_tools.enableBatchPublishing();
    
        // remote control is an introspection tool that allows users to step through a high level script
        // via buttons and keyboard shortcuts in RViz
        visual_tools.loadRemoteControl();
        ros::Duration(3.0).sleep();
    
        // we can use visual_tools to wait for user input
        visual_tools.prompt("Press 'next' to plan the motion. \n");
        visual_tools.trigger();
    
        // getting basic information
        ROS_INFO("Planning frame: %s", move_group.getPlanningFrame().c_str());
        ROS_INFO("End effector link: %s", move_group.getEndEffectorLink().c_str());
        ROS_INFO("Available Planning Groups:");
        std::copy(move_group.getJointModelGroupNames().begin(), move_group.getJointModelGroupNames().end(),
                  std::ostream_iterator<std::string>(std::cout, ", "));
    
        move_group.setStartStateToCurrentState();
    
        // define start and target pose (by specifying the desired pose of the end-effector)
        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);
    
        // uncomment to modify maximum velocity and acceleration of the motion to be planned
        /*
    
        move_group.setMaxVelocityScalingFactor(0.1);
        move_group.setMaxAccelerationScalingFactor(0.1);
    
         */
    
        // create a plan object and plan the motion
        moveit::planning_interface::MoveGroupInterface::Plan my_plan;
        bool success = (move_group.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS);
        ROS_INFO("Visualizing plan %s", success ? "" : "FAILED");
    
        visual_tools.trigger();
        visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to continue the demo");
    
        // Move the (simulated) robot in gazebo
        move_group.move();
    
        ros::shutdown();
        return 0;
    }