├── README.md ├── icl_robotiq_2f_gripper_action_server ├── CMakeLists.txt ├── include │ └── icl_robotiq_2f_gripper_action_server │ │ └── robotiq_2f_gripper_action_server.h ├── launch │ └── robotiq_2f_gripper_action_server.launch ├── package.xml └── src │ ├── robotiq_2f_gripper_action_server.cpp │ └── robotiq_2f_gripper_action_server_node.cpp ├── icl_ur5_setup_bringup ├── CMakeLists.txt ├── launch │ ├── activate_gripper.launch │ ├── old │ │ ├── moveit_bringup.launch │ │ ├── robotiq_bringup.launch │ │ ├── ur5_moveit_bringup.launch │ │ └── ur5_with_gripper.launch │ ├── ur5_bringup.launch │ ├── ur5_fts.launch │ ├── ur5_fts_gripper.launch │ └── ur5_gripper.launch ├── node │ └── gripper_joint_state_publisher.py ├── package.xml └── scenes │ ├── icl_scene.dae │ └── lab_setup.scene ├── icl_ur5_setup_description ├── CMakeLists.txt ├── LICENSE ├── README.md ├── launch │ ├── test_robotiq_arg_2f_140_model.launch │ └── ur5_gripper_upload.launch ├── meshes │ ├── icl_scene.dae │ ├── icl_setup.scene │ ├── robotiq_arg2f_140_finger_tip--.stl │ ├── robotiq_arg2f_140_finger_tip.dae │ ├── robotiq_arg2f_140_finger_tip.stl │ ├── robotiq_arg2f_140_inner_finger.stl │ ├── robotiq_arg2f_140_inner_finger_with_tip.stl │ ├── robotiq_arg2f_140_inner_knuckle.stl │ ├── robotiq_arg2f_140_outer_finger.stl │ ├── robotiq_arg2f_140_outer_knuckle.stl │ ├── robotiq_arg2f_base_link_coarse.stl │ ├── robotiq_arg2f_base_link_fine.stl │ └── robotiq_fts150.stl ├── package.xml ├── robots │ ├── ur5_robotiq_140.xacro │ └── ur5_robotiq_140_joint_limited.xacro ├── urdf │ ├── robotiq_arg2f.xacro │ ├── robotiq_arg2f_140_model.xacro │ ├── robotiq_arg2f_140_model_macro.xacro │ ├── robotiq_arg2f_finger_tips.xacro │ ├── robotiq_arg2f_transmission.xacro │ └── robotiq_fts300.urdf.xacro └── visualize.rviz ├── icl_ur5_setup_gazebo ├── CMakeLists.txt ├── config │ ├── arm_controller_ur5.yaml │ ├── gripper_controller_robotiq.yaml │ └── joint_state_controller.yaml ├── launch │ ├── controller_utils.launch │ └── icl_ur5_gripper.launch ├── package.xml └── worlds │ └── icl_ur5_setup.world ├── icl_ur5_setup_moveit_config ├── .setup_assistant ├── CMakeLists.txt ├── config │ ├── controllers.yaml │ ├── controllers_sim.yaml │ ├── fake_controllers.yaml │ ├── joint_limits.yaml │ ├── kinematics.yaml │ ├── ompl_planning.yaml │ ├── rgbd.yaml │ ├── sensors_kinect.yaml │ ├── ur5_gripper.srdf │ └── ur5_gripper_sim.srdf ├── frames.gv ├── frames.pdf ├── launch │ ├── default_warehouse_db.launch │ ├── demo.launch │ ├── fake_moveit_controller_manager.launch.xml │ ├── joystick_control.launch │ ├── move_group.launch │ ├── moveit.rviz │ ├── moveit_rviz.launch │ ├── ompl_planning_pipeline.launch.xml │ ├── planning_context.launch │ ├── planning_pipeline.launch.xml │ ├── run_benchmark_ompl.launch │ ├── sensor_manager.launch.xml │ ├── setup_assistant.launch │ ├── trajectory_execution.launch.xml │ ├── ur5_gripper_moveit_controller_manager.launch.xml │ ├── ur5_gripper_moveit_planning_execution.launch │ ├── ur5_gripper_moveit_sensor_manager.launch.xml │ ├── warehouse.launch │ └── warehouse_settings.launch.xml └── package.xml └── img └── simulation.png /README.md: -------------------------------------------------------------------------------- 1 | # ur5_with_robotiq_gripper 2 | Author: Yuxiang Gao and Yeping Wang 3 | 4 | --- 5 | __ROS Version__ : Kinetic 6 | 7 | __Dependence__ 8 | 9 | [universal_robot](https://github.com/ros-industrial/universal_robot) : URDFs and Meshes for UR5 10 | 11 | [ur_modern_driver](https://github.com/ros-industrial/ur_modern_driver) : Drivers for UR5. 12 | 13 | [robotiq](https://github.com/ros-industrial/robotiq) : Drivers for the Robotiq gripper. 14 | 15 | [roboticsgroup_gazebo_plugins](https://github.com/roboticsgroup/roboticsgroup_gazebo_plugins) : For the gripper simulation in Gazebo 16 | 17 | [ros_controllers]: For the CripperActionController. Can be installed with `sudo apt-get install ros-kinetic-ros-controllers` 18 | 19 | --- 20 | 21 | __Usage with Gazebo simulation__ 22 | 23 | ![](img/simulation.png) 24 | 25 | To start the Gazebo simulated ur5 and the gripper: 26 | 27 | ```roslaunch icl_ur5_setup_gazebo icl_ur5_gripper.launch``` 28 | 29 | Then bring up the moveit: 30 | 31 | ```roslaunch icl_ur5_setup_moveit_config ur5_gripper_moveit_planning_execution.launch sim:=true``` 32 | 33 | Finally, run a Rviz to visualize the trajectory: 34 | 35 | ```roslaunch icl_ur5_setup_moveit_config moveit_rviz.launch config:=true``` 36 | 37 | To bringup the slide bar for each joint: 38 | ``` 39 | rosrun rqt_joint_trajectory_controller rqt_joint_trajectory_controller 40 | ``` 41 | 42 | --- 43 | 44 | __Usage with the hardware__ 45 | 46 | This package communicates with Robotiq 140 gripper using the [robotiq_action_server](https://github.com/ros-industrial/robotiq/tree/kinetic-devel/robotiq_2f_gripper_action_server) through Modbus RTU protocol, so the first step to do is to connect the gripper using USB. 47 | 48 | To bring up the whole arm configuration with all drivers, you can use the following command: 49 | 50 | ```roslaunch icl_ur5_setup_bringup ur5_fts_gripper.launch``` 51 | 52 | If there are some connection error, you may need to change the `gripper_port`, `serial_id`, and `robot_ip` in the launch file. Currently, `gripper_port` is `ttyUSB0` and `serial_id` is `ttyUSB1`, these require you to plug the gripper's USB first then plug the force torque sensor's USB. To find the robot ip address: 53 | 54 | UR’s teach-pendant -> Setup Robot -> Setup Network Menu -> ip address 55 | 56 | If you don't need the force torque sensor, you just need to launch `ur5_gripper.launch` 57 | 58 | Activited the gripper: 59 | 60 | ```roslaunch icl_ur5_setup_bringup activate_gripper.launch``` 61 | 62 | Then press 'r' to reset and press 'a' to activite the gripper. 63 | 64 | Bring up the moveit: 65 | 66 | ```roslaunch icl_ur5_setup_moveit_config ur5_gripper_moveit_planning_execution.launch``` 67 | 68 | Finally, run a Rviz to visualize the trajectory: 69 | 70 | ```roslaunch icl_ur5_setup_moveit_config moveit_rviz.launch config:=true``` 71 | 72 | --- 73 | 74 | __To control the gripper__ 75 | 76 | Publish the position value to `icl_gripper/gripper_cmd/goal` (or the topic under a similar name). 77 | 78 | position value 0.0: open 79 | 80 | position value 0.8: close 81 | 82 | __Reference__ 83 | 84 | This repo learns a lot from [icl_phri_ur5](https://github.com/intuitivecomputing/icl_phri_ur5), [UR5-with-Robotiq-Gripper-and-Kinect](https://github.com/philwall3/UR5-with-Robotiq-Gripper-and-Kinect) and [tams_ur5_setup](https://github.com/TAMS-Group/tams_ur5_setup) 85 | -------------------------------------------------------------------------------- /icl_robotiq_2f_gripper_action_server/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(icl_robotiq_2f_gripper_action_server) 3 | 4 | find_package(catkin REQUIRED COMPONENTS 5 | actionlib 6 | actionlib_msgs 7 | message_generation 8 | robotiq_2f_gripper_control 9 | roscpp 10 | control_msgs 11 | ) 12 | 13 | catkin_package( 14 | INCLUDE_DIRS include 15 | CATKIN_DEPENDS actionlib actionlib_msgs robotiq_2f_gripper_control roscpp 16 | ) 17 | 18 | include_directories(include) 19 | include_directories( 20 | ${catkin_INCLUDE_DIRS} 21 | ${icl_robotiq_2f_gripper_action_server_INCLUDE_DIRS} 22 | ) 23 | 24 | # The action server 25 | add_executable(icl_robotiq_2f_gripper_action_server_node 26 | src/robotiq_2f_gripper_action_server_node.cpp 27 | src/robotiq_2f_gripper_action_server.cpp 28 | include/icl_robotiq_2f_gripper_action_server/robotiq_2f_gripper_action_server.h) 29 | 30 | add_dependencies(icl_robotiq_2f_gripper_action_server_node 31 | robotiq_2f_gripper_action_server_generate_messages_cpp 32 | ${icl_robotiq_2f_gripper_action_server_EXPORTED_TARGETS} 33 | ${icl_robotiq_2f_gripper_control_EXPORTED_TARGETS}) 34 | 35 | target_link_libraries(icl_robotiq_2f_gripper_action_server_node 36 | ${catkin_LIBRARIES} 37 | ) 38 | 39 | install(TARGETS icl_robotiq_2f_gripper_action_server_node 40 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 41 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 42 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 43 | ) 44 | 45 | install(DIRECTORY include/${PROJECT_NAME}/ 46 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 47 | FILES_MATCHING PATTERN "*.h" 48 | ) 49 | -------------------------------------------------------------------------------- /icl_robotiq_2f_gripper_action_server/include/icl_robotiq_2f_gripper_action_server/robotiq_2f_gripper_action_server.h: -------------------------------------------------------------------------------- 1 | /** 2 | * ActionServer interface to the control_msgs/GripperCommand action 3 | * for a Robotiq 2F gripper 4 | */ 5 | 6 | #ifndef ROBOTIQ_2F_GRIPPER_ACTION_SERVER_H 7 | #define ROBOTIQ_2F_GRIPPER_ACTION_SERVER_H 8 | 9 | // STL 10 | #include 11 | // ROS standard 12 | #include 13 | #include 14 | #include 15 | // Repo specific includes 16 | #include 17 | #include 18 | 19 | 20 | namespace robotiq_2f_gripper_action_server 21 | { 22 | 23 | typedef robotiq_2f_gripper_control::Robotiq2FGripper_robot_input GripperInput; 24 | typedef robotiq_2f_gripper_control::Robotiq2FGripper_robot_output GripperOutput; 25 | 26 | typedef control_msgs::GripperCommandGoal GripperCommandGoal; 27 | typedef control_msgs::GripperCommandFeedback GripperCommandFeedback; 28 | typedef control_msgs::GripperCommandResult GripperCommandResult; 29 | 30 | /** 31 | * @brief Structure containing the parameters necessary to translate 32 | * GripperCommand actions to register-based commands to a 33 | * particular gripper (and vice versa). 34 | * 35 | * The min gap can be less than zero. This represents the case where the 36 | * gripper fingers close and then push forward. 37 | */ 38 | struct Robotiq2FGripperParams 39 | { 40 | double min_gap_; // meters 41 | double max_gap_; 42 | double min_effort_; // N / (Nm) 43 | double max_effort_; 44 | }; 45 | 46 | /** 47 | * @brief The Robotiq2FGripperActionServer class. Takes as arguments the name of the gripper it is to command, 48 | * and a set of parameters that define the physical characteristics of the particular gripper. 49 | * 50 | * Listens for messages on input and publishes on output. Remap these. 51 | */ 52 | class Robotiq2FGripperActionServer 53 | { 54 | public: 55 | Robotiq2FGripperActionServer(const std::string& name, const Robotiq2FGripperParams& params); 56 | 57 | // These functions are meant to be called by simple action server 58 | void goalCB(); 59 | void preemptCB(); 60 | void analysisCB(const GripperInput::ConstPtr& msg); 61 | 62 | private: 63 | void issueActivation(); 64 | 65 | ros::NodeHandle nh_; 66 | actionlib::SimpleActionServer as_; 67 | 68 | ros::Subscriber state_sub_; // Subs to grippers "input" topic 69 | ros::Publisher goal_pub_; // Pubs to grippers "output" topic 70 | 71 | GripperOutput goal_reg_state_; // Goal information in gripper-register form 72 | GripperInput current_reg_state_; // State info in gripper-register form 73 | 74 | /* Used to translate GripperCommands in engineering units 75 | * to/from register states understood by gripper itself. Different 76 | * for different models/generations of Robotiq grippers */ 77 | Robotiq2FGripperParams gripper_params_; 78 | 79 | std::string action_name_; 80 | }; 81 | 82 | } 83 | #endif 84 | -------------------------------------------------------------------------------- /icl_robotiq_2f_gripper_action_server/launch/robotiq_2f_gripper_action_server.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /icl_robotiq_2f_gripper_action_server/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | icl_robotiq_2f_gripper_action_server 4 | 1.0.0 5 | 6 | 7 |

8 | This package defines protocol-agnostic action-server interfaces using the 9 | control_msgs::GripperCommand ROS interface for Robotiq grippers. Depending 10 | on your use case, you may need more fine grained control, but this is 11 | a good place to start. 12 |

13 |
14 | 15 | Jean-Philippe Roberge 16 | Jonathan Meyer 17 | BSD 18 | 19 | catkin 20 | actionlib 21 | actionlib_msgs 22 | control_msgs 23 | robotiq_2f_gripper_control 24 | roscpp 25 | 26 |
27 | -------------------------------------------------------------------------------- /icl_robotiq_2f_gripper_action_server/src/robotiq_2f_gripper_action_server.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * ActionServer interface to the control_msgs/GripperCommand action 3 | * for a Robotiq 2F gripper 4 | */ 5 | 6 | #include "icl_robotiq_2f_gripper_action_server/robotiq_2f_gripper_action_server.h" 7 | 8 | // To keep the fully qualified names managable 9 | 10 | //Anonymous namespaces are file local -> sort of like global static objects 11 | namespace 12 | { 13 | using namespace robotiq_2f_gripper_action_server; 14 | 15 | /* This struct is declared for the sole purpose of being used as an exception internally 16 | to keep the code clean (i.e. no output params). It is caught by the action_server and 17 | should not propogate outwards. If you use these functions yourself, beware. 18 | */ 19 | struct BadArgumentsError {}; 20 | 21 | 22 | GripperOutput goalToRegisterState(const GripperCommandGoal& goal, const Robotiq2FGripperParams& params) 23 | { 24 | GripperOutput result; 25 | result.rACT = 0x1; // active gripper 26 | result.rGTO = 0x1; // go to position 27 | result.rATR = 0x0; // No emergency release 28 | result.rSP = 128; // Middle ground speed 29 | 30 | if (goal.command.position > params.max_gap_ || goal.command.position < params.min_gap_) 31 | { 32 | ROS_WARN("Goal gripper gap size is out of range(%f to %f): %f m", 33 | params.min_gap_, params.max_gap_, goal.command.position); 34 | throw BadArgumentsError(); 35 | } 36 | 37 | if (goal.command.max_effort < params.min_effort_ || goal.command.max_effort > params.max_effort_) 38 | { 39 | ROS_WARN("Goal gripper effort out of range (%f to %f N): %f N", 40 | params.min_effort_, params.max_effort_, goal.command.max_effort); 41 | throw BadArgumentsError(); 42 | } 43 | 44 | double dist_per_tick = (params.max_gap_ - params.min_gap_) / 255; 45 | double eff_per_tick = (params.max_effort_ - params.min_effort_) / 255; 46 | 47 | result.rPR = static_cast((params.max_gap_ - goal.command.position) / dist_per_tick); 48 | result.rFR = static_cast((goal.command.max_effort - params.min_effort_) / eff_per_tick); 49 | 50 | ROS_INFO("Setting goal position register to %hhu", result.rPR); 51 | 52 | return result; 53 | } 54 | 55 | /* This function is templatized because both GripperCommandResult and GripperCommandFeedback consist 56 | of the same fields yet have different types. Templates here act as a "duck typing" mechanism to avoid 57 | code duplication. 58 | */ 59 | template 60 | T registerStateToResultT(const GripperInput& input, const Robotiq2FGripperParams& params, uint8_t goal_pos) 61 | { 62 | T result; 63 | double dist_per_tick = (params.max_gap_ - params.min_gap_) / 255; 64 | double eff_per_tick = (params.max_effort_ - params.min_effort_) / 255; 65 | 66 | result.position = input.gPO * dist_per_tick + params.min_gap_; 67 | result.effort = input.gCU * eff_per_tick + params.min_effort_; 68 | result.stalled = input.gOBJ == 0x1 || input.gOBJ == 0x2; 69 | result.reached_goal = input.gPO == goal_pos; 70 | 71 | return result; 72 | } 73 | 74 | // Inline api-transformers to avoid confusion when reading the action_server source 75 | inline 76 | GripperCommandResult registerStateToResult(const GripperInput& input, const Robotiq2FGripperParams& params, uint8_t goal_pos) 77 | { 78 | return registerStateToResultT(input, params, goal_pos); 79 | } 80 | 81 | inline 82 | GripperCommandFeedback registerStateToFeedback(const GripperInput& input, const Robotiq2FGripperParams& params, uint8_t goal_pos) 83 | { 84 | return registerStateToResultT(input, params, goal_pos); 85 | } 86 | 87 | } // end of anon namespace 88 | 89 | namespace robotiq_2f_gripper_action_server 90 | { 91 | 92 | Robotiq2FGripperActionServer::Robotiq2FGripperActionServer(const std::string& name, const Robotiq2FGripperParams& params) 93 | : nh_() 94 | , as_(nh_, name, false) 95 | , action_name_(name) 96 | , gripper_params_(params) 97 | { 98 | as_.registerGoalCallback(boost::bind(&Robotiq2FGripperActionServer::goalCB, this)); 99 | as_.registerPreemptCallback(boost::bind(&Robotiq2FGripperActionServer::preemptCB, this)); 100 | 101 | state_sub_ = nh_.subscribe("input", 1, &Robotiq2FGripperActionServer::analysisCB, this); 102 | goal_pub_ = nh_.advertise("output", 1); 103 | 104 | as_.start(); 105 | } 106 | 107 | void Robotiq2FGripperActionServer::goalCB() 108 | { 109 | // Check to see if the gripper is in an active state where it can take goals 110 | if (current_reg_state_.gSTA != 0x3) 111 | { 112 | ROS_WARN("%s could not accept goal because the gripper is not yet active", action_name_.c_str()); 113 | return; 114 | } 115 | 116 | GripperCommandGoal current_goal (*(as_.acceptNewGoal())); 117 | 118 | current_goal.command.max_effort = 100.0; 119 | double position = current_goal.command.position; 120 | current_goal.command.position = position * (-0.102) + 0.0848; 121 | 122 | if (as_.isPreemptRequested()) 123 | { 124 | as_.setPreempted(); 125 | } 126 | 127 | try 128 | { 129 | goal_reg_state_ = goalToRegisterState(current_goal, gripper_params_); 130 | goal_pub_.publish(goal_reg_state_); 131 | } 132 | catch (BadArgumentsError& e) 133 | { 134 | ROS_INFO("%s No goal issued to gripper", action_name_.c_str()); 135 | } 136 | } 137 | 138 | void Robotiq2FGripperActionServer::preemptCB() 139 | { 140 | ROS_INFO("%s: Preempted", action_name_.c_str()); 141 | as_.setPreempted(); 142 | } 143 | 144 | void Robotiq2FGripperActionServer::analysisCB(const GripperInput::ConstPtr& msg) 145 | { 146 | current_reg_state_ = *msg; 147 | 148 | if (!as_.isActive()) return; 149 | 150 | // Check to see if the gripper is in its activated state 151 | if (current_reg_state_.gSTA != 0x3) 152 | { 153 | // Check to see if the gripper is active or if it has been asked to be active 154 | if (current_reg_state_.gSTA == 0x0 && goal_reg_state_.rACT != 0x1) 155 | { 156 | // If it hasn't been asked, active it 157 | issueActivation(); 158 | } 159 | 160 | // Otherwise wait for the gripper to activate 161 | // TODO: If message delivery isn't guaranteed, then we may want to resend activate 162 | return; 163 | } 164 | 165 | // Check for errors 166 | if (current_reg_state_.gFLT) 167 | { 168 | ROS_WARN("%s faulted with code: %x", action_name_.c_str(), current_reg_state_.gFLT); 169 | as_.setAborted(registerStateToResult(current_reg_state_, 170 | gripper_params_, 171 | goal_reg_state_.rPR)); 172 | } 173 | else if (current_reg_state_.gGTO && current_reg_state_.gOBJ && current_reg_state_.gPR == goal_reg_state_.rPR) 174 | { 175 | // If commanded to move and if at a goal state and if the position request matches the echo'd PR, we're 176 | // done with a move 177 | ROS_INFO("%s succeeded", action_name_.c_str()); 178 | as_.setSucceeded(registerStateToResult(current_reg_state_, 179 | gripper_params_, 180 | goal_reg_state_.rPR)); 181 | } 182 | else 183 | { 184 | // Publish feedback 185 | as_.publishFeedback(registerStateToFeedback(current_reg_state_, 186 | gripper_params_, 187 | goal_reg_state_.rPR)); 188 | } 189 | } 190 | 191 | void Robotiq2FGripperActionServer::issueActivation() 192 | { 193 | ROS_INFO("Activating gripper for gripper action server: %s", action_name_.c_str()); 194 | GripperOutput out; 195 | out.rACT = 0x1; 196 | // other params should be zero 197 | goal_reg_state_ = out; 198 | goal_pub_.publish(out); 199 | } 200 | } // end robotiq_2f_gripper_action_server namespace 201 | -------------------------------------------------------------------------------- /icl_robotiq_2f_gripper_action_server/src/robotiq_2f_gripper_action_server_node.cpp: -------------------------------------------------------------------------------- 1 | #include "icl_robotiq_2f_gripper_action_server/robotiq_2f_gripper_action_server.h" 2 | 3 | namespace 4 | { 5 | // Defines a default for the c2 model 85 gripper 6 | robotiq_2f_gripper_action_server::Robotiq2FGripperParams c2_85_defaults() 7 | { 8 | robotiq_2f_gripper_action_server::Robotiq2FGripperParams params; 9 | params.min_gap_ = -.017; 10 | params.max_gap_ = 0.085; 11 | params.min_effort_ = 40.0; // This is a guess. Could not find data with quick search. 12 | params.max_effort_ = 100.0; 13 | 14 | return params; 15 | } 16 | } 17 | 18 | int main(int argc, char** argv) 19 | { 20 | // Can be renamed with standard ROS-node launch interface 21 | ros::init(argc, argv, "gripper_2f_gripper_action_server"); 22 | 23 | // Private Note Handle for retrieving parameter arguments to the server 24 | ros::NodeHandle private_nh("~"); 25 | 26 | std::string gripper_name; 27 | private_nh.param("gripper_name", gripper_name, "gripper"); 28 | 29 | // Fill out 2F-Gripper Params 30 | robotiq_2f_gripper_action_server::Robotiq2FGripperParams cparams = c2_85_defaults(); 31 | 32 | // Min because fingers can push forward before the mechanical stops are reached 33 | private_nh.param("min_gap", cparams.min_gap_, cparams.min_gap_); 34 | private_nh.param("max_gap", cparams.max_gap_, cparams.max_gap_); 35 | private_nh.param("min_effort", cparams.min_effort_, cparams.min_effort_); 36 | private_nh.param("max_effort", cparams.max_effort_, cparams.max_effort_); 37 | 38 | ROS_INFO("Initializing Robotiq action server for gripper: %s", gripper_name.c_str()); 39 | 40 | // The name of the gripper -> this server communicates over name/inputs and name/outputs 41 | robotiq_2f_gripper_action_server::Robotiq2FGripperActionServer gripper (gripper_name, cparams); 42 | 43 | ROS_INFO("Robotiq action-server spinning for gripper: %s", gripper_name.c_str()); 44 | ros::spin(); 45 | } 46 | -------------------------------------------------------------------------------- /icl_ur5_setup_bringup/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(icl_ur5_setup_bringup) 3 | 4 | ## Compile as C++11, supported in ROS Kinetic and newer 5 | # add_compile_options(-std=c++11) 6 | 7 | ## Find catkin macros and libraries 8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) 9 | ## is used, also find other catkin packages 10 | find_package(catkin REQUIRED) 11 | 12 | ## System dependencies are found with CMake's conventions 13 | # find_package(Boost REQUIRED COMPONENTS system) 14 | 15 | 16 | ## Uncomment this if the package has a setup.py. This macro ensures 17 | ## modules and global scripts declared therein get installed 18 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html 19 | # catkin_python_setup() 20 | 21 | ################################################ 22 | ## Declare ROS messages, services and actions ## 23 | ################################################ 24 | 25 | ## To declare and build messages, services or actions from within this 26 | ## package, follow these steps: 27 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in 28 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). 29 | ## * In the file package.xml: 30 | ## * add a build_depend tag for "message_generation" 31 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET 32 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in 33 | ## but can be declared for certainty nonetheless: 34 | ## * add a run_depend tag for "message_runtime" 35 | ## * In this file (CMakeLists.txt): 36 | ## * add "message_generation" and every package in MSG_DEP_SET to 37 | ## find_package(catkin REQUIRED COMPONENTS ...) 38 | ## * add "message_runtime" and every package in MSG_DEP_SET to 39 | ## catkin_package(CATKIN_DEPENDS ...) 40 | ## * uncomment the add_*_files sections below as needed 41 | ## and list every .msg/.srv/.action file to be processed 42 | ## * uncomment the generate_messages entry below 43 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) 44 | 45 | ## Generate messages in the 'msg' folder 46 | # add_message_files( 47 | # FILES 48 | # Message1.msg 49 | # Message2.msg 50 | # ) 51 | 52 | ## Generate services in the 'srv' folder 53 | # add_service_files( 54 | # FILES 55 | # Service1.srv 56 | # Service2.srv 57 | # ) 58 | 59 | ## Generate actions in the 'action' folder 60 | # add_action_files( 61 | # FILES 62 | # Action1.action 63 | # Action2.action 64 | # ) 65 | 66 | ## Generate added messages and services with any dependencies listed here 67 | # generate_messages( 68 | # DEPENDENCIES 69 | # std_msgs # Or other packages containing msgs 70 | # ) 71 | 72 | ################################################ 73 | ## Declare ROS dynamic reconfigure parameters ## 74 | ################################################ 75 | 76 | ## To declare and build dynamic reconfigure parameters within this 77 | ## package, follow these steps: 78 | ## * In the file package.xml: 79 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure" 80 | ## * In this file (CMakeLists.txt): 81 | ## * add "dynamic_reconfigure" to 82 | ## find_package(catkin REQUIRED COMPONENTS ...) 83 | ## * uncomment the "generate_dynamic_reconfigure_options" section below 84 | ## and list every .cfg file to be processed 85 | 86 | ## Generate dynamic reconfigure parameters in the 'cfg' folder 87 | # generate_dynamic_reconfigure_options( 88 | # cfg/DynReconf1.cfg 89 | # cfg/DynReconf2.cfg 90 | # ) 91 | 92 | ################################### 93 | ## catkin specific configuration ## 94 | ################################### 95 | ## The catkin_package macro generates cmake config files for your package 96 | ## Declare things to be passed to dependent projects 97 | ## INCLUDE_DIRS: uncomment this if your package contains header files 98 | ## LIBRARIES: libraries you create in this project that dependent projects also need 99 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need 100 | ## DEPENDS: system dependencies of this project that dependent projects also need 101 | catkin_package( 102 | # INCLUDE_DIRS include 103 | # LIBRARIES icl_phri_ur5_gripper_bringup 104 | # CATKIN_DEPENDS other_catkin_pkg 105 | # DEPENDS system_lib 106 | ) 107 | 108 | ########### 109 | ## Build ## 110 | ########### 111 | 112 | ## Specify additional locations of header files 113 | ## Your package locations should be listed before other locations 114 | include_directories( 115 | # include 116 | # ${catkin_INCLUDE_DIRS} 117 | ) 118 | 119 | ## Declare a C++ library 120 | # add_library(${PROJECT_NAME} 121 | # src/${PROJECT_NAME}/icl_phri_ur5_gripper_bringup.cpp 122 | # ) 123 | 124 | ## Add cmake target dependencies of the library 125 | ## as an example, code may need to be generated before libraries 126 | ## either from message generation or dynamic reconfigure 127 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 128 | 129 | ## Declare a C++ executable 130 | ## With catkin_make all packages are built within a single CMake context 131 | ## The recommended prefix ensures that target names across packages don't collide 132 | # add_executable(${PROJECT_NAME}_node src/icl_phri_ur5_gripper_bringup_node.cpp) 133 | 134 | ## Rename C++ executable without prefix 135 | ## The above recommended prefix causes long target names, the following renames the 136 | ## target back to the shorter version for ease of user use 137 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" 138 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") 139 | 140 | ## Add cmake target dependencies of the executable 141 | ## same as for the library above 142 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 143 | 144 | ## Specify libraries to link a library or executable target against 145 | # target_link_libraries(${PROJECT_NAME}_node 146 | # ${catkin_LIBRARIES} 147 | # ) 148 | 149 | ############# 150 | ## Install ## 151 | ############# 152 | 153 | # all install targets should use catkin DESTINATION variables 154 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html 155 | 156 | ## Mark executable scripts (Python etc.) for installation 157 | ## in contrast to setup.py, you can choose the destination 158 | # install(PROGRAMS 159 | # scripts/my_python_script 160 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 161 | # ) 162 | 163 | ## Mark executables and/or libraries for installation 164 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node 165 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 166 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 167 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 168 | # ) 169 | 170 | ## Mark cpp header files for installation 171 | # install(DIRECTORY include/${PROJECT_NAME}/ 172 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 173 | # FILES_MATCHING PATTERN "*.h" 174 | # PATTERN ".svn" EXCLUDE 175 | # ) 176 | 177 | ## Mark other files for installation (e.g. launch and bag files, etc.) 178 | # install(FILES 179 | # # myfile1 180 | # # myfile2 181 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 182 | # ) 183 | 184 | ############# 185 | ## Testing ## 186 | ############# 187 | 188 | ## Add gtest based cpp test target and link libraries 189 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_ur5_gripper_bringup.cpp) 190 | # if(TARGET ${PROJECT_NAME}-test) 191 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) 192 | # endif() 193 | 194 | ## Add folders to be run by python nosetests 195 | # catkin_add_nosetests(test) 196 | -------------------------------------------------------------------------------- /icl_ur5_setup_bringup/launch/activate_gripper.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /icl_ur5_setup_bringup/launch/old/moveit_bringup.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /icl_ur5_setup_bringup/launch/old/robotiq_bringup.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | -------------------------------------------------------------------------------- /icl_ur5_setup_bringup/launch/old/ur5_moveit_bringup.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /icl_ur5_setup_bringup/launch/old/ur5_with_gripper.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | -------------------------------------------------------------------------------- /icl_ur5_setup_bringup/launch/ur5_bringup.launch: -------------------------------------------------------------------------------- 1 | 2 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | -------------------------------------------------------------------------------- /icl_ur5_setup_bringup/launch/ur5_fts.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /icl_ur5_setup_bringup/launch/ur5_fts_gripper.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | -------------------------------------------------------------------------------- /icl_ur5_setup_bringup/launch/ur5_gripper.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /icl_ur5_setup_bringup/node/gripper_joint_state_publisher.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | import rospy 3 | from sensor_msgs.msg import JointState 4 | from copy import deepcopy 5 | import message_filters 6 | from robotiq_2f_gripper_control.msg import _Robotiq2FGripper_robot_input as inputMsg 7 | 8 | class FullState: 9 | def __init__(self): 10 | rospy.init_node('joint_state_republisher', anonymous=True) 11 | manipulator_ns = rospy.get_param("~manipulator_ns", "icl_ur5") 12 | gripper_ns = rospy.get_param("~gripper_ns", "icl_gripper") 13 | fts_input = rospy.get_param("~fts_input", "gripper_cmd/input") 14 | joint_states_sub = message_filters.Subscriber(manipulator_ns + '/' + 'joint_states', JointState) 15 | fts_sub = message_filters.Subscriber(gripper_ns + '/' + fts_input, inputMsg.Robotiq2FGripper_robot_input) 16 | self._ts = message_filters.ApproximateTimeSynchronizer([joint_states_sub, fts_sub], 10, 0.1, allow_headerless=True) 17 | self._ts.registerCallback(self._joint_states_callback) 18 | self._joint_states_pub = rospy.Publisher('joint_states', JointState, queue_size=1) 19 | rospy.spin() 20 | 21 | def _joint_states_callback(self, ur5_joints, gripper_joint): 22 | msg = JointState() 23 | msg.header = ur5_joints.header 24 | msg.name = list(ur5_joints.name) 25 | msg.name.append('finger_joint') 26 | msg.position = list(ur5_joints.position) 27 | msg.position.append(gripper_joint.gPO/255.0) 28 | msg.velocity = list(ur5_joints.velocity) 29 | msg.velocity.append(0.0) 30 | msg.effort = list(ur5_joints.effort) 31 | msg.effort.append(gripper_joint.gCU) 32 | # print msg 33 | self._joint_states_pub.publish(msg) 34 | 35 | 36 | if __name__ == '__main__': 37 | FullState() 38 | -------------------------------------------------------------------------------- /icl_ur5_setup_bringup/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | icl_ur5_setup_bringup 4 | 0.0.0 5 | The icl_ur5_setup_bringup package 6 | 7 | 8 | 9 | 10 | Yuxiang Gao 11 | 12 | 13 | 14 | 15 | 16 | BSD 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | catkin 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | -------------------------------------------------------------------------------- /icl_ur5_setup_bringup/scenes/icl_scene.dae: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | VCGLab 6 | VCGLib | MeshLab 7 | 8 | Y_UP 9 | Tue Feb 13 02:09:36 2018 10 | Tue Feb 13 02:09:36 2018 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 0.61 0.61 0 0 0 0 0 0.61 0 1.52 0 0 1.52 0.61 0 0 0.61 0.03 0 0 0 0 0 0.03 0 0.61 0 0.61 2.13 0 0 2.13 0 0.61 1.52 0 0.61 0.61 0.03 0 0.61 0 0.61 0.61 0 0 0.61 0.03 0.56 0.61 0.03 0.61 0.61 0.03 1.52 0.61 0 0.61 0.61 0 1.52 0.61 0.03 2.13 1.52 0 1.52 1.52 0 2.13 0 0 1.52 0.61 0 1.52 0 0.03 1.52 0 0 1.52 0.564182 0.03 1.52 0.61 0.03 1.52 0 0.03 0 0 0 1.52 0 0 0 0 0.03 1.52 0 0.03 0 0.61 0.03 0 0 0.03 0.56 0.564182 0.03 1.52 0.564182 0.03 0.56 0.61 0.03 0 2.13 0.03 0 2.13 0 0.61 1.52 0 0.61 0.61 0.03 0.61 0.61 0 0.61 1.52 0.03 0 2.13 0.03 0.61 2.13 0 0 2.13 0 0.61 2.13 0.03 2.13 2.13 0 0.61 2.13 0 0.61 2.13 0.03 0.61 0.61 0.15 0.56 0.61 0.53 0.61 0.61 0.53 0.61 0.61 0.03 0.56 1.52 0.03 0.61 1.52 0.03 0 2.13 0.03 0.61 2.13 0.03 0.61 0.61 0.15 1.52 0.61 0.15 1.52 0.61 0.03 1.52 1.52 0.03 1.52 0.61 0 1.52 0.61 0.03 1.52 1.52 0 0.61 1.52 0 1.52 0.61 0.03 1.52 0.61 0 0.61 1.52 0.03 2.13 0 0.03 2.13 0 0 1.52 1.52 0.03 2.13 1.52 0 1.52 1.52 0 2.13 1.52 0.03 2.13 1.52 0 2.13 0 0.03 2.13 0 0 2.13 1.52 0.03 2.13 0 0.03 1.52 1.52 0.03 2.13 1.52 0.03 1.52 0.564182 0.53 1.52 0.61 0.53 1.52 0.61 0.15 1.52 0.564182 0.53 0.56 0.564182 0.03 1.52 0.564182 0.03 0.56 0.564182 0.53 0.56 0.61 0.53 0.56 0.564182 0.03 0.56 0.564182 0.53 0.56 0.61 0.03 1.52 1.52 0.03 0.61 1.52 0 1.52 1.52 0 0.61 1.52 0.03 0.61 0.61 0.15 0.61 1.52 0.15 2.13 2.13 0 2.13 2.13 0.03 2.13 2.13 0 2.13 2.13 0.03 2.13 2.13 0.03 0.61 0.61 0.53 0.61 1.52 0.53 0.61 0.61 0.53 1.52 0.61 0.53 0.61 0.61 0.53 0.56 1.52 0.53 0.56 0.61 0.53 0.61 1.52 0.53 1.52 0.564182 0.53 0.56 0.61 0.53 0.56 0.564182 0.53 0.61 0.61 0.53 1.52 0.61 0.53 0.56 1.52 0.53 0.56 1.52 0.03 0.56 1.52 0.53 0.61 1.52 0.03 0.56 1.52 0.03 0.61 1.52 0.15 0.61 1.52 0.53 1.52 0.61 0.15 0.61 1.52 0.15 0.61 0.61 0.15 1.52 1.52 0.15 1.52 1.52 0.03 1.52 1.52 0.15 0.61 1.52 0.15 0.61 1.52 0.03 1.52 1.52 0.15 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 0 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 0 1 -1 0 0 -1 0 0 0.707107 0.707107 0 0.707107 0.707107 0 0 0 -1 0 -1 0 0 -1 0 0 1 0 0 1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 0 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 1 0 0 1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 1 0 0 1 0 0 0 0 1 0 1 0 0 1 0 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 |

0 0 1 0 2 0 1 1 0 1 3 1 3 2 0 2 4 2 5 3 6 3 7 3 6 4 5 4 8 4 9 5 2 5 10 5 2 6 9 6 0 6 0 7 9 7 11 7 12 8 13 8 14 8 13 9 12 9 15 9 15 10 12 10 16 10 17 11 18 11 19 11 18 12 17 12 20 12 4 13 0 13 11 13 21 14 4 14 22 14 4 15 21 15 3 15 3 16 21 16 23 16 24 17 25 17 26 17 25 18 24 18 27 18 27 19 24 19 28 19 29 20 30 20 31 20 30 21 29 21 32 21 33 22 34 22 35 22 34 23 33 23 36 23 36 24 33 24 37 24 38 25 34 25 36 25 39 26 8 26 5 26 8 27 39 27 40 27 41 28 42 28 43 28 42 29 41 29 44 29 45 30 46 30 47 30 46 31 45 31 48 31 49 32 11 32 9 32 11 33 49 33 22 33 22 34 49 34 21 34 50 35 44 35 41 35 44 36 50 36 51 36 52 37 16 37 12 37 16 38 52 38 53 38 53 39 52 39 54 39 55 40 56 40 38 40 56 41 55 41 57 41 38 42 58 42 34 42 58 43 38 43 56 43 58 44 56 44 59 44 59 45 56 45 57 45 60 46 20 46 17 46 20 47 60 47 61 47 62 48 57 48 55 48 63 49 64 49 65 49 64 50 63 50 66 50 67 51 68 51 69 51 68 52 67 52 70 52 4 53 11 53 22 53 71 54 31 54 72 54 31 55 71 55 29 55 73 56 74 56 75 56 74 57 73 57 76 57 77 58 78 58 79 58 78 59 77 59 80 59 81 60 37 60 33 60 37 61 81 61 62 61 62 62 81 62 82 62 82 63 81 63 83 63 28 64 84 64 27 64 84 65 28 65 85 65 85 66 28 66 86 66 87 67 88 67 89 67 88 68 87 68 90 68 91 69 92 69 93 69 92 70 91 70 94 70 95 71 96 71 97 71 96 72 95 72 98 72 44 73 99 73 42 73 99 74 44 74 100 74 48 75 101 75 46 75 101 76 48 76 102 76 103 77 80 77 77 77 80 78 103 78 104 78 82 79 59 79 57 79 59 80 82 80 105 80 105 81 82 81 83 81 100 82 106 82 99 82 106 83 100 83 107 83 108 84 61 84 60 84 61 85 108 85 109 85 110 86 111 86 112 86 111 87 110 87 113 87 114 88 115 88 116 88 115 89 114 89 117 89 117 90 114 90 118 90 119 91 94 91 91 91 94 92 119 92 120 92 121 93 122 93 123 93 122 94 121 94 124 94 124 95 121 95 125 95 126 96 127 96 128 96 127 97 126 97 129 97 130 98 86 98 28 98 86 99 130 99 131 99 82 100 57 100 62 100 132 101 73 101 133 101 73 102 132 102 134 102

45 |
46 |
47 |
48 |
49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 |
64 | -------------------------------------------------------------------------------- /icl_ur5_setup_bringup/scenes/lab_setup.scene: -------------------------------------------------------------------------------- 1 | (noname)++ 2 | * icl_scene.dae 3 | 1 4 | mesh 5 | 39 103 6 | 0.61 0.61 0 7 | 0 0 0 8 | 0 0.61 0 9 | 1.52 0 0 10 | 1.52 0.61 0 11 | 0 0.61 0.03 12 | 0 0 0.03 13 | 0.61 2.13 0 14 | 0 2.13 0 15 | 0.61 1.52 0 16 | 0.61 0.61 0.03 17 | 0.56 0.61 0.03 18 | 1.52 0.61 0.03 19 | 2.13 1.52 0 20 | 1.52 1.52 0 21 | 2.13 0 0 22 | 1.52 0 0.03 23 | 1.52 0.564182 0.03 24 | 0.56 0.564182 0.03 25 | 0 2.13 0.03 26 | 0.61 1.52 0.03 27 | 0.61 2.13 0.03 28 | 2.13 2.13 0 29 | 0.61 0.61 0.15 30 | 0.56 0.61 0.53 31 | 0.61 0.61 0.53 32 | 0.56 1.52 0.03 33 | 1.52 0.61 0.15 34 | 1.52 1.52 0.03 35 | 2.13 0 0.03 36 | 2.13 1.52 0.03 37 | 1.52 0.564182 0.53 38 | 1.52 0.61 0.53 39 | 0.56 0.564182 0.53 40 | 0.61 1.52 0.15 41 | 2.13 2.13 0.03 42 | 0.61 1.52 0.53 43 | 0.56 1.52 0.53 44 | 1.52 1.52 0.15 45 | 0 1 2 46 | 1 0 3 47 | 3 0 4 48 | 5 1 6 49 | 1 5 2 50 | 7 2 8 51 | 2 7 0 52 | 0 7 9 53 | 10 2 0 54 | 2 10 5 55 | 5 10 11 56 | 10 4 0 57 | 4 10 12 58 | 4 0 9 59 | 13 4 14 60 | 4 13 3 61 | 3 13 15 62 | 4 16 3 63 | 16 4 17 64 | 17 4 12 65 | 16 1 3 66 | 1 16 6 67 | 16 5 6 68 | 5 16 18 69 | 18 16 17 70 | 11 5 18 71 | 19 2 5 72 | 2 19 8 73 | 9 10 0 74 | 10 9 20 75 | 19 7 8 76 | 7 19 21 77 | 22 9 7 78 | 9 22 14 79 | 14 22 13 80 | 7 20 9 81 | 20 7 21 82 | 23 11 10 83 | 11 23 24 84 | 24 23 25 85 | 10 26 11 86 | 26 10 20 87 | 11 19 5 88 | 19 11 26 89 | 19 26 21 90 | 21 26 20 91 | 23 12 10 92 | 12 23 27 93 | 12 20 10 94 | 28 4 12 95 | 4 28 14 96 | 9 12 4 97 | 12 9 20 98 | 4 9 14 99 | 29 3 15 100 | 3 29 16 101 | 28 13 14 102 | 13 28 30 103 | 13 29 15 104 | 29 13 30 105 | 29 17 16 106 | 17 29 12 107 | 12 29 28 108 | 28 29 30 109 | 12 31 17 110 | 31 12 32 111 | 32 12 27 112 | 31 18 17 113 | 18 31 33 114 | 24 18 33 115 | 18 24 11 116 | 28 9 14 117 | 9 28 20 118 | 20 23 10 119 | 23 20 34 120 | 21 22 7 121 | 22 21 35 122 | 22 30 13 123 | 30 22 35 124 | 28 21 20 125 | 21 28 35 126 | 35 28 30 127 | 34 25 23 128 | 25 34 36 129 | 25 27 23 130 | 27 25 32 131 | 25 37 24 132 | 37 25 36 133 | 31 24 33 134 | 24 31 25 135 | 25 31 32 136 | 37 11 24 137 | 11 37 26 138 | 37 20 26 139 | 20 37 34 140 | 34 37 36 141 | 27 34 23 142 | 34 27 38 143 | 28 27 12 144 | 27 28 38 145 | 28 20 12 146 | 34 28 20 147 | 28 34 38 148 | 1.1 1.25 -0.16 149 | 0 0 1 0.000796327 150 | 0 0 0 0 151 | . 152 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(icl_ur5_setup_description) 3 | find_package(catkin REQUIRED) 4 | catkin_package() 5 | 6 | install(DIRECTORY meshes DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 7 | install(DIRECTORY robots DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 8 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/README.md: -------------------------------------------------------------------------------- 1 | # robotiq_arg140_description 2 | Model of the Robotiq 140mm 2-finger gripper 3 | And URDF of the gripper assembled on UR5 robot arm. 4 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/launch/test_robotiq_arg_2f_140_model.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/launch/ur5_gripper_upload.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/meshes/icl_scene.dae: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | VCGLab 6 | VCGLib | MeshLab 7 | 8 | Y_UP 9 | Tue Feb 13 02:09:36 2018 10 | Tue Feb 13 02:09:36 2018 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 0.61 0.61 0 0 0 0 0 0.61 0 1.52 0 0 1.52 0.61 0 0 0.61 0.03 0 0 0 0 0 0.03 0 0.61 0 0.61 2.13 0 0 2.13 0 0.61 1.52 0 0.61 0.61 0.03 0 0.61 0 0.61 0.61 0 0 0.61 0.03 0.56 0.61 0.03 0.61 0.61 0.03 1.52 0.61 0 0.61 0.61 0 1.52 0.61 0.03 2.13 1.52 0 1.52 1.52 0 2.13 0 0 1.52 0.61 0 1.52 0 0.03 1.52 0 0 1.52 0.564182 0.03 1.52 0.61 0.03 1.52 0 0.03 0 0 0 1.52 0 0 0 0 0.03 1.52 0 0.03 0 0.61 0.03 0 0 0.03 0.56 0.564182 0.03 1.52 0.564182 0.03 0.56 0.61 0.03 0 2.13 0.03 0 2.13 0 0.61 1.52 0 0.61 0.61 0.03 0.61 0.61 0 0.61 1.52 0.03 0 2.13 0.03 0.61 2.13 0 0 2.13 0 0.61 2.13 0.03 2.13 2.13 0 0.61 2.13 0 0.61 2.13 0.03 0.61 0.61 0.15 0.56 0.61 0.53 0.61 0.61 0.53 0.61 0.61 0.03 0.56 1.52 0.03 0.61 1.52 0.03 0 2.13 0.03 0.61 2.13 0.03 0.61 0.61 0.15 1.52 0.61 0.15 1.52 0.61 0.03 1.52 1.52 0.03 1.52 0.61 0 1.52 0.61 0.03 1.52 1.52 0 0.61 1.52 0 1.52 0.61 0.03 1.52 0.61 0 0.61 1.52 0.03 2.13 0 0.03 2.13 0 0 1.52 1.52 0.03 2.13 1.52 0 1.52 1.52 0 2.13 1.52 0.03 2.13 1.52 0 2.13 0 0.03 2.13 0 0 2.13 1.52 0.03 2.13 0 0.03 1.52 1.52 0.03 2.13 1.52 0.03 1.52 0.564182 0.53 1.52 0.61 0.53 1.52 0.61 0.15 1.52 0.564182 0.53 0.56 0.564182 0.03 1.52 0.564182 0.03 0.56 0.564182 0.53 0.56 0.61 0.53 0.56 0.564182 0.03 0.56 0.564182 0.53 0.56 0.61 0.03 1.52 1.52 0.03 0.61 1.52 0 1.52 1.52 0 0.61 1.52 0.03 0.61 0.61 0.15 0.61 1.52 0.15 2.13 2.13 0 2.13 2.13 0.03 2.13 2.13 0 2.13 2.13 0.03 2.13 2.13 0.03 0.61 0.61 0.53 0.61 1.52 0.53 0.61 0.61 0.53 1.52 0.61 0.53 0.61 0.61 0.53 0.56 1.52 0.53 0.56 0.61 0.53 0.61 1.52 0.53 1.52 0.564182 0.53 0.56 0.61 0.53 0.56 0.564182 0.53 0.61 0.61 0.53 1.52 0.61 0.53 0.56 1.52 0.53 0.56 1.52 0.03 0.56 1.52 0.53 0.61 1.52 0.03 0.56 1.52 0.03 0.61 1.52 0.15 0.61 1.52 0.53 1.52 0.61 0.15 0.61 1.52 0.15 0.61 0.61 0.15 1.52 1.52 0.15 1.52 1.52 0.03 1.52 1.52 0.15 0.61 1.52 0.15 0.61 1.52 0.03 1.52 1.52 0.15 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 0 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 0 1 -1 0 0 -1 0 0 0.707107 0.707107 0 0.707107 0.707107 0 0 0 -1 0 -1 0 0 -1 0 0 1 0 0 1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 0 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 1 0 0 1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 1 0 0 1 0 0 0 0 1 0 1 0 0 1 0 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 |

0 0 1 0 2 0 1 1 0 1 3 1 3 2 0 2 4 2 5 3 6 3 7 3 6 4 5 4 8 4 9 5 2 5 10 5 2 6 9 6 0 6 0 7 9 7 11 7 12 8 13 8 14 8 13 9 12 9 15 9 15 10 12 10 16 10 17 11 18 11 19 11 18 12 17 12 20 12 4 13 0 13 11 13 21 14 4 14 22 14 4 15 21 15 3 15 3 16 21 16 23 16 24 17 25 17 26 17 25 18 24 18 27 18 27 19 24 19 28 19 29 20 30 20 31 20 30 21 29 21 32 21 33 22 34 22 35 22 34 23 33 23 36 23 36 24 33 24 37 24 38 25 34 25 36 25 39 26 8 26 5 26 8 27 39 27 40 27 41 28 42 28 43 28 42 29 41 29 44 29 45 30 46 30 47 30 46 31 45 31 48 31 49 32 11 32 9 32 11 33 49 33 22 33 22 34 49 34 21 34 50 35 44 35 41 35 44 36 50 36 51 36 52 37 16 37 12 37 16 38 52 38 53 38 53 39 52 39 54 39 55 40 56 40 38 40 56 41 55 41 57 41 38 42 58 42 34 42 58 43 38 43 56 43 58 44 56 44 59 44 59 45 56 45 57 45 60 46 20 46 17 46 20 47 60 47 61 47 62 48 57 48 55 48 63 49 64 49 65 49 64 50 63 50 66 50 67 51 68 51 69 51 68 52 67 52 70 52 4 53 11 53 22 53 71 54 31 54 72 54 31 55 71 55 29 55 73 56 74 56 75 56 74 57 73 57 76 57 77 58 78 58 79 58 78 59 77 59 80 59 81 60 37 60 33 60 37 61 81 61 62 61 62 62 81 62 82 62 82 63 81 63 83 63 28 64 84 64 27 64 84 65 28 65 85 65 85 66 28 66 86 66 87 67 88 67 89 67 88 68 87 68 90 68 91 69 92 69 93 69 92 70 91 70 94 70 95 71 96 71 97 71 96 72 95 72 98 72 44 73 99 73 42 73 99 74 44 74 100 74 48 75 101 75 46 75 101 76 48 76 102 76 103 77 80 77 77 77 80 78 103 78 104 78 82 79 59 79 57 79 59 80 82 80 105 80 105 81 82 81 83 81 100 82 106 82 99 82 106 83 100 83 107 83 108 84 61 84 60 84 61 85 108 85 109 85 110 86 111 86 112 86 111 87 110 87 113 87 114 88 115 88 116 88 115 89 114 89 117 89 117 90 114 90 118 90 119 91 94 91 91 91 94 92 119 92 120 92 121 93 122 93 123 93 122 94 121 94 124 94 124 95 121 95 125 95 126 96 127 96 128 96 127 97 126 97 129 97 130 98 86 98 28 98 86 99 130 99 131 99 82 100 57 100 62 100 132 101 73 101 133 101 73 102 132 102 134 102

45 |
46 |
47 |
48 |
49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 |
64 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/meshes/icl_setup.scene: -------------------------------------------------------------------------------- 1 | (noname)++++ 2 | * icl_scene.dae 3 | 1 4 | mesh 5 | 39 103 6 | 0.61 0.61 0 7 | 0 0 0 8 | 0 0.61 0 9 | 1.52 0 0 10 | 1.52 0.61 0 11 | 0 0.61 0.03 12 | 0 0 0.03 13 | 0.61 2.13 0 14 | 0 2.13 0 15 | 0.61 1.52 0 16 | 0.61 0.61 0.03 17 | 0.56 0.61 0.03 18 | 1.52 0.61 0.03 19 | 2.13 1.52 0 20 | 1.52 1.52 0 21 | 2.13 0 0 22 | 1.52 0 0.03 23 | 1.52 0.564182 0.03 24 | 0.56 0.564182 0.03 25 | 0 2.13 0.03 26 | 0.61 1.52 0.03 27 | 0.61 2.13 0.03 28 | 2.13 2.13 0 29 | 0.61 0.61 0.15 30 | 0.56 0.61 0.53 31 | 0.61 0.61 0.53 32 | 0.56 1.52 0.03 33 | 1.52 0.61 0.15 34 | 1.52 1.52 0.03 35 | 2.13 0 0.03 36 | 2.13 1.52 0.03 37 | 1.52 0.564182 0.53 38 | 1.52 0.61 0.53 39 | 0.56 0.564182 0.53 40 | 0.61 1.52 0.15 41 | 2.13 2.13 0.03 42 | 0.61 1.52 0.53 43 | 0.56 1.52 0.53 44 | 1.52 1.52 0.15 45 | 0 1 2 46 | 1 0 3 47 | 3 0 4 48 | 5 1 6 49 | 1 5 2 50 | 7 2 8 51 | 2 7 0 52 | 0 7 9 53 | 10 2 0 54 | 2 10 5 55 | 5 10 11 56 | 10 4 0 57 | 4 10 12 58 | 4 0 9 59 | 13 4 14 60 | 4 13 3 61 | 3 13 15 62 | 4 16 3 63 | 16 4 17 64 | 17 4 12 65 | 16 1 3 66 | 1 16 6 67 | 16 5 6 68 | 5 16 18 69 | 18 16 17 70 | 11 5 18 71 | 19 2 5 72 | 2 19 8 73 | 9 10 0 74 | 10 9 20 75 | 19 7 8 76 | 7 19 21 77 | 22 9 7 78 | 9 22 14 79 | 14 22 13 80 | 7 20 9 81 | 20 7 21 82 | 23 11 10 83 | 11 23 24 84 | 24 23 25 85 | 10 26 11 86 | 26 10 20 87 | 11 19 5 88 | 19 11 26 89 | 19 26 21 90 | 21 26 20 91 | 23 12 10 92 | 12 23 27 93 | 12 20 10 94 | 28 4 12 95 | 4 28 14 96 | 9 12 4 97 | 12 9 20 98 | 4 9 14 99 | 29 3 15 100 | 3 29 16 101 | 28 13 14 102 | 13 28 30 103 | 13 29 15 104 | 29 13 30 105 | 29 17 16 106 | 17 29 12 107 | 12 29 28 108 | 28 29 30 109 | 12 31 17 110 | 31 12 32 111 | 32 12 27 112 | 31 18 17 113 | 18 31 33 114 | 24 18 33 115 | 18 24 11 116 | 28 9 14 117 | 9 28 20 118 | 20 23 10 119 | 23 20 34 120 | 21 22 7 121 | 22 21 35 122 | 22 30 13 123 | 30 22 35 124 | 28 21 20 125 | 21 28 35 126 | 35 28 30 127 | 34 25 23 128 | 25 34 36 129 | 25 27 23 130 | 27 25 32 131 | 25 37 24 132 | 37 25 36 133 | 31 24 33 134 | 24 31 25 135 | 25 31 32 136 | 37 11 24 137 | 11 37 26 138 | 37 20 26 139 | 20 37 34 140 | 34 37 36 141 | 27 34 23 142 | 34 27 38 143 | 28 27 12 144 | 27 28 38 145 | 28 20 12 146 | 34 28 20 147 | 28 34 38 148 | 1.1 1.1 -0.16 149 | 0 0 1 -0.000796327 150 | 0 0 0 0 151 | . 152 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/meshes/robotiq_arg2f_140_finger_tip--.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/intuitivecomputing/ur5_with_robotiq_gripper/55b77f70fdf1aa4a573d508735a76433f38ae96c/icl_ur5_setup_description/meshes/robotiq_arg2f_140_finger_tip--.stl -------------------------------------------------------------------------------- /icl_ur5_setup_description/meshes/robotiq_arg2f_140_finger_tip.dae: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | VCGLab 6 | VCGLib | MeshLab 7 | 8 | Y_UP 9 | Wed Feb 14 20:21:50 2018 10 | Wed Feb 14 20:21:50 2018 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 0.0157139 0.0296233 -0.007 -0.0142861 -0.0303767 -0.007 -0.0142861 0.0296233 -0.007 0.0157139 -0.0303767 -0.007 -0.0142861 0.0296233 0 0.0157139 0.0296233 -0.007 -0.0142861 0.0296233 -0.007 0.0157139 0.0296233 0 0.0157139 0.0296233 -0.007 0.0157139 -0.0303767 0 0.0157139 -0.0303767 -0.007 0.0157139 0.0296233 0 0.0157139 -0.0303767 0 -0.0142861 -0.0303767 -0.007 0.0157139 -0.0303767 -0.007 -0.0142861 -0.0303767 0 -0.0142861 0.0296233 0 -0.0142861 -0.0303767 -0.007 -0.0142861 -0.0303767 0 -0.0142861 0.0296233 -0.007 0.0157139 -0.0303767 0 -0.0142861 0.0296233 0 -0.0142861 -0.0303767 0 0.0157139 0.0296233 0 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 0 0 -1 0 0 -1 0 1 0 0 1 0 1 0 0 1 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 |

0 0 1 0 2 0 1 1 0 1 3 1 4 2 5 2 6 2 5 3 4 3 7 3 8 4 9 4 10 4 9 5 8 5 11 5 12 6 13 6 14 6 13 7 12 7 15 7 16 8 17 8 18 8 17 9 16 9 19 9 20 10 21 10 22 10 21 11 20 11 23 11

45 |
46 |
47 |
48 |
49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 |
64 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/meshes/robotiq_arg2f_140_finger_tip.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/intuitivecomputing/ur5_with_robotiq_gripper/55b77f70fdf1aa4a573d508735a76433f38ae96c/icl_ur5_setup_description/meshes/robotiq_arg2f_140_finger_tip.stl -------------------------------------------------------------------------------- /icl_ur5_setup_description/meshes/robotiq_arg2f_140_inner_finger.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/intuitivecomputing/ur5_with_robotiq_gripper/55b77f70fdf1aa4a573d508735a76433f38ae96c/icl_ur5_setup_description/meshes/robotiq_arg2f_140_inner_finger.stl -------------------------------------------------------------------------------- /icl_ur5_setup_description/meshes/robotiq_arg2f_140_inner_finger_with_tip.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/intuitivecomputing/ur5_with_robotiq_gripper/55b77f70fdf1aa4a573d508735a76433f38ae96c/icl_ur5_setup_description/meshes/robotiq_arg2f_140_inner_finger_with_tip.stl -------------------------------------------------------------------------------- /icl_ur5_setup_description/meshes/robotiq_arg2f_140_inner_knuckle.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/intuitivecomputing/ur5_with_robotiq_gripper/55b77f70fdf1aa4a573d508735a76433f38ae96c/icl_ur5_setup_description/meshes/robotiq_arg2f_140_inner_knuckle.stl -------------------------------------------------------------------------------- /icl_ur5_setup_description/meshes/robotiq_arg2f_140_outer_finger.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/intuitivecomputing/ur5_with_robotiq_gripper/55b77f70fdf1aa4a573d508735a76433f38ae96c/icl_ur5_setup_description/meshes/robotiq_arg2f_140_outer_finger.stl -------------------------------------------------------------------------------- /icl_ur5_setup_description/meshes/robotiq_arg2f_140_outer_knuckle.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/intuitivecomputing/ur5_with_robotiq_gripper/55b77f70fdf1aa4a573d508735a76433f38ae96c/icl_ur5_setup_description/meshes/robotiq_arg2f_140_outer_knuckle.stl -------------------------------------------------------------------------------- /icl_ur5_setup_description/meshes/robotiq_arg2f_base_link_coarse.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/intuitivecomputing/ur5_with_robotiq_gripper/55b77f70fdf1aa4a573d508735a76433f38ae96c/icl_ur5_setup_description/meshes/robotiq_arg2f_base_link_coarse.stl -------------------------------------------------------------------------------- /icl_ur5_setup_description/meshes/robotiq_arg2f_base_link_fine.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/intuitivecomputing/ur5_with_robotiq_gripper/55b77f70fdf1aa4a573d508735a76433f38ae96c/icl_ur5_setup_description/meshes/robotiq_arg2f_base_link_fine.stl -------------------------------------------------------------------------------- /icl_ur5_setup_description/meshes/robotiq_fts150.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/intuitivecomputing/ur5_with_robotiq_gripper/55b77f70fdf1aa4a573d508735a76433f38ae96c/icl_ur5_setup_description/meshes/robotiq_fts150.stl -------------------------------------------------------------------------------- /icl_ur5_setup_description/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | icl_ur5_setup_description 4 | 0.0.1 5 | UR5 arm with Robotiq ARG140 Gripper Description 6 | Ryan Sinnet 7 | Ryan Sinnet 8 | Yuxiang Gao 9 | Yuxiang Gao 10 | BSD 11 | 12 | catkin 13 | urdf 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/robots/ur5_robotiq_140.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/robots/ur5_robotiq_140_joint_limited.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/urdf/robotiq_arg2f.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/urdf/robotiq_arg2f_140_model.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/urdf/robotiq_arg2f_140_model_macro.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | 182 | 183 | 184 | 185 | 186 | 187 | 188 | 189 | 190 | 191 | 192 | 193 | 200 | 201 | 202 | 203 | 204 | 205 | 206 | 207 | 208 | 209 | 210 | 211 | 212 | 213 | 214 | 215 | 216 | 217 | 218 | 219 | 220 | 221 | 222 | 223 | 224 | 225 | 226 | 227 | 228 | 229 | 230 | 231 | 232 | 233 | 234 | 235 | 236 | 237 | 238 | 239 | 240 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/urdf/robotiq_arg2f_finger_tips.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/urdf/robotiq_arg2f_transmission.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | transmission_interface/SimpleTransmission 6 | 7 | PositionJointInterface 8 | 9 | 10 | 1 11 | 12 | 13 | 14 | 15 | 16 | ${prefix}finger_joint 17 | ${prefix}right_outer_knuckle_joint 18 | -1.0 19 | 20 | 21 | ${prefix}finger_joint 22 | ${prefix}left_inner_finger_joint 23 | 1.0 24 | 25 | 26 | 27 | ${prefix}finger_joint 28 | ${prefix}right_inner_finger_joint 29 | 1.0 30 | 31 | 32 | ${prefix}finger_joint 33 | ${prefix}left_inner_knuckle_joint 34 | -1.0 35 | 36 | 37 | ${prefix}finger_joint 38 | ${prefix}right_inner_knuckle_joint 39 | -1.0 40 | 41 | 42 | 43 | 44 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/urdf/robotiq_fts300.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | -------------------------------------------------------------------------------- /icl_ur5_setup_description/visualize.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz/Displays 3 | Help Height: 78 4 | Name: Displays 5 | Property Tree Widget: 6 | Expanded: 7 | - /Global Options1 8 | - /Status1 9 | - /RobotModel1 10 | Splitter Ratio: 0.494145185 11 | Tree Height: 842 12 | - Class: rviz/Selection 13 | Name: Selection 14 | - Class: rviz/Tool Properties 15 | Expanded: 16 | - /2D Pose Estimate1 17 | - /2D Nav Goal1 18 | - /Publish Point1 19 | Name: Tool Properties 20 | Splitter Ratio: 0.588679016 21 | - Class: rviz/Views 22 | Expanded: 23 | - /Current View1 24 | Name: Views 25 | Splitter Ratio: 0.5 26 | - Class: rviz/Time 27 | Experimental: false 28 | Name: Time 29 | SyncMode: 0 30 | SyncSource: "" 31 | Visualization Manager: 32 | Class: "" 33 | Displays: 34 | - Alpha: 0.5 35 | Cell Size: 1 36 | Class: rviz/Grid 37 | Color: 160; 160; 164 38 | Enabled: true 39 | Line Style: 40 | Line Width: 0.0299999993 41 | Value: Lines 42 | Name: Grid 43 | Normal Cell Count: 0 44 | Offset: 45 | X: 0 46 | Y: 0 47 | Z: 0 48 | Plane: XY 49 | Plane Cell Count: 10 50 | Reference Frame: 51 | Value: true 52 | - Alpha: 1 53 | Class: rviz/RobotModel 54 | Collision Enabled: false 55 | Enabled: true 56 | Links: 57 | All Links Enabled: true 58 | Expand Joint Details: false 59 | Expand Link Details: false 60 | Expand Tree: false 61 | Link Tree Style: Links in Alphabetic Order 62 | left_inner_finger: 63 | Alpha: 1 64 | Show Axes: false 65 | Show Trail: false 66 | Value: true 67 | left_inner_knuckle: 68 | Alpha: 1 69 | Show Axes: false 70 | Show Trail: false 71 | Value: true 72 | left_outer_finger: 73 | Alpha: 1 74 | Show Axes: false 75 | Show Trail: false 76 | Value: true 77 | left_outer_knuckle: 78 | Alpha: 1 79 | Show Axes: false 80 | Show Trail: false 81 | Value: true 82 | right_inner_finger: 83 | Alpha: 1 84 | Show Axes: false 85 | Show Trail: false 86 | Value: true 87 | right_inner_knuckle: 88 | Alpha: 1 89 | Show Axes: false 90 | Show Trail: false 91 | Value: true 92 | right_outer_finger: 93 | Alpha: 1 94 | Show Axes: false 95 | Show Trail: false 96 | Value: true 97 | right_outer_knuckle: 98 | Alpha: 1 99 | Show Axes: false 100 | Show Trail: false 101 | Value: true 102 | robotiq_arg2f_base_link: 103 | Alpha: 1 104 | Show Axes: false 105 | Show Trail: false 106 | Value: true 107 | Name: RobotModel 108 | Robot Description: robot_description 109 | TF Prefix: "" 110 | Update Interval: 0 111 | Value: true 112 | Visual Enabled: true 113 | - Class: rviz/TF 114 | Enabled: false 115 | Frame Timeout: 15 116 | Frames: 117 | All Enabled: true 118 | Marker Scale: 1 119 | Name: TF 120 | Show Arrows: true 121 | Show Axes: true 122 | Show Names: true 123 | Tree: 124 | {} 125 | Update Interval: 0 126 | Value: false 127 | Enabled: true 128 | Global Options: 129 | Background Color: 48; 48; 48 130 | Fixed Frame: robotiq_arg2f_base_link 131 | Frame Rate: 30 132 | Name: root 133 | Tools: 134 | - Class: rviz/Interact 135 | Hide Inactive Objects: true 136 | - Class: rviz/MoveCamera 137 | - Class: rviz/Select 138 | - Class: rviz/FocusCamera 139 | - Class: rviz/Measure 140 | - Class: rviz/SetInitialPose 141 | Topic: /initialpose 142 | - Class: rviz/SetGoal 143 | Topic: /move_base_simple/goal 144 | - Class: rviz/PublishPoint 145 | Single click: true 146 | Topic: /clicked_point 147 | Value: true 148 | Views: 149 | Current: 150 | Class: rviz/Orbit 151 | Distance: 0.782706261 152 | Enable Stereo Rendering: 153 | Stereo Eye Separation: 0.0599999987 154 | Stereo Focal Distance: 1 155 | Swap Stereo Eyes: false 156 | Value: false 157 | Focal Point: 158 | X: 0 159 | Y: 0 160 | Z: 0 161 | Focal Shape Fixed Size: true 162 | Focal Shape Size: 0.0500000007 163 | Name: Current View 164 | Near Clip Distance: 0.00999999978 165 | Pitch: 0.0747964084 166 | Target Frame: 167 | Value: Orbit (rviz) 168 | Yaw: 6.24540329 169 | Saved: ~ 170 | Window Geometry: 171 | Displays: 172 | collapsed: false 173 | Height: 1176 174 | Hide Left Dock: false 175 | Hide Right Dock: false 176 | QMainWindow State: 000000ff00000000fd0000000400000000000001ad000003ebfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006b00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000034000003eb000000ef00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c000002610000000100000132000003ebfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000034000003eb000000cd00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000004afc0100000002fb0000000800540069006d006501000000000000073f0000043900fffffffb0000000800540069006d006501000000000000045000000000000000000000044e000003eb00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 177 | Selection: 178 | collapsed: false 179 | Time: 180 | collapsed: false 181 | Tool Properties: 182 | collapsed: false 183 | Views: 184 | collapsed: false 185 | Width: 1855 186 | X: 98 187 | Y: 36 188 | -------------------------------------------------------------------------------- /icl_ur5_setup_gazebo/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(icl_ur5_setup_gazebo) 3 | 4 | ## Compile as C++11, supported in ROS Kinetic and newer 5 | # add_compile_options(-std=c++11) 6 | 7 | ## Find catkin macros and libraries 8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) 9 | ## is used, also find other catkin packages 10 | find_package(catkin REQUIRED) 11 | 12 | ## System dependencies are found with CMake's conventions 13 | # find_package(Boost REQUIRED COMPONENTS system) 14 | 15 | 16 | ## Uncomment this if the package has a setup.py. This macro ensures 17 | ## modules and global scripts declared therein get installed 18 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html 19 | # catkin_python_setup() 20 | 21 | ################################################ 22 | ## Declare ROS messages, services and actions ## 23 | ################################################ 24 | 25 | ## To declare and build messages, services or actions from within this 26 | ## package, follow these steps: 27 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in 28 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). 29 | ## * In the file package.xml: 30 | ## * add a build_depend tag for "message_generation" 31 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET 32 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in 33 | ## but can be declared for certainty nonetheless: 34 | ## * add a run_depend tag for "message_runtime" 35 | ## * In this file (CMakeLists.txt): 36 | ## * add "message_generation" and every package in MSG_DEP_SET to 37 | ## find_package(catkin REQUIRED COMPONENTS ...) 38 | ## * add "message_runtime" and every package in MSG_DEP_SET to 39 | ## catkin_package(CATKIN_DEPENDS ...) 40 | ## * uncomment the add_*_files sections below as needed 41 | ## and list every .msg/.srv/.action file to be processed 42 | ## * uncomment the generate_messages entry below 43 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) 44 | 45 | ## Generate messages in the 'msg' folder 46 | # add_message_files( 47 | # FILES 48 | # Message1.msg 49 | # Message2.msg 50 | # ) 51 | 52 | ## Generate services in the 'srv' folder 53 | # add_service_files( 54 | # FILES 55 | # Service1.srv 56 | # Service2.srv 57 | # ) 58 | 59 | ## Generate actions in the 'action' folder 60 | # add_action_files( 61 | # FILES 62 | # Action1.action 63 | # Action2.action 64 | # ) 65 | 66 | ## Generate added messages and services with any dependencies listed here 67 | # generate_messages( 68 | # DEPENDENCIES 69 | # std_msgs # Or other packages containing msgs 70 | # ) 71 | 72 | ################################################ 73 | ## Declare ROS dynamic reconfigure parameters ## 74 | ################################################ 75 | 76 | ## To declare and build dynamic reconfigure parameters within this 77 | ## package, follow these steps: 78 | ## * In the file package.xml: 79 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure" 80 | ## * In this file (CMakeLists.txt): 81 | ## * add "dynamic_reconfigure" to 82 | ## find_package(catkin REQUIRED COMPONENTS ...) 83 | ## * uncomment the "generate_dynamic_reconfigure_options" section below 84 | ## and list every .cfg file to be processed 85 | 86 | ## Generate dynamic reconfigure parameters in the 'cfg' folder 87 | # generate_dynamic_reconfigure_options( 88 | # cfg/DynReconf1.cfg 89 | # cfg/DynReconf2.cfg 90 | # ) 91 | 92 | ################################### 93 | ## catkin specific configuration ## 94 | ################################### 95 | ## The catkin_package macro generates cmake config files for your package 96 | ## Declare things to be passed to dependent projects 97 | ## INCLUDE_DIRS: uncomment this if your package contains header files 98 | ## LIBRARIES: libraries you create in this project that dependent projects also need 99 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need 100 | ## DEPENDS: system dependencies of this project that dependent projects also need 101 | catkin_package( 102 | # INCLUDE_DIRS include 103 | # LIBRARIES myrobot2_gazebo 104 | # CATKIN_DEPENDS other_catkin_pkg 105 | # DEPENDS system_lib 106 | ) 107 | 108 | ########### 109 | ## Build ## 110 | ########### 111 | 112 | ## Specify additional locations of header files 113 | ## Your package locations should be listed before other locations 114 | include_directories( 115 | # include 116 | # ${catkin_INCLUDE_DIRS} 117 | ) 118 | 119 | ## Declare a C++ library 120 | # add_library(${PROJECT_NAME} 121 | # src/${PROJECT_NAME}/myrobot2_gazebo.cpp 122 | # ) 123 | 124 | ## Add cmake target dependencies of the library 125 | ## as an example, code may need to be generated before libraries 126 | ## either from message generation or dynamic reconfigure 127 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 128 | 129 | ## Declare a C++ executable 130 | ## With catkin_make all packages are built within a single CMake context 131 | ## The recommended prefix ensures that target names across packages don't collide 132 | # add_executable(${PROJECT_NAME}_node src/myrobot2_gazebo_node.cpp) 133 | 134 | ## Rename C++ executable without prefix 135 | ## The above recommended prefix causes long target names, the following renames the 136 | ## target back to the shorter version for ease of user use 137 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" 138 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") 139 | 140 | ## Add cmake target dependencies of the executable 141 | ## same as for the library above 142 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 143 | 144 | ## Specify libraries to link a library or executable target against 145 | # target_link_libraries(${PROJECT_NAME}_node 146 | # ${catkin_LIBRARIES} 147 | # ) 148 | 149 | ############# 150 | ## Install ## 151 | ############# 152 | 153 | # all install targets should use catkin DESTINATION variables 154 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html 155 | 156 | ## Mark executable scripts (Python etc.) for installation 157 | ## in contrast to setup.py, you can choose the destination 158 | # install(PROGRAMS 159 | # scripts/my_python_script 160 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 161 | # ) 162 | 163 | ## Mark executables and/or libraries for installation 164 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node 165 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 166 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 167 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 168 | # ) 169 | 170 | ## Mark cpp header files for installation 171 | # install(DIRECTORY include/${PROJECT_NAME}/ 172 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 173 | # FILES_MATCHING PATTERN "*.h" 174 | # PATTERN ".svn" EXCLUDE 175 | # ) 176 | 177 | ## Mark other files for installation (e.g. launch and bag files, etc.) 178 | # install(FILES 179 | # # myfile1 180 | # # myfile2 181 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 182 | # ) 183 | 184 | ############# 185 | ## Testing ## 186 | ############# 187 | 188 | ## Add gtest based cpp test target and link libraries 189 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_myrobot2_gazebo.cpp) 190 | # if(TARGET ${PROJECT_NAME}-test) 191 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) 192 | # endif() 193 | 194 | ## Add folders to be run by python nosetests 195 | # catkin_add_nosetests(test) 196 | -------------------------------------------------------------------------------- /icl_ur5_setup_gazebo/config/arm_controller_ur5.yaml: -------------------------------------------------------------------------------- 1 | arm_controller: 2 | type: position_controllers/JointTrajectoryController 3 | joints: 4 | - shoulder_pan_joint 5 | - shoulder_lift_joint 6 | - elbow_joint 7 | - wrist_1_joint 8 | - wrist_2_joint 9 | - wrist_3_joint 10 | constraints: 11 | goal_time: 0.6 12 | stopped_velocity_tolerance: 0.05 13 | shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} 14 | shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} 15 | elbow_joint: {trajectory: 0.1, goal: 0.1} 16 | wrist_1_joint: {trajectory: 0.1, goal: 0.1} 17 | wrist_2_joint: {trajectory: 0.1, goal: 0.1} 18 | wrist_3_joint: {trajectory: 0.1, goal: 0.1} 19 | stop_trajectory_duration: 0.5 20 | state_publish_rate: 25 21 | action_monitor_rate: 10 22 | joint_group_position_controller: 23 | type: position_controllers/JointGroupPositionController 24 | joints: 25 | - shoulder_pan_joint 26 | - shoulder_lift_joint 27 | - elbow_joint 28 | - wrist_1_joint 29 | - wrist_2_joint 30 | - wrist_3_joint 31 | 32 | -------------------------------------------------------------------------------- /icl_ur5_setup_gazebo/config/gripper_controller_robotiq.yaml: -------------------------------------------------------------------------------- 1 | gripper: 2 | # type: position_controllers/JointTrajectoryController 3 | # joints: 4 | # - finger_joint 5 | # constraints: 6 | # goal_time: 0.6 7 | # stopped_velocity_tolerance: 0.05 8 | # finger_joint: {trajectory: 0.1, goal: 0.1} 9 | # stop_trajectory_duration: 0.5 10 | # state_publish_rate: 25 11 | # action_monitor_rate: 10 12 | 13 | type: "position_controllers/GripperActionController" 14 | joint: finger_joint 15 | -------------------------------------------------------------------------------- /icl_ur5_setup_gazebo/config/joint_state_controller.yaml: -------------------------------------------------------------------------------- 1 | joint_state_controller: 2 | type: joint_state_controller/JointStateController 3 | publish_rate: 50 4 | -------------------------------------------------------------------------------- /icl_ur5_setup_gazebo/launch/controller_utils.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /icl_ur5_setup_gazebo/launch/icl_ur5_gripper.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | -------------------------------------------------------------------------------- /icl_ur5_setup_gazebo/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | icl_ur5_setup_gazebo 4 | 0.0.0 5 | The icl_ur5_setup_gazebo package 6 | 7 | 8 | 9 | Jane Doe 10 | 11 | 12 | 13 | 14 | 15 | 16 | TODO 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | catkin 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | -------------------------------------------------------------------------------- /icl_ur5_setup_gazebo/worlds/icl_ur5_setup.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | model://ground_plane 7 | 8 | 9 | 10 | model://sun 11 | 12 | 13 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- 1 | moveit_setup_assistant_config: 2 | URDF: 3 | package: icl_phri_ur5_robotiq_arg140_description 4 | relative_path: robots/ur5_robotiq_140_joint_limited.xacro 5 | SRDF: 6 | relative_path: config/ur5_gripper.srdf 7 | CONFIG: 8 | author_name: Yuxiang Gao 9 | author_email: ygao73@jhu.edu 10 | generated_timestamp: 1523993309 -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(icl_ur5_setup_moveit_config) 3 | 4 | find_package(catkin REQUIRED) 5 | 6 | catkin_package() 7 | 8 | install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 9 | PATTERN "setup_assistant.launch" EXCLUDE) 10 | install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 11 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/config/controllers.yaml: -------------------------------------------------------------------------------- 1 | controller_list: 2 | # -------------for real UR5--------------------------------- 3 | # - name: vel_based_pos_traj_controller 4 | - name: icl_ur5 5 | action_ns: follow_joint_trajectory 6 | type: FollowJointTrajectory 7 | default: true 8 | joints: 9 | - shoulder_pan_joint 10 | - shoulder_lift_joint 11 | - elbow_joint 12 | - wrist_1_joint 13 | - wrist_2_joint 14 | - wrist_3_joint 15 | 16 | - name: icl_gripper 17 | action_ns: gripper_cmd 18 | type: GripperCommand 19 | default: true 20 | joints: 21 | - finger_joint 22 | 23 | 24 | #initial: 25 | # - group: manipulator 26 | # pose: up 27 | 28 | # -------------for gazebo UR5--------------------------------- 29 | # - name: "arm_controller" 30 | # action_ns: follow_joint_trajectory 31 | # type: FollowJointTrajectory 32 | # default: true 33 | # joints: 34 | # - shoulder_pan_joint 35 | # - shoulder_lift_joint 36 | # - elbow_joint 37 | # - wrist_1_joint 38 | # - wrist_2_joint 39 | # - wrist_3_joint 40 | 41 | # -------------for gazebo gripper--------------------------------- 42 | # - name: "gripper" 43 | # action_ns: follow_joint_trajectory 44 | # type: FollowJointTrajectory 45 | # default: true 46 | # joints: 47 | # - finger_joint 48 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/config/controllers_sim.yaml: -------------------------------------------------------------------------------- 1 | controller_list: 2 | # -------------for gazebo UR5--------------------------------- 3 | - name: "arm_controller" 4 | action_ns: follow_joint_trajectory 5 | type: FollowJointTrajectory 6 | default: true 7 | joints: 8 | - shoulder_pan_joint 9 | - shoulder_lift_joint 10 | - elbow_joint 11 | - wrist_1_joint 12 | - wrist_2_joint 13 | - wrist_3_joint 14 | 15 | # -------------for gazebo gripper--------------------------------- 16 | - name: "gripper" 17 | # action_ns: follow_joint_trajectory 18 | # type: FollowJointTrajectory 19 | action_ns: gripper_cmd 20 | type: GripperCommand 21 | default: true 22 | joints: 23 | - finger_joint 24 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/config/fake_controllers.yaml: -------------------------------------------------------------------------------- 1 | controller_list: 2 | - name: fake_manipulator_controller 3 | joints: 4 | - shoulder_pan_joint 5 | - shoulder_lift_joint 6 | - elbow_joint 7 | - wrist_1_joint 8 | - wrist_2_joint 9 | - wrist_3_joint 10 | - name: fake_end_effector_controller 11 | joints: 12 | - finger_joint -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/config/joint_limits.yaml: -------------------------------------------------------------------------------- 1 | # joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed 2 | # Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] 3 | # Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] 4 | joint_limits: 5 | finger_joint: 6 | has_velocity_limits: true 7 | max_velocity: 2 8 | has_acceleration_limits: false 9 | max_acceleration: 0 10 | left_inner_finger_joint: 11 | has_velocity_limits: true 12 | max_velocity: 2 13 | has_acceleration_limits: false 14 | max_acceleration: 0 15 | left_inner_knuckle_joint: 16 | has_velocity_limits: true 17 | max_velocity: 2 18 | has_acceleration_limits: false 19 | max_acceleration: 0 20 | right_inner_finger_joint: 21 | has_velocity_limits: true 22 | max_velocity: 2 23 | has_acceleration_limits: false 24 | max_acceleration: 0 25 | right_inner_knuckle_joint: 26 | has_velocity_limits: true 27 | max_velocity: 2 28 | has_acceleration_limits: false 29 | max_acceleration: 0 30 | right_outer_knuckle_joint: 31 | has_velocity_limits: true 32 | max_velocity: 2 33 | has_acceleration_limits: false 34 | max_acceleration: 0 35 | shoulder_pan_joint: 36 | has_velocity_limits: true 37 | max_velocity: 3.15 38 | has_acceleration_limits: true 39 | max_acceleration: 3.15 40 | shoulder_lift_joint: 41 | has_velocity_limits: true 42 | max_velocity: 3.15 43 | has_acceleration_limits: true 44 | max_acceleration: 3.15 45 | elbow_joint: 46 | has_velocity_limits: true 47 | max_velocity: 3.15 48 | has_acceleration_limits: true 49 | max_acceleration: 3.15 50 | wrist_1_joint: 51 | has_velocity_limits: true 52 | max_velocity: 3.2 53 | has_acceleration_limits: true 54 | max_acceleration: 3.2 55 | wrist_2_joint: 56 | has_velocity_limits: true 57 | max_velocity: 3.2 58 | has_acceleration_limits: true 59 | max_acceleration: 3.2 60 | wrist_3_joint: 61 | has_velocity_limits: true 62 | max_velocity: 3.2 63 | has_acceleration_limits: true 64 | max_acceleration: 3.2 -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- 1 | manipulator: 2 | kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin 3 | kinematics_solver_search_resolution: 0.005 4 | kinematics_solver_timeout: 0.1 5 | kinematics_solver_attempts: 10 6 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/config/ompl_planning.yaml: -------------------------------------------------------------------------------- 1 | planner_configs: 2 | SBLkConfigDefault: 3 | type: geometric::SBL 4 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 5 | ESTkConfigDefault: 6 | type: geometric::EST 7 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() 8 | goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 9 | LBKPIECEkConfigDefault: 10 | type: geometric::LBKPIECE 11 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 12 | border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 13 | min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 14 | BKPIECEkConfigDefault: 15 | type: geometric::BKPIECE 16 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 17 | border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 18 | failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 19 | min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 20 | KPIECEkConfigDefault: 21 | type: geometric::KPIECE 22 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 23 | goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 24 | border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] 25 | failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 26 | min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 27 | RRTkConfigDefault: 28 | type: geometric::RRT 29 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 30 | goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 31 | RRTConnectkConfigDefault: 32 | type: geometric::RRTConnect 33 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 34 | RRTstarkConfigDefault: 35 | type: geometric::RRTstar 36 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 37 | goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 38 | delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 39 | TRRTkConfigDefault: 40 | type: geometric::TRRT 41 | range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() 42 | goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 43 | max_states_failed: 10 # when to start increasing temp. default: 10 44 | temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 45 | min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 46 | init_temperature: 10e-6 # initial temperature. default: 10e-6 47 | frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() 48 | frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 49 | k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() 50 | PRMkConfigDefault: 51 | type: geometric::PRM 52 | max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 53 | PRMstarkConfigDefault: 54 | type: geometric::PRMstar 55 | manipulator: 56 | planner_configs: 57 | - SBLkConfigDefault 58 | - ESTkConfigDefault 59 | - LBKPIECEkConfigDefault 60 | - BKPIECEkConfigDefault 61 | - KPIECEkConfigDefault 62 | - RRTkConfigDefault 63 | - RRTConnectkConfigDefault 64 | - RRTstarkConfigDefault 65 | - TRRTkConfigDefault 66 | - PRMkConfigDefault 67 | - PRMstarkConfigDefault 68 | ##Note: commenting the following line lets moveit chose RRTConnect as default planner rather than LBKPIECE 69 | #projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint) 70 | longest_valid_segment_fraction: 0.01 71 | endeffector: 72 | planner_configs: 73 | - SBLkConfigDefault 74 | - ESTkConfigDefault 75 | - LBKPIECEkConfigDefault 76 | - BKPIECEkConfigDefault 77 | - KPIECEkConfigDefault 78 | - RRTkConfigDefault 79 | - RRTConnectkConfigDefault 80 | - RRTstarkConfigDefault 81 | - TRRTkConfigDefault 82 | - PRMkConfigDefault 83 | - PRMstarkConfigDefault 84 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/config/rgbd.yaml: -------------------------------------------------------------------------------- 1 | sensors: 2 | - sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater 3 | image_topic: /kinect2/sd/image_depth_rect 4 | queue_size: 5 5 | near_clipping_plane_distance: 1.3 6 | far_clipping_plane_distance: 1.4 7 | shadow_threshold: 0.2 8 | padding_scale: 4.0 9 | padding_offset: 0.03 10 | filtered_cloud_topic: filtered_cloud 11 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/config/sensors_kinect.yaml: -------------------------------------------------------------------------------- 1 | sensors: 2 | - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater 3 | point_cloud_topic: /kinect2/sd/points 4 | max_range: 3.5 5 | point_subsample: 1 6 | padding_offset: 0.1 7 | padding_scale: 1.0 8 | filtered_cloud_topic: filtered_cloud 9 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/config/ur5_gripper.srdf: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/config/ur5_gripper_sim.srdf: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/frames.gv: -------------------------------------------------------------------------------- 1 | digraph G { 2 | "base_link" -> "base"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1523739251.530 sec old)\nBuffer length: 0.000 sec\n"]; 3 | "fixed_link" -> "base_link"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1523739251.530 sec old)\nBuffer length: 0.000 sec\n"]; 4 | "wrist_3_link" -> "ee_link"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1523739251.530 sec old)\nBuffer length: 0.000 sec\n"]; 5 | "wrist_2_link" -> "wrist_3_link"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 41.871 Hz\nMost recent transform: 1523739251.507 ( 0.023 sec old)\nBuffer length: 4.920 sec\n"]; 6 | "ee_link" -> "fts_robotside"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1523739251.530 sec old)\nBuffer length: 0.000 sec\n"]; 7 | "left_inner_finger" -> "left_finger_tip"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1523739251.530 sec old)\nBuffer length: 0.000 sec\n"]; 8 | "left_outer_knuckle" -> "left_outer_finger"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1523739251.530 sec old)\nBuffer length: 0.000 sec\n"]; 9 | "fts_robotside" -> "robotiq_force_torque_frame_id"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1523739251.530 sec old)\nBuffer length: 0.000 sec\n"]; 10 | "right_inner_finger" -> "right_finger_tip"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1523739251.530 sec old)\nBuffer length: 0.000 sec\n"]; 11 | "right_outer_knuckle" -> "right_outer_finger"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1523739251.530 sec old)\nBuffer length: 0.000 sec\n"]; 12 | "ee_link" -> "tool"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1523739251.530 sec old)\nBuffer length: 0.000 sec\n"]; 13 | "fts_robotside" -> "fts_toolside"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1523739251.530 sec old)\nBuffer length: 0.000 sec\n"]; 14 | "fts_toolside" -> "robotiq_arg2f_base_link"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1523739251.530 sec old)\nBuffer length: 0.000 sec\n"]; 15 | "wrist_3_link" -> "tool0"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1523739251.530 sec old)\nBuffer length: 0.000 sec\n"]; 16 | "base" -> "tool0_controller"[label="Broadcaster: /icl_phri_ur5/ur_driver\nAverage rate: 125.202 Hz\nMost recent transform: 1523739251.523 ( 0.007 sec old)\nBuffer length: 4.944 sec\n"]; 17 | "upper_arm_link" -> "forearm_link"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 41.871 Hz\nMost recent transform: 1523739251.507 ( 0.023 sec old)\nBuffer length: 4.920 sec\n"]; 18 | "shoulder_link" -> "upper_arm_link"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 41.871 Hz\nMost recent transform: 1523739251.507 ( 0.023 sec old)\nBuffer length: 4.920 sec\n"]; 19 | "base_link" -> "shoulder_link"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 41.871 Hz\nMost recent transform: 1523739251.507 ( 0.023 sec old)\nBuffer length: 4.920 sec\n"]; 20 | "forearm_link" -> "wrist_1_link"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 41.871 Hz\nMost recent transform: 1523739251.507 ( 0.023 sec old)\nBuffer length: 4.920 sec\n"]; 21 | "wrist_1_link" -> "wrist_2_link"[label="Broadcaster: /icl_phri_ur5/robot_state_publisher\nAverage rate: 41.871 Hz\nMost recent transform: 1523739251.507 ( 0.023 sec old)\nBuffer length: 4.920 sec\n"]; 22 | edge [style=invis]; 23 | subgraph cluster_legend { style=bold; color=black; label ="view_frames Result"; 24 | "Recorded at time: 1523739251.530"[ shape=plaintext ] ; 25 | }->"fixed_link"; 26 | edge [style=invis]; 27 | subgraph cluster_legend { style=bold; color=black; label ="view_frames Result"; 28 | "Recorded at time: 1523739251.530"[ shape=plaintext ] ; 29 | }->"left_inner_finger"; 30 | edge [style=invis]; 31 | subgraph cluster_legend { style=bold; color=black; label ="view_frames Result"; 32 | "Recorded at time: 1523739251.530"[ shape=plaintext ] ; 33 | }->"left_outer_knuckle"; 34 | edge [style=invis]; 35 | subgraph cluster_legend { style=bold; color=black; label ="view_frames Result"; 36 | "Recorded at time: 1523739251.530"[ shape=plaintext ] ; 37 | }->"right_inner_finger"; 38 | edge [style=invis]; 39 | subgraph cluster_legend { style=bold; color=black; label ="view_frames Result"; 40 | "Recorded at time: 1523739251.530"[ shape=plaintext ] ; 41 | }->"right_outer_knuckle"; 42 | } -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/frames.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/intuitivecomputing/ur5_with_robotiq_gripper/55b77f70fdf1aa4a573d508735a76433f38ae96c/icl_ur5_setup_moveit_config/frames.pdf -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/demo.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | [/move_group/fake_controller_joint_states] 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/fake_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/joystick_control.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/move_group.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 65 | 66 | 67 | 73 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/moveit.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz/Displays 3 | Help Height: 0 4 | Name: Displays 5 | Property Tree Widget: 6 | Expanded: 7 | - /MotionPlanning1 8 | - /MotionPlanning1/Scene Robot1 9 | - /MotionPlanning1/Planning Request1 10 | - /TF1/Frames1 11 | Splitter Ratio: 0.742560029 12 | Tree Height: 258 13 | - Class: rviz/Help 14 | Name: Help 15 | - Class: rviz/Views 16 | Expanded: 17 | - /Current View1 18 | Name: Views 19 | Splitter Ratio: 0.5 20 | Toolbars: 21 | toolButtonStyle: 2 22 | Visualization Manager: 23 | Class: "" 24 | Displays: 25 | - Alpha: 0.5 26 | Cell Size: 1 27 | Class: rviz/Grid 28 | Color: 160; 160; 164 29 | Enabled: true 30 | Line Style: 31 | Line Width: 0.0299999993 32 | Value: Lines 33 | Name: Grid 34 | Normal Cell Count: 0 35 | Offset: 36 | X: 0 37 | Y: 0 38 | Z: 0 39 | Plane: XY 40 | Plane Cell Count: 10 41 | Reference Frame: 42 | Value: true 43 | - Acceleration_Scaling_Factor: 1 44 | Class: moveit_rviz_plugin/MotionPlanning 45 | Enabled: true 46 | Move Group Namespace: "" 47 | MoveIt_Allow_Approximate_IK: false 48 | MoveIt_Allow_External_Program: false 49 | MoveIt_Allow_Replanning: false 50 | MoveIt_Allow_Sensor_Positioning: false 51 | MoveIt_Goal_Tolerance: 0 52 | MoveIt_Planning_Attempts: 10 53 | MoveIt_Planning_Time: 5 54 | MoveIt_Use_Cartesian_Path: false 55 | MoveIt_Use_Constraint_Aware_IK: true 56 | MoveIt_Warehouse_Host: 127.0.0.1 57 | MoveIt_Warehouse_Port: 33829 58 | MoveIt_Workspace: 59 | Center: 60 | X: 0.29999999999999999 61 | Y: -0.25 62 | Z: 0 63 | Size: 64 | X: 1.2 65 | Y: 1 66 | Z: 1.3999999999999999 67 | Name: MotionPlanning 68 | Planned Path: 69 | Color Enabled: false 70 | Interrupt Display: false 71 | Links: 72 | All Links Enabled: true 73 | Expand Joint Details: false 74 | Expand Link Details: false 75 | Expand Tree: false 76 | Link Tree Style: Links in Alphabetic Order 77 | base: 78 | Alpha: 1 79 | Show Axes: false 80 | Show Trail: false 81 | base_link: 82 | Alpha: 1 83 | Show Axes: false 84 | Show Trail: false 85 | Value: true 86 | ee_link: 87 | Alpha: 1 88 | Show Axes: false 89 | Show Trail: false 90 | Value: true 91 | forearm_link: 92 | Alpha: 1 93 | Show Axes: false 94 | Show Trail: false 95 | Value: true 96 | fts_robotside: 97 | Alpha: 1 98 | Show Axes: false 99 | Show Trail: false 100 | Value: true 101 | fts_toolside: 102 | Alpha: 1 103 | Show Axes: false 104 | Show Trail: false 105 | left_finger_tip: 106 | Alpha: 1 107 | Show Axes: false 108 | Show Trail: false 109 | Value: true 110 | left_inner_finger: 111 | Alpha: 1 112 | Show Axes: false 113 | Show Trail: false 114 | Value: true 115 | left_inner_knuckle: 116 | Alpha: 1 117 | Show Axes: false 118 | Show Trail: false 119 | Value: true 120 | left_outer_finger: 121 | Alpha: 1 122 | Show Axes: false 123 | Show Trail: false 124 | Value: true 125 | left_outer_knuckle: 126 | Alpha: 1 127 | Show Axes: false 128 | Show Trail: false 129 | Value: true 130 | right_finger_tip: 131 | Alpha: 1 132 | Show Axes: false 133 | Show Trail: false 134 | Value: true 135 | right_inner_finger: 136 | Alpha: 1 137 | Show Axes: false 138 | Show Trail: false 139 | Value: true 140 | right_inner_knuckle: 141 | Alpha: 1 142 | Show Axes: false 143 | Show Trail: false 144 | Value: true 145 | right_outer_finger: 146 | Alpha: 1 147 | Show Axes: false 148 | Show Trail: false 149 | Value: true 150 | right_outer_knuckle: 151 | Alpha: 1 152 | Show Axes: false 153 | Show Trail: false 154 | Value: true 155 | robotiq_arg2f_base_link: 156 | Alpha: 1 157 | Show Axes: false 158 | Show Trail: false 159 | Value: true 160 | robotiq_force_torque_frame_id: 161 | Alpha: 1 162 | Show Axes: false 163 | Show Trail: false 164 | shoulder_link: 165 | Alpha: 1 166 | Show Axes: false 167 | Show Trail: false 168 | Value: true 169 | tool: 170 | Alpha: 1 171 | Show Axes: false 172 | Show Trail: false 173 | tool0: 174 | Alpha: 1 175 | Show Axes: false 176 | Show Trail: false 177 | upper_arm_link: 178 | Alpha: 1 179 | Show Axes: false 180 | Show Trail: false 181 | Value: true 182 | world: 183 | Alpha: 1 184 | Show Axes: false 185 | Show Trail: false 186 | wrist_1_link: 187 | Alpha: 1 188 | Show Axes: false 189 | Show Trail: false 190 | Value: true 191 | wrist_2_link: 192 | Alpha: 1 193 | Show Axes: false 194 | Show Trail: false 195 | Value: true 196 | wrist_3_link: 197 | Alpha: 1 198 | Show Axes: false 199 | Show Trail: false 200 | Value: true 201 | Loop Animation: false 202 | Robot Alpha: 0.5 203 | Robot Color: 150; 50; 150 204 | Show Robot Collision: false 205 | Show Robot Visual: true 206 | Show Trail: false 207 | State Display Time: 0.05 s 208 | Trail Step Size: 1 209 | Trajectory Topic: move_group/display_planned_path 210 | Planning Metrics: 211 | Payload: 1 212 | Show Joint Torques: false 213 | Show Manipulability: false 214 | Show Manipulability Index: false 215 | Show Weight Limit: false 216 | TextHeight: 0.0799999982 217 | Planning Request: 218 | Colliding Link Color: 255; 0; 0 219 | Goal State Alpha: 1 220 | Goal State Color: 250; 128; 0 221 | Interactive Marker Size: 0 222 | Joint Violation Color: 255; 0; 255 223 | Planning Group: manipulator 224 | Query Goal State: true 225 | Query Start State: false 226 | Show Workspace: false 227 | Start State Alpha: 1 228 | Start State Color: 0; 255; 0 229 | Planning Scene Topic: move_group/monitored_planning_scene 230 | Robot Description: robot_description 231 | Scene Geometry: 232 | Scene Alpha: 1 233 | Scene Color: 50; 230; 50 234 | Scene Display Time: 0.200000003 235 | Show Scene Geometry: true 236 | Voxel Coloring: Z-Axis 237 | Voxel Rendering: Occupied Voxels 238 | Scene Robot: 239 | Attached Body Color: 150; 50; 150 240 | Links: 241 | All Links Enabled: true 242 | Expand Joint Details: false 243 | Expand Link Details: false 244 | Expand Tree: false 245 | Link Tree Style: Links in Alphabetic Order 246 | base: 247 | Alpha: 1 248 | Show Axes: false 249 | Show Trail: false 250 | base_link: 251 | Alpha: 1 252 | Show Axes: false 253 | Show Trail: false 254 | Value: true 255 | ee_link: 256 | Alpha: 1 257 | Show Axes: false 258 | Show Trail: false 259 | Value: true 260 | forearm_link: 261 | Alpha: 1 262 | Show Axes: false 263 | Show Trail: false 264 | Value: true 265 | fts_robotside: 266 | Alpha: 1 267 | Show Axes: false 268 | Show Trail: false 269 | Value: true 270 | fts_toolside: 271 | Alpha: 1 272 | Show Axes: false 273 | Show Trail: false 274 | left_finger_tip: 275 | Alpha: 1 276 | Show Axes: false 277 | Show Trail: false 278 | Value: true 279 | left_inner_finger: 280 | Alpha: 1 281 | Show Axes: false 282 | Show Trail: false 283 | Value: true 284 | left_inner_knuckle: 285 | Alpha: 1 286 | Show Axes: false 287 | Show Trail: false 288 | Value: true 289 | left_outer_finger: 290 | Alpha: 1 291 | Show Axes: false 292 | Show Trail: false 293 | Value: true 294 | left_outer_knuckle: 295 | Alpha: 1 296 | Show Axes: false 297 | Show Trail: false 298 | Value: true 299 | right_finger_tip: 300 | Alpha: 1 301 | Show Axes: false 302 | Show Trail: false 303 | Value: true 304 | right_inner_finger: 305 | Alpha: 1 306 | Show Axes: false 307 | Show Trail: false 308 | Value: true 309 | right_inner_knuckle: 310 | Alpha: 1 311 | Show Axes: false 312 | Show Trail: false 313 | Value: true 314 | right_outer_finger: 315 | Alpha: 1 316 | Show Axes: false 317 | Show Trail: false 318 | Value: true 319 | right_outer_knuckle: 320 | Alpha: 1 321 | Show Axes: false 322 | Show Trail: false 323 | Value: true 324 | robotiq_arg2f_base_link: 325 | Alpha: 1 326 | Show Axes: false 327 | Show Trail: false 328 | Value: true 329 | robotiq_force_torque_frame_id: 330 | Alpha: 1 331 | Show Axes: false 332 | Show Trail: false 333 | shoulder_link: 334 | Alpha: 1 335 | Show Axes: false 336 | Show Trail: false 337 | Value: true 338 | tool: 339 | Alpha: 1 340 | Show Axes: false 341 | Show Trail: false 342 | tool0: 343 | Alpha: 1 344 | Show Axes: false 345 | Show Trail: false 346 | upper_arm_link: 347 | Alpha: 1 348 | Show Axes: false 349 | Show Trail: false 350 | Value: true 351 | world: 352 | Alpha: 1 353 | Show Axes: false 354 | Show Trail: false 355 | wrist_1_link: 356 | Alpha: 1 357 | Show Axes: false 358 | Show Trail: false 359 | Value: true 360 | wrist_2_link: 361 | Alpha: 1 362 | Show Axes: false 363 | Show Trail: false 364 | Value: true 365 | wrist_3_link: 366 | Alpha: 1 367 | Show Axes: false 368 | Show Trail: false 369 | Value: true 370 | Robot Alpha: 0.5 371 | Show Robot Collision: false 372 | Show Robot Visual: true 373 | Value: true 374 | Velocity_Scaling_Factor: 1 375 | - Class: rviz/TF 376 | Enabled: true 377 | Frame Timeout: 15 378 | Frames: 379 | All Enabled: false 380 | base: 381 | Value: false 382 | base_link: 383 | Value: false 384 | ee_link: 385 | Value: false 386 | forearm_link: 387 | Value: false 388 | fts_robotside: 389 | Value: true 390 | fts_toolside: 391 | Value: true 392 | left_finger_tip: 393 | Value: false 394 | left_inner_finger: 395 | Value: false 396 | left_outer_finger: 397 | Value: false 398 | left_outer_knuckle: 399 | Value: false 400 | right_finger_tip: 401 | Value: false 402 | right_inner_finger: 403 | Value: false 404 | right_outer_finger: 405 | Value: false 406 | right_outer_knuckle: 407 | Value: false 408 | robotiq_arg2f_base_link: 409 | Value: false 410 | robotiq_force_torque_frame_id: 411 | Value: true 412 | shoulder_link: 413 | Value: false 414 | tool: 415 | Value: false 416 | tool0: 417 | Value: false 418 | tool0_controller: 419 | Value: true 420 | upper_arm_link: 421 | Value: false 422 | world: 423 | Value: true 424 | wrist_1_link: 425 | Value: false 426 | wrist_2_link: 427 | Value: false 428 | wrist_3_link: 429 | Value: false 430 | Marker Scale: 1 431 | Name: TF 432 | Show Arrows: true 433 | Show Axes: true 434 | Show Names: true 435 | Tree: 436 | world: 437 | base_link: 438 | base: 439 | tool0_controller: 440 | {} 441 | shoulder_link: 442 | upper_arm_link: 443 | forearm_link: 444 | wrist_1_link: 445 | wrist_2_link: 446 | wrist_3_link: 447 | ee_link: 448 | fts_robotside: 449 | fts_toolside: 450 | robotiq_arg2f_base_link: 451 | {} 452 | robotiq_force_torque_frame_id: 453 | {} 454 | tool: 455 | {} 456 | tool0: 457 | {} 458 | Update Interval: 0 459 | Value: true 460 | - Alpha: 1 461 | Autocompute Intensity Bounds: true 462 | Autocompute Value Bounds: 463 | Max Value: 10 464 | Min Value: -10 465 | Value: true 466 | Axis: Z 467 | Channel Name: intensity 468 | Class: rviz/PointCloud2 469 | Color: 255; 255; 255 470 | Color Transformer: RGB8 471 | Decay Time: 0 472 | Enabled: false 473 | Invert Rainbow: false 474 | Max Color: 255; 255; 255 475 | Max Intensity: 4096 476 | Min Color: 0; 0; 0 477 | Min Intensity: 0 478 | Name: PointCloud2 479 | Position Transformer: XYZ 480 | Queue Size: 10 481 | Selectable: true 482 | Size (Pixels): 2 483 | Size (m): 0.00999999978 484 | Style: Points 485 | Topic: /kinect2/sd/points 486 | Unreliable: false 487 | Use Fixed Frame: true 488 | Use rainbow: true 489 | Value: false 490 | Enabled: true 491 | Global Options: 492 | Background Color: 48; 48; 48 493 | Default Light: true 494 | Fixed Frame: base_link 495 | Frame Rate: 30 496 | Name: root 497 | Tools: 498 | - Class: rviz/Interact 499 | Hide Inactive Objects: true 500 | - Class: rviz/MoveCamera 501 | - Class: rviz/Select 502 | Value: true 503 | Views: 504 | Current: 505 | Class: rviz/XYOrbit 506 | Distance: 2.88726282 507 | Enable Stereo Rendering: 508 | Stereo Eye Separation: 0.0599999987 509 | Stereo Focal Distance: 1 510 | Swap Stereo Eyes: false 511 | Value: false 512 | Focal Point: 513 | X: 0.229295075 514 | Y: 0.343941271 515 | Z: 7.00355145e-07 516 | Focal Shape Fixed Size: true 517 | Focal Shape Size: 0.0500000007 518 | Invert Z Axis: false 519 | Name: Current View 520 | Near Clip Distance: 0.00999999978 521 | Pitch: 0.544796944 522 | Target Frame: fixed_link 523 | Value: XYOrbit (rviz) 524 | Yaw: 2.74359465 525 | Saved: ~ 526 | Window Geometry: 527 | Displays: 528 | collapsed: false 529 | Height: 1026 530 | Help: 531 | collapsed: false 532 | Hide Left Dock: false 533 | Hide Right Dock: true 534 | MotionPlanning: 535 | collapsed: false 536 | MotionPlanning - Trajectory Slider: 537 | collapsed: false 538 | QMainWindow State: 000000ff00000000fd0000000100000000000002ad000003bcfc020000000afb000000100044006900730070006c006100790073010000002800000143000000d700fffffffb0000000800480065006c00700000000342000000bb0000007300fffffffb0000000a0056006900650077007300000003b0000000b0000000ad00fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb0000002e004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d00200053006c00690064006500720000000000ffffffff0000000000000000fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000171000002730000019700fffffffb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004a00fffffffb0000000a0049006d00610067006500000002ad0000008b0000000000000000fb0000000a0049006d0061006700650000000320000000c4000000000000000000000471000003bc00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 539 | Views: 540 | collapsed: false 541 | Width: 1828 542 | X: 92 543 | Y: 24 544 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/ompl_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 8 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/planning_context.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/trajectory_execution.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/ur5_gripper_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/ur5_gripper_moveit_planning_execution.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/ur5_gripper_moveit_sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /icl_ur5_setup_moveit_config/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | icl_ur5_setup_moveit_config 4 | 0.3.0 5 | 6 | An automatically generated package with all the configuration and launch files for using the ur5_gripper with the MoveIt! Motion Planning Framework 7 | 8 | Yuxiang Gao 9 | Yuxiang Gao 10 | 11 | BSD 12 | 13 | http://moveit.ros.org/ 14 | https://github.com/ros-planning/moveit/issues 15 | https://github.com/ros-planning/moveit 16 | 17 | catkin 18 | 19 | moveit_ros_move_group 20 | moveit_fake_controller_manager 21 | moveit_kinematics 22 | moveit_planners_ompl 23 | moveit_ros_visualization 24 | joint_state_publisher 25 | robot_state_publisher 26 | xacro 27 | 28 | 29 | icl_phri_ur5_robotiq_arg140_description 30 | icl_phri_ur5_robotiq_arg140_description 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /img/simulation.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/intuitivecomputing/ur5_with_robotiq_gripper/55b77f70fdf1aa4a573d508735a76433f38ae96c/img/simulation.png --------------------------------------------------------------------------------