├── .catkin_workspace ├── .vscode ├── launch.json ├── launch_args.json └── tasks.json ├── .ycm_extra_conf.py ├── .ycm_extra_conf.pyc ├── README.md ├── readme.md └── src ├── CMakeLists.txt ├── UR_with_Robotiq_grasp_gazebo ├── .gitignore ├── CMakeLists.txt ├── depends │ ├── gazebo2rviz │ │ ├── .gitignore │ │ ├── .gitremotes │ │ ├── CMakeLists.txt │ │ ├── launch │ │ │ ├── gazebo2marker.launch │ │ │ ├── gazebo2moveit.launch │ │ │ ├── gazebo2rviz.launch │ │ │ ├── gazebo2tf.launch │ │ │ ├── sdf2moveit.launch │ │ │ └── sdf2rviz.launch │ │ ├── package.xml │ │ ├── setup.py │ │ └── src │ │ │ └── gazebo2rviz │ │ │ ├── __init__.py │ │ │ ├── conversions.py │ │ │ ├── gazebo2marker_node.py │ │ │ ├── gazebo2moveit_collision_node.py │ │ │ ├── gazebo2tf_node.py │ │ │ ├── sdf2extract_tfstatic_node.py │ │ │ ├── sdf2marker_node.py │ │ │ ├── sdf2moveit_collision_node.py │ │ │ └── sdf2tfstatic_node.py │ ├── gazebo_ros_pkgs │ │ ├── .gitignore │ │ ├── CONTRIBUTING.md │ │ ├── README.md │ │ ├── SENSORS.md │ │ ├── gazebo_dev │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── cmake │ │ │ │ └── gazebo_dev-extras.cmake │ │ │ └── package.xml │ │ ├── gazebo_msgs │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── msg │ │ │ │ ├── ContactState.msg │ │ │ │ ├── ContactsState.msg │ │ │ │ ├── LinkState.msg │ │ │ │ ├── LinkStates.msg │ │ │ │ ├── ModelState.msg │ │ │ │ ├── ModelStates.msg │ │ │ │ ├── ODEJointProperties.msg │ │ │ │ ├── ODEPhysics.msg │ │ │ │ └── WorldState.msg │ │ │ ├── package.xml │ │ │ └── srv │ │ │ │ ├── ApplyBodyWrench.srv │ │ │ │ ├── ApplyJointEffort.srv │ │ │ │ ├── BodyRequest.srv │ │ │ │ ├── DeleteLight.srv │ │ │ │ ├── DeleteModel.srv │ │ │ │ ├── GetJointProperties.srv │ │ │ │ ├── GetLightProperties.srv │ │ │ │ ├── GetLinkProperties.srv │ │ │ │ ├── GetLinkState.srv │ │ │ │ ├── GetModelProperties.srv │ │ │ │ ├── GetModelState.srv │ │ │ │ ├── GetPhysicsProperties.srv │ │ │ │ ├── GetWorldProperties.srv │ │ │ │ ├── JointRequest.srv │ │ │ │ ├── SetJointProperties.srv │ │ │ │ ├── SetJointTrajectory.srv │ │ │ │ ├── SetLightProperties.srv │ │ │ │ ├── SetLinkProperties.srv │ │ │ │ ├── SetLinkState.srv │ │ │ │ ├── SetModelConfiguration.srv │ │ │ │ ├── SetModelState.srv │ │ │ │ ├── SetPhysicsProperties.srv │ │ │ │ └── SpawnModel.srv │ │ ├── gazebo_ros │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── cfg │ │ │ │ └── Physics.cfg │ │ │ ├── include │ │ │ │ └── gazebo_ros │ │ │ │ │ └── gazebo_ros_api_plugin.h │ │ │ ├── launch │ │ │ │ ├── elevator_world.launch │ │ │ │ ├── empty_world.launch │ │ │ │ ├── mud_world.launch │ │ │ │ ├── range_world.launch │ │ │ │ ├── rubble_world.launch │ │ │ │ ├── shapes_world.launch │ │ │ │ └── willowgarage_world.launch │ │ │ ├── package.xml │ │ │ ├── scripts │ │ │ │ ├── debug │ │ │ │ ├── gazebo │ │ │ │ ├── gdbrun │ │ │ │ ├── gzclient │ │ │ │ ├── gzserver │ │ │ │ ├── libcommon.sh │ │ │ │ ├── perf │ │ │ │ └── spawn_model │ │ │ ├── setup.py │ │ │ └── src │ │ │ │ ├── gazebo_ros │ │ │ │ ├── __init__.py │ │ │ │ └── gazebo_interface.py │ │ │ │ ├── gazebo_ros_api_plugin.cpp │ │ │ │ └── gazebo_ros_paths_plugin.cpp │ │ └── gazebo_ros_pkgs │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── documentation │ │ │ ├── gazebo_ros_api.odg │ │ │ ├── gazebo_ros_api.pdf │ │ │ ├── gazebo_ros_api.png │ │ │ ├── gazebo_ros_transmission.odg │ │ │ ├── gazebo_ros_transmission.pdf │ │ │ └── gazebo_ros_transmission.png │ │ │ └── package.xml │ ├── opencv_candidate │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── README.rst │ │ ├── include │ │ │ ├── opencv_candidate │ │ │ │ ├── datamatrix.hpp │ │ │ │ └── feature2d.hpp │ │ │ ├── opencv_candidate_reconst3d │ │ │ │ └── reconst3d.hpp │ │ │ └── opencv_creative │ │ │ │ └── reader.h │ │ ├── package.xml │ │ └── src │ │ │ ├── CMakeLists.txt │ │ │ ├── creative │ │ │ ├── CMakeLists.txt │ │ │ ├── creative.cpp │ │ │ └── main.cpp │ │ │ ├── opencv_candidate │ │ │ ├── CMakeLists.txt │ │ │ ├── datamatrix.cpp │ │ │ └── feature2d.cpp │ │ │ ├── reconst3d │ │ │ ├── CMakeLists.txt │ │ │ ├── TODO │ │ │ ├── arbitrary_capture.cpp │ │ │ ├── capture.cpp │ │ │ ├── feature2d_ransac3d.cpp │ │ │ ├── graph_optimizations.hpp │ │ │ ├── graph_se3.cpp │ │ │ ├── graph_se3_rgbd_icp.cpp │ │ │ ├── graph_se3_rgbd_icp_model.cpp │ │ │ ├── load_data.cpp │ │ │ ├── mask_data.cpp │ │ │ ├── model.cpp │ │ │ ├── ocv_pcl_convert.hpp │ │ │ ├── reconst3d_init.cpp │ │ │ ├── reconstruction.cpp │ │ │ └── samples │ │ │ │ ├── arbitrary_model_capture.cpp │ │ │ │ ├── circular_model_capture.cpp │ │ │ │ └── cylinder_evaluation.cpp │ │ │ └── rgbd │ │ │ ├── CMakeLists.txt │ │ │ ├── doc │ │ │ └── rgbd.rst │ │ │ ├── include │ │ │ └── opencv2 │ │ │ │ └── rgbd │ │ │ │ └── rgbd.hpp │ │ │ ├── samples │ │ │ └── odometry_evaluation.cpp │ │ │ ├── src │ │ │ ├── depth_cleaner.cpp │ │ │ ├── depth_to_3d.cpp │ │ │ ├── depth_to_3d.h │ │ │ ├── normal.cpp │ │ │ ├── odometry.cpp │ │ │ ├── plane.cpp │ │ │ ├── rgbd_init.cpp │ │ │ ├── utils.cpp │ │ │ └── utils.h │ │ │ ├── test │ │ │ ├── test_main.cpp │ │ │ ├── test_normal.cpp │ │ │ ├── test_odometry.cpp │ │ │ ├── test_precomp.cpp │ │ │ ├── test_precomp.hpp │ │ │ └── test_utils.cpp │ │ │ └── testdata │ │ │ └── rgbd │ │ │ └── odometry │ │ │ ├── depth.png │ │ │ └── rgb.png │ ├── pysdf │ │ ├── CMakeLists.txt │ │ ├── package.xml │ │ ├── scripts │ │ │ └── sdf2urdf.py │ │ ├── setup.py │ │ └── src │ │ │ └── pysdf │ │ │ ├── __init__.py │ │ │ ├── conversions.py │ │ │ ├── naming.py │ │ │ └── parse.py │ ├── ros_control │ │ ├── .gitignore │ │ ├── .travis.yml │ │ ├── LICENSE │ │ ├── README.md │ │ ├── combined_robot_hw │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── etc │ │ │ │ └── architecture.svg │ │ │ ├── include │ │ │ │ └── combined_robot_hw │ │ │ │ │ └── combined_robot_hw.h │ │ │ ├── package.xml │ │ │ └── src │ │ │ │ └── combined_robot_hw.cpp │ │ ├── combined_robot_hw_tests │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── include │ │ │ │ └── combined_robot_hw_tests │ │ │ │ │ ├── my_robot_hw_1.h │ │ │ │ │ ├── my_robot_hw_2.h │ │ │ │ │ ├── my_robot_hw_3.h │ │ │ │ │ └── my_robot_hw_4.h │ │ │ ├── package.xml │ │ │ ├── src │ │ │ │ ├── dummy_app.cpp │ │ │ │ ├── my_robot_hw_1.cpp │ │ │ │ ├── my_robot_hw_2.cpp │ │ │ │ ├── my_robot_hw_3.cpp │ │ │ │ └── my_robot_hw_4.cpp │ │ │ ├── test │ │ │ │ ├── cm_test.cpp │ │ │ │ ├── cm_test.test │ │ │ │ ├── combined_robot_hw_test.cpp │ │ │ │ └── combined_robot_hw_test.test │ │ │ └── test_robot_hw_plugin.xml │ │ ├── controller_interface │ │ │ ├── .gitignore │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── include │ │ │ │ └── controller_interface │ │ │ │ │ ├── controller.h │ │ │ │ │ ├── controller_base.h │ │ │ │ │ └── multi_interface_controller.h │ │ │ ├── package.xml │ │ │ └── rosdoc.yaml │ │ ├── controller_manager │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── README.md │ │ │ ├── include │ │ │ │ └── controller_manager │ │ │ │ │ ├── controller_loader.h │ │ │ │ │ ├── controller_loader_interface.h │ │ │ │ │ ├── controller_manager.h │ │ │ │ │ └── controller_spec.h │ │ │ ├── package.xml │ │ │ ├── rosdoc.yaml │ │ │ ├── scripts │ │ │ │ ├── controller_manager │ │ │ │ ├── spawner │ │ │ │ └── unspawner │ │ │ ├── setup.py │ │ │ ├── src │ │ │ │ ├── controller_manager.cpp │ │ │ │ └── controller_manager │ │ │ │ │ ├── __init__.py │ │ │ │ │ └── controller_manager_interface.py │ │ │ └── test │ │ │ │ ├── hwi_switch_test.cpp │ │ │ │ ├── hwi_switch_test.test │ │ │ │ └── hwi_switch_test.yaml │ │ ├── controller_manager_msgs │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── msg │ │ │ │ ├── ControllerState.msg │ │ │ │ ├── ControllerStatistics.msg │ │ │ │ ├── ControllersStatistics.msg │ │ │ │ └── HardwareInterfaceResources.msg │ │ │ ├── package.xml │ │ │ ├── rosdoc.yaml │ │ │ ├── setup.py │ │ │ ├── src │ │ │ │ └── controller_manager_msgs │ │ │ │ │ ├── __init__.py │ │ │ │ │ └── utils.py │ │ │ └── srv │ │ │ │ ├── ListControllerTypes.srv │ │ │ │ ├── ListControllers.srv │ │ │ │ ├── LoadController.srv │ │ │ │ ├── ReloadControllerLibraries.srv │ │ │ │ ├── SwitchController.srv │ │ │ │ └── UnloadController.srv │ │ ├── controller_manager_tests │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── include │ │ │ │ └── controller_manager_tests │ │ │ │ │ ├── effort_test_controller.h │ │ │ │ │ ├── my_dummy_controller.h │ │ │ │ │ ├── my_robot_hw.h │ │ │ │ │ ├── pos_eff_controller.h │ │ │ │ │ ├── pos_eff_opt_controller.h │ │ │ │ │ └── vel_eff_controller.h │ │ │ ├── package.xml │ │ │ ├── setup.py │ │ │ ├── src │ │ │ │ ├── controller_manager_tests │ │ │ │ │ ├── __init__.py │ │ │ │ │ └── controller_manager_dummy.py │ │ │ │ ├── dummy_app.cpp │ │ │ │ ├── effort_test_controller.cpp │ │ │ │ ├── my_dummy_controller.cpp │ │ │ │ ├── my_robot_hw.cpp │ │ │ │ ├── pos_eff_controller.cpp │ │ │ │ ├── pos_eff_opt_controller.cpp │ │ │ │ └── vel_eff_controller.cpp │ │ │ ├── test │ │ │ │ ├── cm_msgs_utils_rostest.py │ │ │ │ ├── cm_msgs_utils_rostest.test │ │ │ │ ├── cm_msgs_utils_test.py │ │ │ │ ├── cm_test.cpp │ │ │ │ ├── cm_test.test │ │ │ │ ├── controller_manager_interface_test.py │ │ │ │ ├── controller_manager_scripts.py │ │ │ │ ├── controller_manager_scripts.test │ │ │ │ ├── controller_params.yaml │ │ │ │ └── multi_cm_dummy.py │ │ │ └── test_controllers_plugin.xml │ │ ├── docs │ │ │ └── architecture.svg │ │ ├── hardware_interface │ │ │ ├── .gitignore │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── include │ │ │ │ └── hardware_interface │ │ │ │ │ ├── actuator_command_interface.h │ │ │ │ │ ├── actuator_state_interface.h │ │ │ │ │ ├── controller_info.h │ │ │ │ │ ├── force_torque_sensor_interface.h │ │ │ │ │ ├── hardware_interface.h │ │ │ │ │ ├── imu_sensor_interface.h │ │ │ │ │ ├── interface_resources.h │ │ │ │ │ ├── internal │ │ │ │ │ ├── demangle_symbol.h │ │ │ │ │ ├── hardware_resource_manager.h │ │ │ │ │ ├── interface_manager.h │ │ │ │ │ └── resource_manager.h │ │ │ │ │ ├── joint_command_interface.h │ │ │ │ │ ├── joint_state_interface.h │ │ │ │ │ ├── posvel_command_interface.h │ │ │ │ │ ├── posvelacc_command_interface.h │ │ │ │ │ └── robot_hw.h │ │ │ ├── package.xml │ │ │ ├── rosdoc.yaml │ │ │ └── test │ │ │ │ ├── actuator_command_interface_test.cpp │ │ │ │ ├── actuator_state_interface_test.cpp │ │ │ │ ├── force_torque_sensor_interface_test.cpp │ │ │ │ ├── hardware_resource_manager_test.cpp │ │ │ │ ├── imu_sensor_interface_test.cpp │ │ │ │ ├── interface_manager_test.cpp │ │ │ │ ├── joint_command_interface_test.cpp │ │ │ │ ├── joint_state_interface_test.cpp │ │ │ │ ├── posvel_command_interface_test.cpp │ │ │ │ ├── posvelacc_command_interface_test.cpp │ │ │ │ └── robot_hw_test.cpp │ │ ├── joint_limits_interface │ │ │ ├── .gitignore │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── README.md │ │ │ ├── include │ │ │ │ └── joint_limits_interface │ │ │ │ │ ├── joint_limits.h │ │ │ │ │ ├── joint_limits_interface.h │ │ │ │ │ ├── joint_limits_interface_exception.h │ │ │ │ │ ├── joint_limits_rosparam.h │ │ │ │ │ └── joint_limits_urdf.h │ │ │ ├── mainpage.dox │ │ │ ├── package.xml │ │ │ ├── rosdoc.yaml │ │ │ └── test │ │ │ │ ├── joint_limits_interface_test.cpp │ │ │ │ ├── joint_limits_rosparam.test │ │ │ │ ├── joint_limits_rosparam.yaml │ │ │ │ ├── joint_limits_rosparam_test.cpp │ │ │ │ └── joint_limits_urdf_test.cpp │ │ ├── ros_control.rosinstall │ │ ├── ros_control │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── documentation │ │ │ │ ├── gazebo_ros_control.odg │ │ │ │ ├── gazebo_ros_control.pdf │ │ │ │ └── gazebo_ros_control.png │ │ │ └── package.xml │ │ ├── rqt_controller_manager │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── package.xml │ │ │ ├── plugin.xml │ │ │ ├── resource │ │ │ │ ├── cm_icon.png │ │ │ │ ├── controller_info.ui │ │ │ │ ├── controller_manager.ui │ │ │ │ ├── led_green.png │ │ │ │ ├── led_off.png │ │ │ │ └── led_red.png │ │ │ ├── scripts │ │ │ │ └── rqt_controller_manager │ │ │ ├── setup.py │ │ │ └── src │ │ │ │ └── rqt_controller_manager │ │ │ │ ├── __init__.py │ │ │ │ ├── controller_manager.py │ │ │ │ └── update_combo.py │ │ └── transmission_interface │ │ │ ├── .gitignore │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── README.md │ │ │ ├── images │ │ │ ├── differential_transmission.png │ │ │ ├── differential_transmission.svg │ │ │ ├── four_bar_linkage_transmission.png │ │ │ ├── four_bar_linkage_transmission.svg │ │ │ ├── simple_transmission.png │ │ │ ├── simple_transmission.svg │ │ │ ├── simple_transmission_gears.png │ │ │ └── simple_transmission_timing_belt.png │ │ │ ├── include │ │ │ └── transmission_interface │ │ │ │ ├── bidirectional_effort_joint_interface_provider.h │ │ │ │ ├── bidirectional_position_joint_interface_provider.h │ │ │ │ ├── bidirectional_velocity_joint_interface_provider.h │ │ │ │ ├── differential_transmission.h │ │ │ │ ├── differential_transmission_loader.h │ │ │ │ ├── effort_joint_interface_provider.h │ │ │ │ ├── four_bar_linkage_transmission.h │ │ │ │ ├── four_bar_linkage_transmission_loader.h │ │ │ │ ├── joint_state_interface_provider.h │ │ │ │ ├── position_joint_interface_provider.h │ │ │ │ ├── robot_transmissions.h │ │ │ │ ├── simple_transmission.h │ │ │ │ ├── simple_transmission_loader.h │ │ │ │ ├── transmission.h │ │ │ │ ├── transmission_info.h │ │ │ │ ├── transmission_interface.h │ │ │ │ ├── transmission_interface_exception.h │ │ │ │ ├── transmission_interface_loader.h │ │ │ │ ├── transmission_loader.h │ │ │ │ ├── transmission_parser.h │ │ │ │ └── velocity_joint_interface_provider.h │ │ │ ├── mainpage.dox │ │ │ ├── package.xml │ │ │ ├── ros_control_plugins.xml │ │ │ ├── rosdoc.yaml │ │ │ ├── src │ │ │ ├── bidirectional_effort_joint_interface_provider.cpp │ │ │ ├── bidirectional_position_joint_interface_provider.cpp │ │ │ ├── bidirectional_velocity_joint_interface_provider.cpp │ │ │ ├── differential_transmission_loader.cpp │ │ │ ├── effort_joint_interface_provider.cpp │ │ │ ├── four_bar_linkage_transmission_loader.cpp │ │ │ ├── joint_state_interface_provider.cpp │ │ │ ├── position_joint_interface_provider.cpp │ │ │ ├── simple_transmission_loader.cpp │ │ │ ├── transmission_interface_loader.cpp │ │ │ ├── transmission_loader.cpp │ │ │ ├── transmission_parser.cpp │ │ │ └── velocity_joint_interface_provider.cpp │ │ │ └── test │ │ │ ├── differential_transmission_loader_test.cpp │ │ │ ├── differential_transmission_test.cpp │ │ │ ├── four_bar_linkage_transmission_loader_test.cpp │ │ │ ├── four_bar_linkage_transmission_test.cpp │ │ │ ├── loader_utils.h │ │ │ ├── random_generator_utils.h │ │ │ ├── read_file.h │ │ │ ├── simple_transmission_loader_test.cpp │ │ │ ├── simple_transmission_test.cpp │ │ │ ├── transmission_interface_loader_test.cpp │ │ │ ├── transmission_interface_test.cpp │ │ │ ├── transmission_parser_test.cpp │ │ │ └── urdf │ │ │ ├── differential_transmission_loader_full.urdf │ │ │ ├── differential_transmission_loader_invalid.urdf │ │ │ ├── differential_transmission_loader_minimal.urdf │ │ │ ├── four_bar_linkage_transmission_loader_full.urdf │ │ │ ├── four_bar_linkage_transmission_loader_invalid.urdf │ │ │ ├── four_bar_linkage_transmission_loader_minimal.urdf │ │ │ ├── parser_test_invalid.urdf │ │ │ ├── parser_test_valid.urdf │ │ │ ├── simple_transmission_loader_full.urdf │ │ │ ├── simple_transmission_loader_invalid.urdf │ │ │ ├── simple_transmission_loader_minimal.urdf │ │ │ ├── transmission_interface_loader_bidirectional_valid.urdf │ │ │ ├── transmission_interface_loader_duplicate.urdf │ │ │ ├── transmission_interface_loader_hw_iface_permutation.urdf │ │ │ ├── transmission_interface_loader_unsupported.urdf │ │ │ └── transmission_interface_loader_valid.urdf │ ├── ros_controllers │ │ ├── diff_drive_controller │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── README.md │ │ │ ├── cfg │ │ │ │ └── DiffDriveController.cfg │ │ │ ├── diff_drive_controller_plugins.xml │ │ │ ├── include │ │ │ │ └── diff_drive_controller │ │ │ │ │ ├── diff_drive_controller.h │ │ │ │ │ ├── odometry.h │ │ │ │ │ └── speed_limiter.h │ │ │ ├── package.xml │ │ │ ├── src │ │ │ │ ├── diff_drive_controller.cpp │ │ │ │ ├── odometry.cpp │ │ │ │ └── speed_limiter.cpp │ │ │ └── test │ │ │ │ ├── diff_drive_bad_urdf.test │ │ │ │ ├── diff_drive_common.launch │ │ │ │ ├── diff_drive_controller.test │ │ │ │ ├── diff_drive_controller_limits.test │ │ │ │ ├── diff_drive_controller_nan.test │ │ │ │ ├── diff_drive_default_cmd_vel_out.test │ │ │ │ ├── diff_drive_default_cmd_vel_out_test.cpp │ │ │ │ ├── diff_drive_default_odom_frame.test │ │ │ │ ├── diff_drive_default_odom_frame_test.cpp │ │ │ │ ├── diff_drive_dyn_reconf.test │ │ │ │ ├── diff_drive_dyn_reconf_test.cpp │ │ │ │ ├── diff_drive_fail_test.cpp │ │ │ │ ├── diff_drive_left_right_multipliers.test │ │ │ │ ├── diff_drive_limits_test.cpp │ │ │ │ ├── diff_drive_multiple_cmd_vel_publishers.test │ │ │ │ ├── diff_drive_multiple_cmd_vel_publishers_test.cpp │ │ │ │ ├── diff_drive_multipliers.test │ │ │ │ ├── diff_drive_nan_test.cpp │ │ │ │ ├── diff_drive_odom_frame.test │ │ │ │ ├── diff_drive_odom_frame_test.cpp │ │ │ │ ├── diff_drive_odom_tf.test │ │ │ │ ├── diff_drive_odom_tf_test.cpp │ │ │ │ ├── diff_drive_open_loop.test │ │ │ │ ├── diff_drive_pub_cmd_vel_out.test │ │ │ │ ├── diff_drive_pub_cmd_vel_out_test.cpp │ │ │ │ ├── diff_drive_radius_param.test │ │ │ │ ├── diff_drive_radius_param_fail.test │ │ │ │ ├── diff_drive_radius_sphere.test │ │ │ │ ├── diff_drive_separation_param.test │ │ │ │ ├── diff_drive_test.cpp │ │ │ │ ├── diff_drive_timeout.test │ │ │ │ ├── diff_drive_timeout_test.cpp │ │ │ │ ├── diff_drive_wrong.test │ │ │ │ ├── diffbot.cpp │ │ │ │ ├── diffbot.h │ │ │ │ ├── diffbot.xacro │ │ │ │ ├── diffbot_bad.xacro │ │ │ │ ├── diffbot_controllers.yaml │ │ │ │ ├── diffbot_left_right_multipliers.yaml │ │ │ │ ├── diffbot_limits.yaml │ │ │ │ ├── diffbot_multipliers.yaml │ │ │ │ ├── diffbot_open_loop.yaml │ │ │ │ ├── diffbot_sphere_wheels.xacro │ │ │ │ ├── diffbot_square_wheels.xacro │ │ │ │ ├── diffbot_timeout.yaml │ │ │ │ ├── diffbot_wrong.yaml │ │ │ │ ├── skid_steer_common.launch │ │ │ │ ├── skid_steer_controller.test │ │ │ │ ├── skid_steer_no_wheels.test │ │ │ │ ├── skidsteerbot.cpp │ │ │ │ ├── skidsteerbot.xacro │ │ │ │ ├── skidsteerbot_controllers.yaml │ │ │ │ ├── skidsteerbot_no_wheels.yaml │ │ │ │ ├── sphere_wheel.xacro │ │ │ │ ├── square_wheel.xacro │ │ │ │ ├── test_common.h │ │ │ │ ├── view_diffbot.launch │ │ │ │ ├── view_skidsteerbot.launch │ │ │ │ └── wheel.xacro │ │ ├── effort_controllers │ │ │ ├── .gitignore │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── effort_controllers_plugins.xml │ │ │ ├── include │ │ │ │ └── effort_controllers │ │ │ │ │ ├── joint_effort_controller.h │ │ │ │ │ ├── joint_group_effort_controller.h │ │ │ │ │ ├── joint_group_position_controller.h │ │ │ │ │ ├── joint_position_controller.h │ │ │ │ │ └── joint_velocity_controller.h │ │ │ ├── mainpage.dox │ │ │ ├── package.xml │ │ │ └── src │ │ │ │ ├── joint_effort_controller.cpp │ │ │ │ ├── joint_group_effort_controller.cpp │ │ │ │ ├── joint_group_position_controller.cpp │ │ │ │ ├── joint_position_controller.cpp │ │ │ │ └── joint_velocity_controller.cpp │ │ ├── force_torque_sensor_controller │ │ │ ├── .gitignore │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── force_torque_sensor_controller.launch │ │ │ ├── force_torque_sensor_controller.yaml │ │ │ ├── force_torque_sensor_plugin.xml │ │ │ ├── include │ │ │ │ └── force_torque_sensor_controller │ │ │ │ │ └── force_torque_sensor_controller.h │ │ │ ├── package.xml │ │ │ └── src │ │ │ │ └── force_torque_sensor_controller.cpp │ │ ├── forward_command_controller │ │ │ ├── .gitignore │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── include │ │ │ │ └── forward_command_controller │ │ │ │ │ ├── forward_command_controller.h │ │ │ │ │ └── forward_joint_group_command_controller.h │ │ │ ├── mainpage.dox │ │ │ └── package.xml │ │ ├── four_wheel_steering_controller │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── README.md │ │ │ ├── four_wheel_steering_controller_plugins.xml │ │ │ ├── include │ │ │ │ └── four_wheel_steering_controller │ │ │ │ │ ├── four_wheel_steering_controller.h │ │ │ │ │ ├── odometry.h │ │ │ │ │ └── speed_limiter.h │ │ │ ├── package.xml │ │ │ ├── src │ │ │ │ ├── four_wheel_steering_controller.cpp │ │ │ │ ├── odometry.cpp │ │ │ │ └── speed_limiter.cpp │ │ │ └── test │ │ │ │ ├── config │ │ │ │ ├── four_wheel_steering_controller_4ws_cmd.yaml │ │ │ │ ├── four_wheel_steering_controller_twist_cmd.yaml │ │ │ │ └── four_wheel_steering_wrong_config.yaml │ │ │ │ ├── four_wheel_steering_controller_4ws_cmd.test │ │ │ │ ├── four_wheel_steering_controller_twist_cmd.test │ │ │ │ ├── four_wheel_steering_wrong_config.test │ │ │ │ ├── launch │ │ │ │ ├── four_wheel_steering_common.launch │ │ │ │ └── view_four_wheel_steering.launch │ │ │ │ ├── src │ │ │ │ ├── four_wheel_steering.cpp │ │ │ │ ├── four_wheel_steering.h │ │ │ │ ├── four_wheel_steering_4ws_cmd_test.cpp │ │ │ │ ├── four_wheel_steering_twist_cmd_test.cpp │ │ │ │ ├── four_wheel_steering_wrong_config.cpp │ │ │ │ └── test_common.h │ │ │ │ └── urdf │ │ │ │ ├── chassis.xacro │ │ │ │ ├── four_wheel_steering.urdf.xacro │ │ │ │ ├── wheel.xacro │ │ │ │ └── wheel_steered.xacro │ │ ├── gripper_action_controller │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── include │ │ │ │ └── gripper_action_controller │ │ │ │ │ ├── gripper_action_controller.h │ │ │ │ │ ├── gripper_action_controller_impl.h │ │ │ │ │ └── hardware_interface_adapter.h │ │ │ ├── package.xml │ │ │ ├── ros_control_plugins.xml │ │ │ └── src │ │ │ │ └── gripper_action_controller.cpp │ │ ├── imu_sensor_controller │ │ │ ├── .gitignore │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── imu_sensor_controller.launch │ │ │ ├── imu_sensor_controller.yaml │ │ │ ├── imu_sensor_plugin.xml │ │ │ ├── include │ │ │ │ └── imu_sensor_controller │ │ │ │ │ └── imu_sensor_controller.h │ │ │ ├── package.xml │ │ │ └── src │ │ │ │ └── imu_sensor_controller.cpp │ │ ├── joint_state_controller │ │ │ ├── .gitignore │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── include │ │ │ │ └── joint_state_controller │ │ │ │ │ └── joint_state_controller.h │ │ │ ├── joint_state_controller.launch │ │ │ ├── joint_state_controller.yaml │ │ │ ├── joint_state_plugin.xml │ │ │ ├── package.xml │ │ │ ├── rosdoc.yaml │ │ │ ├── src │ │ │ │ └── joint_state_controller.cpp │ │ │ └── test │ │ │ │ ├── joint_state_controller.test │ │ │ │ ├── joint_state_controller_extra_joints_ko.yaml │ │ │ │ ├── joint_state_controller_extra_joints_ok.yaml │ │ │ │ ├── joint_state_controller_ko.yaml │ │ │ │ ├── joint_state_controller_ok.yaml │ │ │ │ └── joint_state_controller_test.cpp │ │ ├── joint_trajectory_controller │ │ │ ├── .gitignore │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── README.md │ │ │ ├── images │ │ │ │ ├── new_trajectory.png │ │ │ │ ├── new_trajectory.svg │ │ │ │ ├── trajectory_replacement_future.png │ │ │ │ ├── trajectory_replacement_future.svg │ │ │ │ ├── trajectory_replacement_now.png │ │ │ │ ├── trajectory_replacement_now.svg │ │ │ │ ├── trajectory_replacement_past.png │ │ │ │ └── trajectory_replacement_past.svg │ │ │ ├── include │ │ │ │ ├── joint_trajectory_controller │ │ │ │ │ ├── hardware_interface_adapter.h │ │ │ │ │ ├── init_joint_trajectory.h │ │ │ │ │ ├── joint_trajectory_controller.h │ │ │ │ │ ├── joint_trajectory_controller_impl.h │ │ │ │ │ ├── joint_trajectory_msg_utils.h │ │ │ │ │ ├── joint_trajectory_segment.h │ │ │ │ │ └── tolerances.h │ │ │ │ └── trajectory_interface │ │ │ │ │ ├── pos_vel_acc_state.h │ │ │ │ │ ├── quintic_spline_segment.h │ │ │ │ │ └── trajectory_interface.h │ │ │ ├── mainpage.dox │ │ │ ├── package.xml │ │ │ ├── ros_control_plugins.xml │ │ │ ├── rosdoc.yaml │ │ │ ├── src │ │ │ │ └── joint_trajectory_controller.cpp │ │ │ └── test │ │ │ │ ├── init_joint_trajectory_test.cpp │ │ │ │ ├── joint_partial_trajectory_controller.test │ │ │ │ ├── joint_partial_trajectory_controller_test.cpp │ │ │ │ ├── joint_trajectory_controller.test │ │ │ │ ├── joint_trajectory_controller_stopramp.test │ │ │ │ ├── joint_trajectory_controller_test.cpp │ │ │ │ ├── joint_trajectory_controller_vel.test │ │ │ │ ├── joint_trajectory_controller_wrapping.test │ │ │ │ ├── joint_trajectory_controller_wrapping_test.cpp │ │ │ │ ├── joint_trajectory_msg_utils_test.cpp │ │ │ │ ├── joint_trajectory_segment_test.cpp │ │ │ │ ├── quintic_spline_segment_test.cpp │ │ │ │ ├── rrbot.cpp │ │ │ │ ├── rrbot.xacro │ │ │ │ ├── rrbot_controllers.yaml │ │ │ │ ├── rrbot_controllers_stopramp.yaml │ │ │ │ ├── rrbot_partial_controllers.yaml │ │ │ │ ├── rrbot_vel_controllers.yaml │ │ │ │ ├── rrbot_wrapping.cpp │ │ │ │ ├── rrbot_wrapping_controllers.yaml │ │ │ │ ├── tolerances.test │ │ │ │ ├── tolerances.yaml │ │ │ │ ├── tolerances_test.cpp │ │ │ │ └── trajectory_interface_test.cpp │ │ ├── position_controllers │ │ │ ├── .gitignore │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── include │ │ │ │ └── position_controllers │ │ │ │ │ ├── joint_group_position_controller.h │ │ │ │ │ └── joint_position_controller.h │ │ │ ├── mainpage.dox │ │ │ ├── package.xml │ │ │ ├── position_controllers_plugins.xml │ │ │ └── src │ │ │ │ ├── joint_group_position_controller.cpp │ │ │ │ └── joint_position_controller.cpp │ │ ├── ros_controllers │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ └── package.xml │ │ ├── rqt_joint_trajectory_controller │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── package.xml │ │ │ ├── plugin.xml │ │ │ ├── resource │ │ │ │ ├── double_editor.ui │ │ │ │ ├── joint_trajectory_controller.ui │ │ │ │ ├── off.svg │ │ │ │ ├── on.svg │ │ │ │ ├── scope.png │ │ │ │ └── scope.svg │ │ │ ├── rosdoc.yaml │ │ │ ├── scripts │ │ │ │ └── rqt_joint_trajectory_controller │ │ │ ├── setup.py │ │ │ └── src │ │ │ │ └── rqt_joint_trajectory_controller │ │ │ │ ├── __init__.py │ │ │ │ ├── double_editor.py │ │ │ │ ├── joint_limits_urdf.py │ │ │ │ ├── joint_trajectory_controller.py │ │ │ │ └── update_combo.py │ │ └── velocity_controllers │ │ │ ├── .gitignore │ │ │ ├── CHANGELOG.rst │ │ │ ├── CMakeLists.txt │ │ │ ├── include │ │ │ └── velocity_controllers │ │ │ │ ├── joint_group_velocity_controller.h │ │ │ │ ├── joint_position_controller.h │ │ │ │ └── joint_velocity_controller.h │ │ │ ├── mainpage.dox │ │ │ ├── package.xml │ │ │ ├── src │ │ │ ├── joint_group_velocity_controller.cpp │ │ │ ├── joint_position_controller.cpp │ │ │ └── joint_velocity_controller.cpp │ │ │ └── velocity_controllers_plugins.xml │ ├── spawn_robot_tools │ │ ├── .gitignore │ │ ├── README.md │ │ └── spawn_robot_tools_pkg │ │ │ ├── CMakeLists.txt │ │ │ ├── launch │ │ │ ├── move_ball_model.launch │ │ │ ├── move_model.launch │ │ │ ├── spawn_object.launch │ │ │ ├── spawn_robot_urdf.launch │ │ │ ├── spawn_robot_urdf_multiple.launch │ │ │ ├── spawn_robot_xacro.launch │ │ │ ├── spawn_robot_xacro_multiple.launch │ │ │ ├── spawn_sdf.launch │ │ │ └── spawn_sdf_robotdesc.launch │ │ │ ├── package.xml │ │ │ ├── rviz_config │ │ │ └── robot_urdf.rviz │ │ │ ├── scripts │ │ │ ├── inertial_calculator.py │ │ │ ├── model_twist_keyboard.py │ │ │ ├── move_ball_like_model.py │ │ │ ├── move_generic_model_script.py │ │ │ └── move_object_in_circles.py │ │ │ ├── setup.py │ │ │ ├── src │ │ │ └── spawn_robot_tools_pkg │ │ │ │ ├── __init__.py │ │ │ │ ├── get_model_gazebo_pose.py │ │ │ │ └── move_generic_model.py │ │ │ └── worlds │ │ │ ├── model.world │ │ │ └── urdf_demo.world │ ├── ur5_gazebo_controllers │ │ ├── CMakeLists.txt │ │ ├── launch │ │ │ ├── main.launch │ │ │ └── ur5_upload_mod.launch │ │ ├── package.xml │ │ └── urdf │ │ │ ├── common_mod.gazebo.xacro │ │ │ └── ur5_robot_mod.urdf.xacro │ └── vision_opencv │ │ ├── README.rst │ │ ├── cv_bridge │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── cmake │ │ │ └── cv_bridge-extras.cmake.in │ │ ├── doc │ │ │ ├── conf.py │ │ │ ├── index.rst │ │ │ └── mainpage.dox │ │ ├── include │ │ │ └── cv_bridge │ │ │ │ ├── cv_bridge.h │ │ │ │ └── rgb_colors.h │ │ ├── package.xml │ │ ├── python │ │ │ ├── CMakeLists.txt │ │ │ ├── __init__.py.plain.in │ │ │ └── cv_bridge │ │ │ │ ├── __init__.py │ │ │ │ └── core.py │ │ ├── rosdoc.yaml │ │ ├── setup.py │ │ ├── src │ │ │ ├── CMakeLists.txt │ │ │ ├── boost │ │ │ │ ├── README │ │ │ │ ├── core │ │ │ │ │ └── scoped_enum.hpp │ │ │ │ ├── endian │ │ │ │ │ ├── conversion.hpp │ │ │ │ │ └── detail │ │ │ │ │ │ └── intrinsic.hpp │ │ │ │ └── predef │ │ │ │ │ ├── detail │ │ │ │ │ ├── _cassert.h │ │ │ │ │ ├── endian_compat.h │ │ │ │ │ └── test.h │ │ │ │ │ ├── library │ │ │ │ │ └── c │ │ │ │ │ │ ├── _prefix.h │ │ │ │ │ │ └── gnu.h │ │ │ │ │ ├── make.h │ │ │ │ │ ├── os │ │ │ │ │ ├── android.h │ │ │ │ │ ├── bsd.h │ │ │ │ │ ├── bsd │ │ │ │ │ │ ├── bsdi.h │ │ │ │ │ │ ├── dragonfly.h │ │ │ │ │ │ ├── free.h │ │ │ │ │ │ ├── net.h │ │ │ │ │ │ └── open.h │ │ │ │ │ ├── ios.h │ │ │ │ │ └── macos.h │ │ │ │ │ ├── other │ │ │ │ │ └── endian.h │ │ │ │ │ └── version_number.h │ │ │ ├── cv_bridge.cpp │ │ │ ├── module.cpp │ │ │ ├── module.hpp │ │ │ ├── module_opencv2.cpp │ │ │ ├── module_opencv3.cpp │ │ │ ├── pycompat.hpp │ │ │ └── rgb_colors.cpp │ │ └── test │ │ │ ├── CMakeLists.txt │ │ │ ├── conversions.py │ │ │ ├── enumerants.py │ │ │ ├── python_bindings.py │ │ │ ├── test_compression.cpp │ │ │ ├── test_endian.cpp │ │ │ ├── test_rgb_colors.cpp │ │ │ ├── utest.cpp │ │ │ └── utest2.cpp │ │ ├── image_geometry │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── doc │ │ │ ├── conf.py │ │ │ ├── index.rst │ │ │ └── mainpage.dox │ │ ├── include │ │ │ └── image_geometry │ │ │ │ ├── pinhole_camera_model.h │ │ │ │ └── stereo_camera_model.h │ │ ├── package.xml │ │ ├── rosdoc.yaml │ │ ├── setup.py │ │ ├── src │ │ │ ├── image_geometry │ │ │ │ ├── __init__.py │ │ │ │ └── cameramodels.py │ │ │ ├── pinhole_camera_model.cpp │ │ │ └── stereo_camera_model.cpp │ │ └── test │ │ │ ├── CMakeLists.txt │ │ │ ├── directed.py │ │ │ └── utest.cpp │ │ ├── opencv_tests │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── launch │ │ │ └── pong.launch │ │ ├── mainpage.dox │ │ ├── nodes │ │ │ ├── broadcast.py │ │ │ ├── rosfacedetect.py │ │ │ └── source.py │ │ └── package.xml │ │ └── vision_opencv │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ └── package.xml ├── readme.md └── ur_tc │ ├── confgi │ ├── .setup_assistant │ ├── CMakeLists.txt │ ├── config │ │ ├── chomp_planning.yaml │ │ ├── controllers.yaml │ │ ├── controllers2.yaml │ │ ├── fake_controllers.yaml │ │ ├── joint_limits.yaml │ │ ├── joint_names.yaml │ │ ├── kinematics.yaml │ │ ├── ompl_planning.yaml │ │ ├── ros_controllers.yaml │ │ ├── sensors_3d.yaml │ │ └── urwh.srdf │ ├── launch │ │ ├── chomp_planning_pipeline.launch.xml │ │ ├── default_warehouse_db.launch │ │ ├── demo.launch │ │ ├── demo_gazebo.launch │ │ ├── fake_moveit_controller_manager.launch.xml │ │ ├── gazebo.launch │ │ ├── joystick_control.launch │ │ ├── move_group.launch │ │ ├── moveit.rviz │ │ ├── moveit_rviz.launch │ │ ├── ompl_planning_pipeline.launch.xml │ │ ├── planning_context.launch │ │ ├── planning_execution.launch │ │ ├── planning_pipeline.launch.xml │ │ ├── planning_with_pcl.launch │ │ ├── ros_controllers.launch │ │ ├── run_benchmark_ompl.launch │ │ ├── sensor_manager.launch.xml │ │ ├── setup_assistant.launch │ │ ├── trajectory_execution.launch.xml │ │ ├── urwh_moveit_controller_manager.launch.xml │ │ ├── urwh_moveit_sensor_manager.launch.xml │ │ ├── warehouse.launch │ │ └── warehouse_settings.launch.xml │ └── package.xml │ ├── robotiq_85_gripper │ ├── LICENSE │ ├── README.md │ ├── robotiq_85_bringup │ │ ├── CMakeLists.txt │ │ ├── launch │ │ │ └── robotiq_85.launch │ │ ├── package.xml │ │ └── rviz │ │ │ └── robotiq_85.rviz │ ├── robotiq_85_description │ │ ├── CMakeLists.txt │ │ ├── launch │ │ │ ├── display.launch │ │ │ └── upload_robotiq_85_gripper.launch │ │ ├── meshes │ │ │ ├── collision │ │ │ │ ├── kinova_robotiq_coupler.stl │ │ │ │ ├── robotiq_85_base_link.stl │ │ │ │ ├── robotiq_85_finger_link.stl │ │ │ │ ├── robotiq_85_finger_tip_link.stl │ │ │ │ ├── robotiq_85_inner_knuckle_link.stl │ │ │ │ └── robotiq_85_knuckle_link.stl │ │ │ └── visual │ │ │ │ ├── kinova_robotiq_coupler.dae │ │ │ │ ├── robotiq_85_base_link.dae │ │ │ │ ├── robotiq_85_finger_link.dae │ │ │ │ ├── robotiq_85_finger_tip_link.dae │ │ │ │ ├── robotiq_85_inner_knuckle_link.dae │ │ │ │ └── robotiq_85_knuckle_link.dae │ │ ├── package.xml │ │ ├── urdf.rviz │ │ └── urdf │ │ │ ├── kinova_robotiq_85_gripper.xacro │ │ │ ├── robotiq_85.urdf │ │ │ ├── robotiq_85_gripper.transmission.xacro │ │ │ ├── robotiq_85_gripper.urdf.xacro │ │ │ ├── robotiq_85_gripper.xacro │ │ │ ├── robotiq_85_gripper_sim_base.urdf.xacro │ │ │ └── robotiq_85_kinova_coupler.urdf.xacro │ ├── robotiq_85_driver │ │ ├── CMakeLists.txt │ │ ├── bin │ │ │ ├── robotiq_85_driver │ │ │ └── robotiq_85_test │ │ ├── package.xml │ │ ├── setup.py │ │ └── src │ │ │ └── robotiq_85 │ │ │ ├── __init__.py │ │ │ ├── gripper_io.py │ │ │ ├── modbus_crc.py │ │ │ ├── robotiq_85_driver.py │ │ │ ├── robotiq_85_gripper.py │ │ │ └── robotiq_85_gripper_test.py │ ├── robotiq_85_gripper │ │ ├── CMakeLists.txt │ │ └── package.xml │ ├── robotiq_85_moveit_config │ │ ├── .setup_assistant │ │ ├── CMakeLists.txt │ │ ├── config │ │ │ ├── controllers.yaml │ │ │ ├── fake_controllers.yaml │ │ │ ├── joint_limits.yaml │ │ │ ├── kinematics.yaml │ │ │ ├── ompl_planning.yaml │ │ │ └── robotiq_85_gripper.srdf │ │ ├── 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 │ │ │ ├── robotiq_85_gripper_moveit_controller_manager.launch.xml │ │ │ ├── robotiq_85_gripper_moveit_sensor_manager.launch.xml │ │ │ ├── robotiq_85_moveit_planning_execution.launch │ │ │ ├── run_benchmark_ompl.launch │ │ │ ├── sensor_manager.launch.xml │ │ │ ├── setup_assistant.launch │ │ │ ├── trajectory_execution.launch.xml │ │ │ ├── warehouse.launch │ │ │ └── warehouse_settings.launch.xml │ │ └── package.xml │ ├── robotiq_85_msgs │ │ ├── CMakeLists.txt │ │ ├── msg │ │ │ ├── GripperCmd.msg │ │ │ └── GripperStat.msg │ │ └── package.xml │ ├── robotiq_85_simulation │ │ ├── roboticsgroup_gazebo_plugins │ │ │ ├── CMakeLists.txt │ │ │ ├── README.md │ │ │ ├── include │ │ │ │ └── roboticsgroup_gazebo_plugins │ │ │ │ │ ├── disable_link_plugin.h │ │ │ │ │ └── mimic_joint_plugin.h │ │ │ ├── package.xml │ │ │ └── src │ │ │ │ ├── disable_link_plugin.cpp │ │ │ │ └── mimic_joint_plugin.cpp │ │ ├── robotiq_85_gazebo │ │ │ ├── CMakeLists.txt │ │ │ ├── controller │ │ │ │ ├── gripper_controller_robotiq.yaml │ │ │ │ └── joint_state_controller.yaml │ │ │ ├── launch │ │ │ │ ├── controller_utils.launch │ │ │ │ ├── robotiq_85.launch │ │ │ │ ├── robotiq_85_moveit_rviz_test.launch │ │ │ │ ├── robotiq_85_moveit_sim.launch │ │ │ │ └── test_kinematics.launch │ │ │ ├── package.xml │ │ │ └── scripts │ │ │ │ └── robotiq_85_moveit_test.py │ │ └── robotiq_85_simulation │ │ │ ├── CMakeLists.txt │ │ │ └── package.xml │ └── si_utils │ │ ├── CMakeLists.txt │ │ ├── launch │ │ └── test.launch │ │ ├── package.xml │ │ └── scripts │ │ └── timed_roslaunch │ ├── smart_grasping_sandbox_sample │ ├── CMakeLists.txt │ ├── launch │ │ ├── launch_simulation.launch │ │ ├── launch_simulation_hole.launch │ │ ├── launch_simulation_speed.launch │ │ ├── main.launch │ │ ├── main_hole.launch │ │ ├── main_speed.launch │ │ └── model_gazebo.launch │ ├── package.xml │ ├── scripts │ │ ├── demo_add_obs.py │ │ ├── demo_listen_from_vision.py │ │ ├── demo_qt.py │ │ ├── hole2.py │ │ ├── listen_demo.py │ │ ├── listen_four_move.py │ │ ├── movetrans.py │ │ ├── pcltrans.py │ │ └── stop_demo.py │ └── world │ │ ├── smart_grasp_sandbox.world │ │ ├── world_holes.world │ │ ├── world_thing.world │ │ ├── world_thing2.world │ │ ├── world_with_obs.world │ │ ├── world_work (复件).world │ │ └── world_work.world │ ├── ur_desc │ ├── CMakeLists.txt │ ├── config │ │ └── gripper_gazebo_trajectory.yaml │ ├── launch │ │ ├── test_gripper.launch │ │ ├── test_robot_with_robotiq.launch │ │ └── view_arm.launch │ ├── meshes │ │ ├── collision │ │ │ ├── kinova_robotiq_coupler.stl │ │ │ ├── robotiq_85_base_link.stl │ │ │ ├── robotiq_85_finger_link.stl │ │ │ ├── robotiq_85_finger_tip_link.stl │ │ │ ├── robotiq_85_inner_knuckle_link.stl │ │ │ └── robotiq_85_knuckle_link.stl │ │ ├── hole.STL │ │ ├── hole.dae │ │ ├── kinect.dae │ │ ├── kinect.jpg │ │ ├── kinect.tga │ │ └── visual │ │ │ ├── kinova_robotiq_coupler.dae │ │ │ ├── robotiq_85_base_link.dae │ │ │ ├── robotiq_85_finger_link.dae │ │ │ ├── robotiq_85_finger_tip_link.dae │ │ │ ├── robotiq_85_inner_knuckle_link.dae │ │ │ └── robotiq_85_knuckle_link.dae │ ├── package.xml │ ├── scripts │ │ └── test_ur5.py │ └── urdf │ │ └── ur5_robotiq_85 │ │ ├── hole.urdf │ │ ├── ikfast61_arm.cpp │ │ ├── kinect.xacro │ │ ├── kinect2.xacro │ │ ├── model.backup.dae │ │ ├── model.config │ │ ├── model.dae │ │ ├── model.urdf │ │ ├── model2.urdf │ │ ├── model_v.urdf │ │ ├── realsense.xacro │ │ ├── ur10_wh.gv │ │ ├── ur_with_kinect.xacro │ │ ├── ur_with_kinect2.xacro │ │ ├── ur_with_realsense.xacro │ │ └── urwh.gv │ └── urwh_moveit_config │ ├── .setup_assistant │ ├── CMakeLists.txt │ ├── config │ ├── chomp_planning.yaml │ ├── controllers.yaml │ ├── fake_controllers.yaml │ ├── joint_limits.yaml │ ├── joint_names.yaml │ ├── kinematics.yaml │ ├── ompl_planning.yaml │ ├── ros_controllers.yaml │ ├── sensors_3d.yaml │ ├── sensors_realsense.yaml │ └── ur10_wh.srdf │ ├── launch │ ├── chomp_planning_pipeline.launch.xml │ ├── default_warehouse_db.launch │ ├── demo.launch │ ├── demo_gazebo.launch │ ├── fake_moveit_controller_manager.launch.xml │ ├── gazebo.launch │ ├── joystick_control.launch │ ├── move_group.launch │ ├── moveit.rviz │ ├── moveit_rviz.launch │ ├── ompl_planning_pipeline.launch.xml │ ├── planning_context.launch │ ├── planning_pipeline.launch.xml │ ├── ros_controllers.launch │ ├── run_benchmark_ompl.launch │ ├── sensor_manager.launch.xml │ ├── setup_assistant.launch │ ├── trajectory_execution.launch.xml │ ├── ur10_wh_moveit_controller_manager.launch.xml │ ├── ur10_wh_moveit_sensor_manager.launch.xml │ ├── urwh_planning_example_execution.launch │ ├── urwh_with_pcl.launch │ ├── warehouse.launch │ └── warehouse_settings.launch.xml │ └── package.xml ├── gazebo-pkgs ├── Dockerfile ├── LICENSE ├── README.md ├── TODO.md ├── gazebo_grasp_plugin │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── gazebo_grasp_plugin │ │ │ ├── GazeboGraspFix.h │ │ │ └── GazeboGraspGripper.h │ ├── package.xml │ └── src │ │ ├── GazeboGraspFix.cpp │ │ └── GazeboGraspGripper.cpp ├── gazebo_state_plugins │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config │ │ ├── GazeboMapPublisher.yaml │ │ ├── GazeboObjectInfo.yaml │ │ └── WorldPlugins.yaml │ ├── include │ │ └── gazebo_state_plugins │ │ │ ├── GazeboMapPublisher.h │ │ │ └── GazeboObjectInfo.h │ ├── launch │ │ └── plugin_loader.launch │ ├── package.xml │ ├── src │ │ ├── GazeboMapPublisher.cpp │ │ └── GazeboObjectInfo.cpp │ └── test │ │ └── object_info_request.cpp ├── gazebo_test_tools │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config │ │ ├── FakeObjectRecognizer.yaml │ │ └── ObjectTFBroadcaster.yaml │ ├── include │ │ └── gazebo_test_tools │ │ │ ├── FakeObjectRecognizer.h │ │ │ └── gazebo_cube_spawner.h │ ├── launch │ │ ├── fake_object_recognizer.launch │ │ ├── gazebo_fake_object_recognition.launch │ │ ├── object_tf_broadcaster.launch │ │ └── spawn_and_recognize_cube.launch │ ├── package.xml │ ├── src │ │ ├── FakeObjectRecognizer.cpp │ │ ├── SetGazeboPhysicsClient.cpp │ │ ├── cube_spawner.cpp │ │ ├── cube_spawner_node.cpp │ │ └── fake_object_recognizer_node.cpp │ ├── srv │ │ └── RecognizeGazeboObject.srv │ └── test │ │ └── fake_object_recognizer_cmd.cpp ├── gazebo_version_helpers │ ├── CMakeLists.txt │ ├── include │ │ └── gazebo_version_helpers │ │ │ └── GazeboVersionHelpers.h │ ├── package.xml │ └── src │ │ └── GazeboVersionHelpers.cpp └── gazebo_world_plugin_loader │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config │ └── WorldPluginsTemplate.config │ ├── include │ └── gazebo_world_plugin_loader │ │ └── GazeboPluginLoader.h │ ├── launch │ └── plugin_loader_template.launch │ ├── package.xml │ └── src │ └── GazeboPluginLoader.cpp ├── general-message-pkgs ├── Dockerfile ├── LICENSE ├── README.md ├── object_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── msg │ │ ├── Object.msg │ │ └── ObjectPose.msg │ ├── package.xml │ └── srv │ │ ├── ObjectInfo.srv │ │ └── RegisterObject.srv ├── object_msgs_tools │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config │ │ └── ObjectTFBroadcaster.yaml │ ├── include │ │ └── object_msgs_tools │ │ │ ├── ObjectFunctions.h │ │ │ └── ObjectTFBroadcaster.h │ ├── launch │ │ └── object_tf_broadcaster.launch │ ├── package.xml │ └── src │ │ ├── ObjectFunctions.cpp │ │ ├── ObjectTFBroadcaster.cpp │ │ ├── object_tf_broadcaster_node.cpp │ │ └── register_object_client.cpp └── path_navigation_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── action │ ├── PathExecution.action │ └── TransformPathExecution.action │ └── package.xml ├── grasp_msg ├── CMakeLists.txt ├── msg │ └── newmsg2.msg ├── package.xml ├── script │ ├── listener.py │ └── talker.py └── src │ └── talkerr.cpp ├── qt_test ├── CMakeLists.txt ├── CMakeLists.txt.user ├── package.xml └── src │ ├── mainwindow.cpp │ ├── mainwindow.h │ ├── mainwindow.ui │ ├── qnode.cpp │ ├── qnode.h │ └── qt_app_node.cpp ├── readme.md ├── realsense_gazebo_plugin ├── CMakeLists.txt ├── README.md ├── doc │ └── pointcloud.png ├── include │ └── realsense_gazebo_plugin │ │ ├── RealSensePlugin.h │ │ └── gazebo_ros_realsense.h ├── launch │ ├── depth_proc.launch │ ├── realsense.launch │ ├── realsense_multiple_urdf.launch │ └── realsense_urdf.launch ├── models │ └── realsense_camera │ │ ├── materials │ │ └── textures │ │ │ └── realsense_diffuse.png │ │ ├── meshes │ │ └── realsense.dae │ │ ├── model.config │ │ └── model.sdf ├── package.xml ├── src │ ├── RealSensePlugin.cpp │ └── gazebo_ros_realsense.cpp ├── test │ ├── realsense_streams.test │ ├── realsense_streams_test.cpp │ └── template.cpp ├── urdf │ ├── multi_rs200_simulation.xacro │ ├── realsense-RS200.macro.xacro │ └── rs200_simulation.xacro └── worlds │ └── realsense.world ├── test_ikfast_plugin ├── CMakeLists.txt ├── include │ └── ikfast.h ├── package.xml ├── src │ ├── ur5_manipulator_ikfast_moveit_plugin.cpp │ └── ur5_manipulator_ikfast_solver.cpp ├── update_ikfast_plugin.sh └── ur5_manipulator_moveit_ikfast_plugin_description.xml ├── universal_robot ├── .gitignore ├── .travis.yml ├── CONTRIBUTING.md ├── README.md ├── universal_robot │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ └── package.xml ├── universal_robots │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ └── package.xml ├── ur10_e_moveit_config │ ├── .setup_assistant │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config │ │ ├── controllers.yaml │ │ ├── fake_controllers.yaml │ │ ├── joint_limits.yaml │ │ ├── kinematics.yaml │ │ ├── ompl_planning.yaml │ │ └── ur10e.srdf │ ├── launch │ │ ├── default_warehouse_db.launch │ │ ├── demo.launch │ │ ├── fake_moveit_controller_manager.launch.xml │ │ ├── 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 │ │ ├── ur10_e_moveit_controller_manager.launch.xml │ │ ├── ur10_e_moveit_planning_execution.launch │ │ ├── ur10_e_moveit_sensor_manager.launch.xml │ │ ├── warehouse.launch │ │ └── warehouse_settings.launch.xml │ ├── package.xml │ └── tests │ │ └── moveit_planning_execution.xml ├── ur10_moveit_config │ ├── .setup_assistant │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config │ │ ├── controllers.yaml │ │ ├── fake_controllers.yaml │ │ ├── joint_limits.yaml │ │ ├── kinematics.yaml │ │ ├── ompl_planning.yaml │ │ └── ur10.srdf │ ├── launch │ │ ├── default_warehouse_db.launch │ │ ├── demo.launch │ │ ├── fake_moveit_controller_manager.launch.xml │ │ ├── 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 │ │ ├── ur10_moveit_controller_manager.launch.xml │ │ ├── ur10_moveit_planning_execution.launch │ │ ├── ur10_moveit_sensor_manager.launch.xml │ │ ├── warehouse.launch │ │ └── warehouse_settings.launch.xml │ ├── package.xml │ └── tests │ │ └── moveit_planning_execution.xml ├── ur3_e_moveit_config │ ├── .setup_assistant │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config │ │ ├── controllers.yaml │ │ ├── fake_controllers.yaml │ │ ├── joint_limits.yaml │ │ ├── kinematics.yaml │ │ ├── ompl_planning.yaml │ │ └── ur3e.srdf │ ├── 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 │ │ ├── ur3_e_moveit_controller_manager.launch.xml │ │ ├── ur3_e_moveit_planning_execution.launch │ │ ├── ur3_e_moveit_sensor_manager.launch.xml │ │ ├── warehouse.launch │ │ └── warehouse_settings.launch.xml │ ├── package.xml │ └── tests │ │ └── moveit_planning_execution.xml ├── ur3_moveit_config │ ├── .setup_assistant │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config │ │ ├── controllers.yaml │ │ ├── fake_controllers.yaml │ │ ├── joint_limits.yaml │ │ ├── kinematics.yaml │ │ ├── ompl_planning.yaml │ │ └── ur3.srdf │ ├── 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 │ │ ├── ur3_moveit_controller_manager.launch.xml │ │ ├── ur3_moveit_planning_execution.launch │ │ ├── ur3_moveit_sensor_manager.launch.xml │ │ ├── warehouse.launch │ │ └── warehouse_settings.launch.xml │ ├── package.xml │ └── tests │ │ └── moveit_planning_execution.xml ├── ur5_e_moveit_config │ ├── .setup_assistant │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config │ │ ├── controllers.yaml │ │ ├── fake_controllers.yaml │ │ ├── joint_limits.yaml │ │ ├── kinematics.yaml │ │ ├── ompl_planning.yaml │ │ └── ur5e.srdf │ ├── launch │ │ ├── default_warehouse_db.launch │ │ ├── demo.launch │ │ ├── fake_moveit_controller_manager.launch.xml │ │ ├── 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_e_moveit_controller_manager.launch.xml │ │ ├── ur5_e_moveit_planning_execution.launch │ │ ├── ur5_e_moveit_sensor_manager.launch.xml │ │ ├── warehouse.launch │ │ └── warehouse_settings.launch.xml │ ├── package.xml │ └── tests │ │ └── moveit_planning_execution.xml ├── ur5_moveit_config │ ├── .setup_assistant │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config │ │ ├── controllers.yaml │ │ ├── fake_controllers.yaml │ │ ├── joint_limits.yaml │ │ ├── kinematics.yaml │ │ ├── ompl_planning.yaml │ │ └── ur5.srdf │ ├── launch │ │ ├── default_warehouse_db.launch │ │ ├── demo.launch │ │ ├── fake_moveit_controller_manager.launch.xml │ │ ├── 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_moveit_controller_manager.launch.xml │ │ ├── ur5_moveit_planning_execution.launch │ │ ├── ur5_moveit_sensor_manager.launch.xml │ │ ├── warehouse.launch │ │ └── warehouse_settings.launch.xml │ ├── package.xml │ └── tests │ │ └── moveit_planning_execution.xml ├── ur_bringup │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── launch │ │ ├── ur10_bringup.launch │ │ ├── ur10_bringup_joint_limited.launch │ │ ├── ur3_bringup.launch │ │ ├── ur3_bringup_joint_limited.launch │ │ ├── ur5_bringup.launch │ │ ├── ur5_bringup_joint_limited.launch │ │ └── ur_common.launch │ ├── package.xml │ └── tests │ │ └── roslaunch_test.xml ├── ur_description │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── cfg │ │ └── view_robot.rviz │ ├── launch │ │ ├── ur10_upload.launch │ │ ├── ur3_upload.launch │ │ ├── ur5_upload.launch │ │ ├── view_ur10.launch │ │ ├── view_ur3.launch │ │ └── view_ur5.launch │ ├── meshes │ │ ├── ur10 │ │ │ ├── collision │ │ │ │ ├── base.stl │ │ │ │ ├── forearm.stl │ │ │ │ ├── shoulder.stl │ │ │ │ ├── upperarm.stl │ │ │ │ ├── wrist1.stl │ │ │ │ ├── wrist2.stl │ │ │ │ └── wrist3.stl │ │ │ └── visual │ │ │ │ ├── base.dae │ │ │ │ ├── forearm.dae │ │ │ │ ├── shoulder.dae │ │ │ │ ├── upperarm.dae │ │ │ │ ├── wrist1.dae │ │ │ │ ├── wrist2.dae │ │ │ │ └── wrist3.dae │ │ ├── ur3 │ │ │ ├── collision │ │ │ │ ├── base.stl │ │ │ │ ├── forearm.stl │ │ │ │ ├── shoulder.stl │ │ │ │ ├── upperarm.stl │ │ │ │ ├── wrist1.stl │ │ │ │ ├── wrist2.stl │ │ │ │ └── wrist3.stl │ │ │ └── visual │ │ │ │ ├── base.dae │ │ │ │ ├── forearm.dae │ │ │ │ ├── shoulder.dae │ │ │ │ ├── upperarm.dae │ │ │ │ ├── wrist1.dae │ │ │ │ ├── wrist2.dae │ │ │ │ └── wrist3.dae │ │ └── ur5 │ │ │ ├── collision │ │ │ ├── base.stl │ │ │ ├── forearm.stl │ │ │ ├── shoulder.stl │ │ │ ├── upperarm.stl │ │ │ ├── wrist1.stl │ │ │ ├── wrist2.stl │ │ │ └── wrist3.stl │ │ │ └── visual │ │ │ ├── base.dae │ │ │ ├── forearm.dae │ │ │ ├── shoulder.dae │ │ │ ├── upperarm.dae │ │ │ ├── wrist1.dae │ │ │ ├── wrist2.dae │ │ │ └── wrist3.dae │ ├── model.pdf │ ├── package.xml │ └── urdf │ │ ├── common.gazebo.xacro │ │ ├── ikfast61_arm.cpp │ │ ├── ur.gazebo.xacro │ │ ├── ur.transmission.xacro │ │ ├── ur10.urdf.xacro │ │ ├── ur10_joint_limited_robot.urdf.xacro │ │ ├── ur10_robot.urdf.xacro │ │ ├── ur3.urdf.xacro │ │ ├── ur3_joint_limited_robot.urdf.xacro │ │ ├── ur3_robot.urdf.xacro │ │ ├── ur5.urdf.xacro │ │ ├── ur5_joint_limited_robot.urdf.xacro │ │ ├── ur5_robot.backup.dae │ │ ├── ur5_robot.dae │ │ ├── ur5_robot.urdf │ │ └── ur5_robot.urdf.xacro ├── ur_e_description │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── cfg │ │ └── view_robot.rviz │ ├── launch │ │ ├── ur10e_upload.launch │ │ ├── ur3e_upload.launch │ │ ├── ur5e_upload.launch │ │ ├── view_ur10e.launch │ │ ├── view_ur3e.launch │ │ └── view_ur5e.launch │ ├── meshes │ │ ├── ur10e │ │ │ ├── collision │ │ │ │ ├── base.stl │ │ │ │ ├── forearm.stl │ │ │ │ ├── shoulder.stl │ │ │ │ ├── upperarm.stl │ │ │ │ ├── wrist1.stl │ │ │ │ ├── wrist2.stl │ │ │ │ └── wrist3.stl │ │ │ └── visual │ │ │ │ ├── base.dae │ │ │ │ ├── forearm.dae │ │ │ │ ├── shoulder.dae │ │ │ │ ├── upperarm.dae │ │ │ │ ├── wrist1.dae │ │ │ │ ├── wrist2.dae │ │ │ │ └── wrist3.dae │ │ ├── ur3e │ │ │ ├── collision │ │ │ │ ├── base.stl │ │ │ │ ├── forearm.stl │ │ │ │ ├── shoulder.stl │ │ │ │ ├── upperarm.stl │ │ │ │ ├── wrist1.stl │ │ │ │ ├── wrist2.stl │ │ │ │ └── wrist3.stl │ │ │ └── visual │ │ │ │ ├── base.dae │ │ │ │ ├── forearm.dae │ │ │ │ ├── shoulder.dae │ │ │ │ ├── upperarm.dae │ │ │ │ ├── wrist1.dae │ │ │ │ ├── wrist2.dae │ │ │ │ └── wrist3.dae │ │ └── ur5e │ │ │ ├── collision │ │ │ ├── base.stl │ │ │ ├── forearm.stl │ │ │ ├── shoulder.stl │ │ │ ├── upperarm.stl │ │ │ ├── wrist1.stl │ │ │ ├── wrist2.stl │ │ │ └── wrist3.stl │ │ │ └── visual │ │ │ ├── base.dae │ │ │ ├── forearm.dae │ │ │ ├── shoulder.dae │ │ │ ├── upperarm.dae │ │ │ ├── wrist1.dae │ │ │ ├── wrist2.dae │ │ │ └── wrist3.dae │ ├── package.xml │ └── urdf │ │ ├── common.gazebo.xacro │ │ ├── ur.gazebo.xacro │ │ ├── ur.transmission.xacro │ │ ├── ur10e.urdf.xacro │ │ ├── ur10e_joint_limited_robot.urdf.xacro │ │ ├── ur10e_robot.urdf.xacro │ │ ├── ur3e.urdf.xacro │ │ ├── ur3e_joint_limited_robot.urdf.xacro │ │ ├── ur3e_robot.urdf.xacro │ │ ├── ur5e.urdf.xacro │ │ ├── ur5e_joint_limited_robot.urdf.xacro │ │ └── ur5e_robot.urdf.xacro ├── ur_e_gazebo │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── controller │ │ ├── arm_controller_ur10e.yaml │ │ ├── arm_controller_ur3e.yaml │ │ ├── arm_controller_ur5e.yaml │ │ └── joint_state_controller.yaml │ ├── launch │ │ ├── controller_utils.launch │ │ ├── ur10e.launch │ │ ├── ur10e_joint_limited.launch │ │ ├── ur3e.launch │ │ ├── ur3e_joint_limited.launch │ │ ├── ur5e.launch │ │ └── ur5e_joint_limited.launch │ ├── package.xml │ └── tests │ │ └── roslaunch_test.xml ├── ur_gazebo │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── controller │ │ ├── arm_controller_ur10.yaml │ │ ├── arm_controller_ur3.yaml │ │ ├── arm_controller_ur5.yaml │ │ └── joint_state_controller.yaml │ ├── launch │ │ ├── controller_utils.launch │ │ ├── ur10.launch │ │ ├── ur10_joint_limited.launch │ │ ├── ur3.launch │ │ ├── ur3_joint_limited.launch │ │ ├── ur5.launch │ │ └── ur5_joint_limited.launch │ ├── package.xml │ └── tests │ │ └── roslaunch_test.xml ├── ur_kinematics │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── ur_kinematics │ │ │ ├── ikfast.h │ │ │ ├── ur_kin.h │ │ │ └── ur_moveit_plugin.h │ ├── package.xml │ ├── setup.py │ ├── src │ │ ├── ur_kin.cpp │ │ ├── ur_kin_py.cpp │ │ ├── ur_kinematics │ │ │ ├── __init__.py │ │ │ └── test_analytical_ik.py │ │ └── ur_moveit_plugin.cpp │ └── ur_moveit_plugins.xml └── ur_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── msg │ ├── Analog.msg │ ├── Digital.msg │ ├── IOStates.msg │ ├── MasterboardDataMsg.msg │ ├── RobotModeDataMsg.msg │ ├── RobotStateRTMsg.msg │ └── ToolDataMsg.msg │ ├── package.xml │ └── srv │ ├── SetIO.srv │ ├── SetPayload.srv │ └── SetSpeedSliderFraction.srv └── urwh_ikfast_arm_plugin ├── CMakeLists.txt ├── include └── ikfast.h ├── package.xml ├── src ├── urwh_arm_ikfast_moveit_plugin.cpp └── urwh_arm_ikfast_solver.cpp ├── update_ikfast_plugin.sh └── urwh_arm_moveit_ikfast_plugin_description.xml /.catkin_workspace: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/.catkin_workspace -------------------------------------------------------------------------------- /.vscode/launch.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/.vscode/launch.json -------------------------------------------------------------------------------- /.vscode/launch_args.json: -------------------------------------------------------------------------------- 1 | {} -------------------------------------------------------------------------------- /.vscode/tasks.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/.vscode/tasks.json -------------------------------------------------------------------------------- /.ycm_extra_conf.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/.ycm_extra_conf.py -------------------------------------------------------------------------------- /.ycm_extra_conf.pyc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/.ycm_extra_conf.pyc -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/README.md -------------------------------------------------------------------------------- /readme.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/readme.md -------------------------------------------------------------------------------- /src/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | /opt/ros/kinetic/share/catkin/cmake/toplevel.cmake -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/.gitignore: -------------------------------------------------------------------------------- 1 | *pyc 2 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | /opt/ros/kinetic/share/catkin/cmake/toplevel.cmake -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/.gitignore: -------------------------------------------------------------------------------- 1 | *.swp 2 | *.pyc 3 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/.gitremotes: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/.gitremotes -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/CMakeLists.txt -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/launch/gazebo2marker.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/launch/gazebo2marker.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/launch/gazebo2moveit.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/launch/gazebo2moveit.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/launch/gazebo2rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/launch/gazebo2rviz.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/launch/gazebo2tf.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/launch/gazebo2tf.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/launch/sdf2moveit.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/launch/sdf2moveit.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/launch/sdf2rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/launch/sdf2rviz.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/setup.py -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo2rviz/src/gazebo2rviz/__init__.py: -------------------------------------------------------------------------------- 1 | from conversions import link2marker_msg 2 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/.gitignore -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/CONTRIBUTING.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/CONTRIBUTING.md -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/README.md -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/SENSORS.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/SENSORS.md -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_dev/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_dev/CHANGELOG.rst -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_dev/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_dev/CMakeLists.txt -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_dev/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_dev/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_msgs/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/CHANGELOG.rst -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/CMakeLists.txt -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/scripts/debug: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/scripts/debug -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/scripts/gazebo: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/scripts/gazebo -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/scripts/gdbrun: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/scripts/gdbrun -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/scripts/perf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/scripts/perf -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/setup.py -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/gazebo_ros_pkgs/gazebo_ros/src/gazebo_ros/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/CHANGELOG.rst -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/CMakeLists.txt -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/README.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/README.rst -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/CMakeLists.txt -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/creative/main.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/creative/main.cpp -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/reconst3d/TODO: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/reconst3d/TODO -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/reconst3d/model.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/reconst3d/model.cpp -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/rgbd/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/rgbd/CMakeLists.txt -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/rgbd/doc/rgbd.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/rgbd/doc/rgbd.rst -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/rgbd/src/normal.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/rgbd/src/normal.cpp -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/rgbd/src/plane.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/rgbd/src/plane.cpp -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/rgbd/src/utils.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/rgbd/src/utils.cpp -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/rgbd/src/utils.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/rgbd/src/utils.h -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/rgbd/test/test_main.cpp: -------------------------------------------------------------------------------- 1 | #include "test_precomp.hpp" 2 | 3 | CV_TEST_MAIN("rgbd") 4 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/opencv_candidate/src/rgbd/test/test_precomp.cpp: -------------------------------------------------------------------------------- 1 | #include "test_precomp.hpp" 2 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/CMakeLists.txt -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/scripts/sdf2urdf.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/scripts/sdf2urdf.py -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/setup.py -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/src/pysdf/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/src/pysdf/__init__.py -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/src/pysdf/conversions.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/src/pysdf/conversions.py -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/src/pysdf/naming.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/src/pysdf/naming.py -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/src/pysdf/parse.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/pysdf/src/pysdf/parse.py -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/.gitignore -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/.travis.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/.travis.yml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/LICENSE -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/README.md -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/combined_robot_hw/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/combined_robot_hw/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/controller_interface/.gitignore: -------------------------------------------------------------------------------- 1 | bin 2 | build 3 | doc 4 | lib 5 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/controller_manager/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/controller_manager/README.md -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/controller_manager/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/controller_manager/setup.py -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/controller_manager/src/controller_manager/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/controller_manager_msgs/rosdoc.yaml: -------------------------------------------------------------------------------- 1 | - builder: epydoc 2 | output_dir: python 3 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/controller_manager_msgs/src/controller_manager_msgs/__init__.py: -------------------------------------------------------------------------------- 1 | 2 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/controller_manager_tests/src/controller_manager_tests/__init__.py: -------------------------------------------------------------------------------- 1 | from .controller_manager_dummy import * 2 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/docs/architecture.svg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/docs/architecture.svg -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/hardware_interface/.gitignore: -------------------------------------------------------------------------------- 1 | doc 2 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/joint_limits_interface/.gitignore: -------------------------------------------------------------------------------- 1 | bin 2 | build 3 | doc 4 | lib 5 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/ros_control.rosinstall: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/ros_control.rosinstall -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/ros_control/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/ros_control/CHANGELOG.rst -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/ros_control/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/ros_control/CMakeLists.txt -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/ros_control/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/ros_control/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/rqt_controller_manager/src/rqt_controller_manager/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_control/transmission_interface/.gitignore: -------------------------------------------------------------------------------- 1 | doc -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_controllers/diff_drive_controller/test/diffbot_open_loop.yaml: -------------------------------------------------------------------------------- 1 | diffbot_controller: 2 | open_loop: true 3 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_controllers/diff_drive_controller/test/diffbot_timeout.yaml: -------------------------------------------------------------------------------- 1 | diffbot_controller: 2 | cmd_vel_timeout: 0.5 3 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_controllers/effort_controllers/.gitignore: -------------------------------------------------------------------------------- 1 | build 2 | lib -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_controllers/force_torque_sensor_controller/.gitignore: -------------------------------------------------------------------------------- 1 | bin 2 | build 3 | lib -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_controllers/forward_command_controller/.gitignore: -------------------------------------------------------------------------------- 1 | build -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_controllers/imu_sensor_controller/.gitignore: -------------------------------------------------------------------------------- 1 | bin 2 | build 3 | lib -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_controllers/joint_state_controller/.gitignore: -------------------------------------------------------------------------------- 1 | build 2 | lib -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_controllers/joint_trajectory_controller/.gitignore: -------------------------------------------------------------------------------- 1 | bin 2 | build 3 | doc 4 | lib 5 | manifest.xml 6 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_controllers/position_controllers/.gitignore: -------------------------------------------------------------------------------- 1 | build 2 | lib -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_controllers/rqt_joint_trajectory_controller/rosdoc.yaml: -------------------------------------------------------------------------------- 1 | - builder: epydoc 2 | output_dir: python -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_controllers/rqt_joint_trajectory_controller/src/rqt_joint_trajectory_controller/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ros_controllers/velocity_controllers/.gitignore: -------------------------------------------------------------------------------- 1 | build 2 | lib -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/spawn_robot_tools/.gitignore: -------------------------------------------------------------------------------- 1 | *.pyc 2 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/spawn_robot_tools/README.md: -------------------------------------------------------------------------------- 1 | # My project's README 2 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/spawn_robot_tools/spawn_robot_tools_pkg/src/spawn_robot_tools_pkg/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ur5_gazebo_controllers/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ur5_gazebo_controllers/CMakeLists.txt -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ur5_gazebo_controllers/launch/main.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ur5_gazebo_controllers/launch/main.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/ur5_gazebo_controllers/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/ur5_gazebo_controllers/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/README.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/README.rst -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/CHANGELOG.rst -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/CMakeLists.txt -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/doc/conf.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/doc/conf.py -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/doc/index.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/doc/index.rst -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/doc/mainpage.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/doc/mainpage.dox -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/python/__init__.py.plain.in: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/rosdoc.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/rosdoc.yaml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/setup.py -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/src/boost/README: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/src/boost/README -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/src/cv_bridge.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/src/cv_bridge.cpp -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/src/module.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/src/module.cpp -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/src/module.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/src/module.hpp -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/src/pycompat.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/src/pycompat.hpp -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/test/utest.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/test/utest.cpp -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/test/utest2.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/cv_bridge/test/utest2.cpp -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/image_geometry/doc/conf.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/image_geometry/doc/conf.py -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/image_geometry/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/image_geometry/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/image_geometry/rosdoc.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/image_geometry/rosdoc.yaml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/image_geometry/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/image_geometry/setup.py -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/opencv_tests/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/opencv_tests/CHANGELOG.rst -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/opencv_tests/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/opencv_tests/CMakeLists.txt -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/opencv_tests/mainpage.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/opencv_tests/mainpage.dox -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/opencv_tests/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/opencv_tests/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/vision_opencv/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/vision_opencv/CHANGELOG.rst -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/vision_opencv/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/depends/vision_opencv/vision_opencv/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/readme.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/readme.md -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/.setup_assistant: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/.setup_assistant -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/CMakeLists.txt -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/chomp_planning.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/chomp_planning.yaml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/controllers.yaml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/controllers2.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/controllers2.yaml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/fake_controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/fake_controllers.yaml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/joint_limits.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/joint_limits.yaml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/joint_names.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/joint_names.yaml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/kinematics.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/kinematics.yaml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/ompl_planning.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/ompl_planning.yaml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/ros_controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/ros_controllers.yaml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/sensors_3d.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/sensors_3d.yaml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/urwh.srdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/config/urwh.srdf -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/default_warehouse_db.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/demo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/demo.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/demo_gazebo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/demo_gazebo.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/gazebo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/gazebo.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/joystick_control.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/joystick_control.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/move_group.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/move_group.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/moveit.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/moveit.rviz -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/moveit_rviz.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/planning_context.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/planning_context.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/planning_execution.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/planning_execution.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/planning_pipeline.launch.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/planning_with_pcl.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/planning_with_pcl.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/ros_controllers.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/ros_controllers.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/run_benchmark_ompl.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/sensor_manager.launch.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/setup_assistant.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/setup_assistant.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/warehouse.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/warehouse.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/launch/warehouse_settings.launch.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/confgi/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/robotiq_85_gripper/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/robotiq_85_gripper/LICENSE -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/robotiq_85_gripper/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/robotiq_85_gripper/README.md -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/robotiq_85_gripper/robotiq_85_driver/src/robotiq_85/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/robotiq_85_gripper/robotiq_85_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- 1 | {} -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/robotiq_85_gripper/si_utils/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/robotiq_85_gripper/si_utils/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/CMakeLists.txt -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/launch/test_gripper.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/launch/test_gripper.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/launch/view_arm.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/launch/view_arm.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/meshes/hole.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/meshes/hole.STL -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/meshes/hole.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/meshes/hole.dae -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/meshes/kinect.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/meshes/kinect.dae -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/meshes/kinect.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/meshes/kinect.jpg -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/meshes/kinect.tga: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/meshes/kinect.tga -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/package.xml -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/scripts/test_ur5.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/scripts/test_ur5.py -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/hole.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/hole.urdf -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/kinect.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/kinect.xacro -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/model.config -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/model.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/model.dae -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/model.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/model.urdf -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/model2.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/model2.urdf -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/model_v.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/model_v.urdf -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/ur10_wh.gv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/ur10_wh.gv -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/urwh.gv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/ur_desc/urdf/ur5_robotiq_85/urwh.gv -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/urwh_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/urwh_moveit_config/.setup_assistant -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/urwh_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/urwh_moveit_config/CMakeLists.txt -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/urwh_moveit_config/config/ur10_wh.srdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/urwh_moveit_config/config/ur10_wh.srdf -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/urwh_moveit_config/launch/demo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/urwh_moveit_config/launch/demo.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/urwh_moveit_config/launch/gazebo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/urwh_moveit_config/launch/gazebo.launch -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/urwh_moveit_config/launch/moveit.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/urwh_moveit_config/launch/moveit.rviz -------------------------------------------------------------------------------- /src/UR_with_Robotiq_grasp_gazebo/ur_tc/urwh_moveit_config/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/UR_with_Robotiq_grasp_gazebo/ur_tc/urwh_moveit_config/package.xml -------------------------------------------------------------------------------- /src/gazebo-pkgs/Dockerfile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/Dockerfile -------------------------------------------------------------------------------- /src/gazebo-pkgs/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/LICENSE -------------------------------------------------------------------------------- /src/gazebo-pkgs/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/README.md -------------------------------------------------------------------------------- /src/gazebo-pkgs/TODO.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/TODO.md -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_grasp_plugin/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_grasp_plugin/CHANGELOG.rst -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_grasp_plugin/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_grasp_plugin/CMakeLists.txt -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_grasp_plugin/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_grasp_plugin/package.xml -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_grasp_plugin/src/GazeboGraspFix.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_grasp_plugin/src/GazeboGraspFix.cpp -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_grasp_plugin/src/GazeboGraspGripper.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_grasp_plugin/src/GazeboGraspGripper.cpp -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_state_plugins/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_state_plugins/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_state_plugins/CMakeLists.txt -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_state_plugins/config/GazeboMapPublisher.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_state_plugins/config/GazeboMapPublisher.yaml -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_state_plugins/config/GazeboObjectInfo.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_state_plugins/config/GazeboObjectInfo.yaml -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_state_plugins/config/WorldPlugins.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_state_plugins/config/WorldPlugins.yaml -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_state_plugins/launch/plugin_loader.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_state_plugins/launch/plugin_loader.launch -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_state_plugins/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_state_plugins/package.xml -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_state_plugins/src/GazeboMapPublisher.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_state_plugins/src/GazeboMapPublisher.cpp -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_state_plugins/src/GazeboObjectInfo.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_state_plugins/src/GazeboObjectInfo.cpp -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_state_plugins/test/object_info_request.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_state_plugins/test/object_info_request.cpp -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/CHANGELOG.rst -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/CMakeLists.txt -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/config/FakeObjectRecognizer.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/config/FakeObjectRecognizer.yaml -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/config/ObjectTFBroadcaster.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/config/ObjectTFBroadcaster.yaml -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/launch/fake_object_recognizer.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/launch/fake_object_recognizer.launch -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/launch/gazebo_fake_object_recognition.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/launch/gazebo_fake_object_recognition.launch -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/launch/object_tf_broadcaster.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/launch/object_tf_broadcaster.launch -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/launch/spawn_and_recognize_cube.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/launch/spawn_and_recognize_cube.launch -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/package.xml -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/src/FakeObjectRecognizer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/src/FakeObjectRecognizer.cpp -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/src/SetGazeboPhysicsClient.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/src/SetGazeboPhysicsClient.cpp -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/src/cube_spawner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/src/cube_spawner.cpp -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/src/cube_spawner_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/src/cube_spawner_node.cpp -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/src/fake_object_recognizer_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/src/fake_object_recognizer_node.cpp -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/srv/RecognizeGazeboObject.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/srv/RecognizeGazeboObject.srv -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_test_tools/test/fake_object_recognizer_cmd.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_test_tools/test/fake_object_recognizer_cmd.cpp -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_version_helpers/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_version_helpers/CMakeLists.txt -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_version_helpers/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_version_helpers/package.xml -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_version_helpers/src/GazeboVersionHelpers.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_version_helpers/src/GazeboVersionHelpers.cpp -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_world_plugin_loader/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_world_plugin_loader/CHANGELOG.rst -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_world_plugin_loader/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_world_plugin_loader/CMakeLists.txt -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_world_plugin_loader/config/WorldPluginsTemplate.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_world_plugin_loader/config/WorldPluginsTemplate.config -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_world_plugin_loader/launch/plugin_loader_template.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_world_plugin_loader/launch/plugin_loader_template.launch -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_world_plugin_loader/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_world_plugin_loader/package.xml -------------------------------------------------------------------------------- /src/gazebo-pkgs/gazebo_world_plugin_loader/src/GazeboPluginLoader.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/gazebo-pkgs/gazebo_world_plugin_loader/src/GazeboPluginLoader.cpp -------------------------------------------------------------------------------- /src/general-message-pkgs/Dockerfile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/Dockerfile -------------------------------------------------------------------------------- /src/general-message-pkgs/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/LICENSE -------------------------------------------------------------------------------- /src/general-message-pkgs/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/README.md -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs/msg/Object.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs/msg/Object.msg -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs/msg/ObjectPose.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs/msg/ObjectPose.msg -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs/package.xml -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs/srv/ObjectInfo.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs/srv/ObjectInfo.srv -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs/srv/RegisterObject.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs/srv/RegisterObject.srv -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs_tools/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs_tools/CHANGELOG.rst -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs_tools/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs_tools/CMakeLists.txt -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs_tools/config/ObjectTFBroadcaster.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs_tools/config/ObjectTFBroadcaster.yaml -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs_tools/launch/object_tf_broadcaster.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs_tools/launch/object_tf_broadcaster.launch -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs_tools/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs_tools/package.xml -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs_tools/src/ObjectFunctions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs_tools/src/ObjectFunctions.cpp -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs_tools/src/ObjectTFBroadcaster.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs_tools/src/ObjectTFBroadcaster.cpp -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs_tools/src/object_tf_broadcaster_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs_tools/src/object_tf_broadcaster_node.cpp -------------------------------------------------------------------------------- /src/general-message-pkgs/object_msgs_tools/src/register_object_client.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/object_msgs_tools/src/register_object_client.cpp -------------------------------------------------------------------------------- /src/general-message-pkgs/path_navigation_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/path_navigation_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /src/general-message-pkgs/path_navigation_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/path_navigation_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /src/general-message-pkgs/path_navigation_msgs/action/PathExecution.action: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/path_navigation_msgs/action/PathExecution.action -------------------------------------------------------------------------------- /src/general-message-pkgs/path_navigation_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/general-message-pkgs/path_navigation_msgs/package.xml -------------------------------------------------------------------------------- /src/grasp_msg/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/grasp_msg/CMakeLists.txt -------------------------------------------------------------------------------- /src/grasp_msg/msg/newmsg2.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/grasp_msg/msg/newmsg2.msg -------------------------------------------------------------------------------- /src/grasp_msg/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/grasp_msg/package.xml -------------------------------------------------------------------------------- /src/grasp_msg/script/listener.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/grasp_msg/script/listener.py -------------------------------------------------------------------------------- /src/grasp_msg/script/talker.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/grasp_msg/script/talker.py -------------------------------------------------------------------------------- /src/grasp_msg/src/talkerr.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/grasp_msg/src/talkerr.cpp -------------------------------------------------------------------------------- /src/qt_test/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/qt_test/CMakeLists.txt -------------------------------------------------------------------------------- /src/qt_test/CMakeLists.txt.user: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/qt_test/CMakeLists.txt.user -------------------------------------------------------------------------------- /src/qt_test/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/qt_test/package.xml -------------------------------------------------------------------------------- /src/qt_test/src/mainwindow.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/qt_test/src/mainwindow.cpp -------------------------------------------------------------------------------- /src/qt_test/src/mainwindow.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/qt_test/src/mainwindow.h -------------------------------------------------------------------------------- /src/qt_test/src/mainwindow.ui: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/qt_test/src/mainwindow.ui -------------------------------------------------------------------------------- /src/qt_test/src/qnode.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/qt_test/src/qnode.cpp -------------------------------------------------------------------------------- /src/qt_test/src/qnode.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/qt_test/src/qnode.h -------------------------------------------------------------------------------- /src/qt_test/src/qt_app_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/qt_test/src/qt_app_node.cpp -------------------------------------------------------------------------------- /src/readme.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/readme.md -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/CMakeLists.txt -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/README.md -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/doc/pointcloud.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/doc/pointcloud.png -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/include/realsense_gazebo_plugin/RealSensePlugin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/include/realsense_gazebo_plugin/RealSensePlugin.h -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/launch/depth_proc.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/launch/depth_proc.launch -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/launch/realsense.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/launch/realsense.launch -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/launch/realsense_multiple_urdf.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/launch/realsense_multiple_urdf.launch -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/launch/realsense_urdf.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/launch/realsense_urdf.launch -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/models/realsense_camera/meshes/realsense.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/models/realsense_camera/meshes/realsense.dae -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/models/realsense_camera/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/models/realsense_camera/model.config -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/models/realsense_camera/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/models/realsense_camera/model.sdf -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/package.xml -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/src/RealSensePlugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/src/RealSensePlugin.cpp -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/src/gazebo_ros_realsense.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/src/gazebo_ros_realsense.cpp -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/test/realsense_streams.test: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/test/realsense_streams.test -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/test/realsense_streams_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/test/realsense_streams_test.cpp -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/test/template.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/test/template.cpp -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/urdf/multi_rs200_simulation.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/urdf/multi_rs200_simulation.xacro -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/urdf/realsense-RS200.macro.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/urdf/realsense-RS200.macro.xacro -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/urdf/rs200_simulation.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/urdf/rs200_simulation.xacro -------------------------------------------------------------------------------- /src/realsense_gazebo_plugin/worlds/realsense.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/realsense_gazebo_plugin/worlds/realsense.world -------------------------------------------------------------------------------- /src/test_ikfast_plugin/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/test_ikfast_plugin/CMakeLists.txt -------------------------------------------------------------------------------- /src/test_ikfast_plugin/include/ikfast.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/test_ikfast_plugin/include/ikfast.h -------------------------------------------------------------------------------- /src/test_ikfast_plugin/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/test_ikfast_plugin/package.xml -------------------------------------------------------------------------------- /src/test_ikfast_plugin/src/ur5_manipulator_ikfast_moveit_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/test_ikfast_plugin/src/ur5_manipulator_ikfast_moveit_plugin.cpp -------------------------------------------------------------------------------- /src/test_ikfast_plugin/src/ur5_manipulator_ikfast_solver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/test_ikfast_plugin/src/ur5_manipulator_ikfast_solver.cpp -------------------------------------------------------------------------------- /src/test_ikfast_plugin/update_ikfast_plugin.sh: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/test_ikfast_plugin/update_ikfast_plugin.sh -------------------------------------------------------------------------------- /src/test_ikfast_plugin/ur5_manipulator_moveit_ikfast_plugin_description.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/test_ikfast_plugin/ur5_manipulator_moveit_ikfast_plugin_description.xml -------------------------------------------------------------------------------- /src/universal_robot/.gitignore: -------------------------------------------------------------------------------- 1 | *~ 2 | *.pyc 3 | 4 | -------------------------------------------------------------------------------- /src/universal_robot/.travis.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/.travis.yml -------------------------------------------------------------------------------- /src/universal_robot/CONTRIBUTING.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/CONTRIBUTING.md -------------------------------------------------------------------------------- /src/universal_robot/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/README.md -------------------------------------------------------------------------------- /src/universal_robot/universal_robot/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/universal_robot/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/universal_robot/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/universal_robot/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/universal_robot/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/universal_robot/package.xml -------------------------------------------------------------------------------- /src/universal_robot/universal_robots/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/universal_robots/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/universal_robots/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/universal_robots/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/universal_robots/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/universal_robots/package.xml -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/.setup_assistant -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/config/controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/config/controllers.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/config/fake_controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/config/fake_controllers.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/config/joint_limits.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/config/joint_limits.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/config/kinematics.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/config/ompl_planning.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/config/ompl_planning.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/config/ur10e.srdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/config/ur10e.srdf -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/launch/default_warehouse_db.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/launch/demo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/launch/demo.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/launch/move_group.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/launch/move_group.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/launch/moveit.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/launch/moveit.rviz -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/launch/moveit_rviz.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/launch/planning_context.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/launch/planning_context.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/launch/planning_pipeline.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/launch/run_benchmark_ompl.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/launch/sensor_manager.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/launch/setup_assistant.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/launch/trajectory_execution.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/launch/trajectory_execution.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/launch/warehouse.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/launch/warehouse_settings.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/package.xml -------------------------------------------------------------------------------- /src/universal_robot/ur10_e_moveit_config/tests/moveit_planning_execution.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_e_moveit_config/tests/moveit_planning_execution.xml -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/.setup_assistant -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/config/controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/config/controllers.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/config/fake_controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/config/fake_controllers.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/config/joint_limits.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/config/joint_limits.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/config/kinematics.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/config/ompl_planning.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/config/ompl_planning.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/config/ur10.srdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/config/ur10.srdf -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/launch/default_warehouse_db.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/launch/demo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/launch/demo.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/launch/move_group.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/launch/move_group.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/launch/moveit.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/launch/moveit.rviz -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/launch/moveit_rviz.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/launch/ompl_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/launch/ompl_planning_pipeline.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/launch/planning_context.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/launch/planning_context.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/launch/planning_pipeline.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/launch/run_benchmark_ompl.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/launch/sensor_manager.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/launch/setup_assistant.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/launch/trajectory_execution.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/launch/trajectory_execution.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/launch/warehouse.launch -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/launch/warehouse_settings.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/package.xml -------------------------------------------------------------------------------- /src/universal_robot/ur10_moveit_config/tests/moveit_planning_execution.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur10_moveit_config/tests/moveit_planning_execution.xml -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/.setup_assistant -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/config/controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/config/controllers.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/config/fake_controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/config/fake_controllers.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/config/joint_limits.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/config/joint_limits.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/config/kinematics.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/config/ompl_planning.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/config/ompl_planning.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/config/ur3e.srdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/config/ur3e.srdf -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/launch/default_warehouse_db.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/launch/demo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/launch/demo.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/launch/joystick_control.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/launch/joystick_control.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/launch/move_group.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/launch/move_group.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/launch/moveit.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/launch/moveit.rviz -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/launch/moveit_rviz.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/launch/planning_context.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/launch/planning_context.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/launch/planning_pipeline.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/launch/run_benchmark_ompl.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/launch/sensor_manager.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/launch/setup_assistant.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/launch/trajectory_execution.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/launch/trajectory_execution.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/launch/warehouse.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/launch/warehouse_settings.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/package.xml -------------------------------------------------------------------------------- /src/universal_robot/ur3_e_moveit_config/tests/moveit_planning_execution.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_e_moveit_config/tests/moveit_planning_execution.xml -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/.setup_assistant -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/config/controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/config/controllers.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/config/fake_controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/config/fake_controllers.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/config/joint_limits.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/config/joint_limits.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/config/kinematics.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/config/ompl_planning.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/config/ompl_planning.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/config/ur3.srdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/config/ur3.srdf -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/default_warehouse_db.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/demo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/demo.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/joystick_control.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/joystick_control.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/move_group.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/move_group.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/moveit.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/moveit.rviz -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/moveit_rviz.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/ompl_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/ompl_planning_pipeline.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/planning_context.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/planning_context.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/planning_pipeline.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/run_benchmark_ompl.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/sensor_manager.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/setup_assistant.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/trajectory_execution.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/trajectory_execution.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/warehouse.launch -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/launch/warehouse_settings.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/package.xml -------------------------------------------------------------------------------- /src/universal_robot/ur3_moveit_config/tests/moveit_planning_execution.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur3_moveit_config/tests/moveit_planning_execution.xml -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/.setup_assistant -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/config/controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/config/controllers.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/config/fake_controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/config/fake_controllers.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/config/joint_limits.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/config/joint_limits.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/config/kinematics.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/config/ompl_planning.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/config/ompl_planning.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/config/ur5e.srdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/config/ur5e.srdf -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/launch/default_warehouse_db.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/launch/demo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/launch/demo.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/launch/move_group.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/launch/move_group.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/launch/moveit.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/launch/moveit.rviz -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/launch/moveit_rviz.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/launch/planning_context.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/launch/planning_context.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/launch/planning_pipeline.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/launch/run_benchmark_ompl.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/launch/sensor_manager.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/launch/setup_assistant.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/launch/trajectory_execution.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/launch/trajectory_execution.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/launch/warehouse.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/launch/warehouse_settings.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/package.xml -------------------------------------------------------------------------------- /src/universal_robot/ur5_e_moveit_config/tests/moveit_planning_execution.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_e_moveit_config/tests/moveit_planning_execution.xml -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/.setup_assistant -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/config/controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/config/controllers.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/config/fake_controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/config/fake_controllers.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/config/joint_limits.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/config/joint_limits.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/config/kinematics.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/config/ompl_planning.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/config/ompl_planning.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/config/ur5.srdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/config/ur5.srdf -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/launch/default_warehouse_db.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/launch/demo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/launch/demo.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/launch/move_group.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/launch/move_group.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/launch/moveit.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/launch/moveit.rviz -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/launch/moveit_rviz.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/launch/ompl_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/launch/ompl_planning_pipeline.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/launch/planning_context.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/launch/planning_context.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/launch/planning_pipeline.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/launch/run_benchmark_ompl.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/launch/sensor_manager.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/launch/setup_assistant.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/launch/trajectory_execution.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/launch/trajectory_execution.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/launch/warehouse.launch -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/launch/warehouse_settings.launch.xml -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/package.xml -------------------------------------------------------------------------------- /src/universal_robot/ur5_moveit_config/tests/moveit_planning_execution.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur5_moveit_config/tests/moveit_planning_execution.xml -------------------------------------------------------------------------------- /src/universal_robot/ur_bringup/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_bringup/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/ur_bringup/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_bringup/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/ur_bringup/launch/ur10_bringup.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_bringup/launch/ur10_bringup.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_bringup/launch/ur10_bringup_joint_limited.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_bringup/launch/ur10_bringup_joint_limited.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_bringup/launch/ur3_bringup.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_bringup/launch/ur3_bringup.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_bringup/launch/ur3_bringup_joint_limited.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_bringup/launch/ur3_bringup_joint_limited.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_bringup/launch/ur5_bringup.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_bringup/launch/ur5_bringup.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_bringup/launch/ur5_bringup_joint_limited.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_bringup/launch/ur5_bringup_joint_limited.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_bringup/launch/ur_common.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_bringup/launch/ur_common.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_bringup/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_bringup/package.xml -------------------------------------------------------------------------------- /src/universal_robot/ur_bringup/tests/roslaunch_test.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_bringup/tests/roslaunch_test.xml -------------------------------------------------------------------------------- /src/universal_robot/ur_description/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/ur_description/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/ur_description/cfg/view_robot.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/cfg/view_robot.rviz -------------------------------------------------------------------------------- /src/universal_robot/ur_description/launch/ur10_upload.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/launch/ur10_upload.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_description/launch/ur3_upload.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/launch/ur3_upload.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_description/launch/ur5_upload.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/launch/ur5_upload.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_description/launch/view_ur10.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/launch/view_ur10.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_description/launch/view_ur3.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/launch/view_ur3.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_description/launch/view_ur5.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/launch/view_ur5.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur10/collision/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur10/collision/base.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur10/collision/forearm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur10/collision/forearm.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur10/collision/shoulder.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur10/collision/shoulder.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur10/collision/upperarm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur10/collision/upperarm.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur10/collision/wrist1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur10/collision/wrist1.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur10/collision/wrist2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur10/collision/wrist2.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur10/collision/wrist3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur10/collision/wrist3.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur10/visual/base.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur10/visual/base.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur10/visual/forearm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur10/visual/forearm.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur10/visual/shoulder.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur10/visual/shoulder.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur10/visual/upperarm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur10/visual/upperarm.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur10/visual/wrist1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur10/visual/wrist1.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur10/visual/wrist2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur10/visual/wrist2.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur10/visual/wrist3.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur10/visual/wrist3.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur3/collision/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur3/collision/base.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur3/collision/forearm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur3/collision/forearm.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur3/collision/shoulder.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur3/collision/shoulder.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur3/collision/upperarm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur3/collision/upperarm.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur3/collision/wrist1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur3/collision/wrist1.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur3/collision/wrist2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur3/collision/wrist2.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur3/collision/wrist3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur3/collision/wrist3.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur3/visual/base.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur3/visual/base.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur3/visual/forearm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur3/visual/forearm.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur3/visual/shoulder.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur3/visual/shoulder.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur3/visual/upperarm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur3/visual/upperarm.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur3/visual/wrist1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur3/visual/wrist1.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur3/visual/wrist2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur3/visual/wrist2.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur3/visual/wrist3.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur3/visual/wrist3.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur5/collision/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur5/collision/base.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur5/collision/forearm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur5/collision/forearm.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur5/collision/shoulder.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur5/collision/shoulder.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur5/collision/upperarm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur5/collision/upperarm.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur5/collision/wrist1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur5/collision/wrist1.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur5/collision/wrist2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur5/collision/wrist2.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur5/collision/wrist3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur5/collision/wrist3.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur5/visual/base.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur5/visual/base.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur5/visual/forearm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur5/visual/forearm.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur5/visual/shoulder.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur5/visual/shoulder.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur5/visual/upperarm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur5/visual/upperarm.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur5/visual/wrist1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur5/visual/wrist1.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur5/visual/wrist2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur5/visual/wrist2.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/meshes/ur5/visual/wrist3.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/meshes/ur5/visual/wrist3.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/model.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/model.pdf -------------------------------------------------------------------------------- /src/universal_robot/ur_description/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/package.xml -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/common.gazebo.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/common.gazebo.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ikfast61_arm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ikfast61_arm.cpp -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ur.gazebo.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ur.gazebo.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ur.transmission.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ur.transmission.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ur10.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ur10.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ur10_joint_limited_robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ur10_joint_limited_robot.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ur10_robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ur10_robot.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ur3.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ur3.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ur3_joint_limited_robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ur3_joint_limited_robot.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ur3_robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ur3_robot.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ur5.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ur5.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ur5_joint_limited_robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ur5_joint_limited_robot.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ur5_robot.backup.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ur5_robot.backup.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ur5_robot.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ur5_robot.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ur5_robot.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ur5_robot.urdf -------------------------------------------------------------------------------- /src/universal_robot/ur_description/urdf/ur5_robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_description/urdf/ur5_robot.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/cfg/view_robot.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/cfg/view_robot.rviz -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/launch/ur10e_upload.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/launch/ur10e_upload.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/launch/ur3e_upload.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/launch/ur3e_upload.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/launch/ur5e_upload.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/launch/ur5e_upload.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/launch/view_ur10e.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/launch/view_ur10e.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/launch/view_ur3e.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/launch/view_ur3e.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/launch/view_ur5e.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/launch/view_ur5e.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur10e/collision/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur10e/collision/base.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur10e/collision/forearm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur10e/collision/forearm.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur10e/collision/shoulder.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur10e/collision/shoulder.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur10e/collision/upperarm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur10e/collision/upperarm.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur10e/collision/wrist1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur10e/collision/wrist1.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur10e/collision/wrist2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur10e/collision/wrist2.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur10e/collision/wrist3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur10e/collision/wrist3.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur10e/visual/base.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur10e/visual/base.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur10e/visual/forearm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur10e/visual/forearm.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur10e/visual/shoulder.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur10e/visual/shoulder.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur10e/visual/upperarm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur10e/visual/upperarm.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur10e/visual/wrist1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur10e/visual/wrist1.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur10e/visual/wrist2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur10e/visual/wrist2.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur10e/visual/wrist3.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur10e/visual/wrist3.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur3e/collision/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur3e/collision/base.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur3e/collision/forearm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur3e/collision/forearm.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur3e/collision/shoulder.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur3e/collision/shoulder.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur3e/collision/upperarm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur3e/collision/upperarm.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur3e/collision/wrist1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur3e/collision/wrist1.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur3e/collision/wrist2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur3e/collision/wrist2.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur3e/collision/wrist3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur3e/collision/wrist3.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur3e/visual/base.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur3e/visual/base.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur3e/visual/forearm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur3e/visual/forearm.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur3e/visual/shoulder.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur3e/visual/shoulder.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur3e/visual/upperarm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur3e/visual/upperarm.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur3e/visual/wrist1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur3e/visual/wrist1.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur3e/visual/wrist2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur3e/visual/wrist2.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur3e/visual/wrist3.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur3e/visual/wrist3.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur5e/collision/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur5e/collision/base.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur5e/collision/forearm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur5e/collision/forearm.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur5e/collision/shoulder.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur5e/collision/shoulder.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur5e/collision/upperarm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur5e/collision/upperarm.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur5e/collision/wrist1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur5e/collision/wrist1.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur5e/collision/wrist2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur5e/collision/wrist2.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur5e/collision/wrist3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur5e/collision/wrist3.stl -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur5e/visual/base.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur5e/visual/base.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur5e/visual/forearm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur5e/visual/forearm.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur5e/visual/shoulder.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur5e/visual/shoulder.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur5e/visual/upperarm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur5e/visual/upperarm.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur5e/visual/wrist1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur5e/visual/wrist1.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur5e/visual/wrist2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur5e/visual/wrist2.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/meshes/ur5e/visual/wrist3.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/meshes/ur5e/visual/wrist3.dae -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/package.xml -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/urdf/common.gazebo.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/urdf/common.gazebo.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/urdf/ur.gazebo.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/urdf/ur.gazebo.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/urdf/ur.transmission.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/urdf/ur.transmission.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/urdf/ur10e.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/urdf/ur10e.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/urdf/ur10e_joint_limited_robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/urdf/ur10e_joint_limited_robot.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/urdf/ur10e_robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/urdf/ur10e_robot.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/urdf/ur3e.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/urdf/ur3e.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/urdf/ur3e_joint_limited_robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/urdf/ur3e_joint_limited_robot.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/urdf/ur3e_robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/urdf/ur3e_robot.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/urdf/ur5e.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/urdf/ur5e.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/urdf/ur5e_joint_limited_robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/urdf/ur5e_joint_limited_robot.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_e_description/urdf/ur5e_robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_description/urdf/ur5e_robot.urdf.xacro -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/controller/arm_controller_ur10e.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/controller/arm_controller_ur10e.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/controller/arm_controller_ur3e.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/controller/arm_controller_ur3e.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/controller/arm_controller_ur5e.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/controller/arm_controller_ur5e.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/controller/joint_state_controller.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/controller/joint_state_controller.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/launch/controller_utils.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/launch/controller_utils.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/launch/ur10e.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/launch/ur10e.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/launch/ur10e_joint_limited.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/launch/ur10e_joint_limited.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/launch/ur3e.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/launch/ur3e.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/launch/ur3e_joint_limited.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/launch/ur3e_joint_limited.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/launch/ur5e.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/launch/ur5e.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/launch/ur5e_joint_limited.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/launch/ur5e_joint_limited.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/package.xml -------------------------------------------------------------------------------- /src/universal_robot/ur_e_gazebo/tests/roslaunch_test.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_e_gazebo/tests/roslaunch_test.xml -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/controller/arm_controller_ur10.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/controller/arm_controller_ur10.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/controller/arm_controller_ur3.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/controller/arm_controller_ur3.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/controller/arm_controller_ur5.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/controller/arm_controller_ur5.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/controller/joint_state_controller.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/controller/joint_state_controller.yaml -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/launch/controller_utils.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/launch/controller_utils.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/launch/ur10.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/launch/ur10.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/launch/ur10_joint_limited.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/launch/ur10_joint_limited.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/launch/ur3.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/launch/ur3.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/launch/ur3_joint_limited.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/launch/ur3_joint_limited.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/launch/ur5.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/launch/ur5.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/launch/ur5_joint_limited.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/launch/ur5_joint_limited.launch -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/package.xml -------------------------------------------------------------------------------- /src/universal_robot/ur_gazebo/tests/roslaunch_test.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_gazebo/tests/roslaunch_test.xml -------------------------------------------------------------------------------- /src/universal_robot/ur_kinematics/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_kinematics/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/ur_kinematics/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_kinematics/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/ur_kinematics/include/ur_kinematics/ikfast.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_kinematics/include/ur_kinematics/ikfast.h -------------------------------------------------------------------------------- /src/universal_robot/ur_kinematics/include/ur_kinematics/ur_kin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_kinematics/include/ur_kinematics/ur_kin.h -------------------------------------------------------------------------------- /src/universal_robot/ur_kinematics/include/ur_kinematics/ur_moveit_plugin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_kinematics/include/ur_kinematics/ur_moveit_plugin.h -------------------------------------------------------------------------------- /src/universal_robot/ur_kinematics/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_kinematics/package.xml -------------------------------------------------------------------------------- /src/universal_robot/ur_kinematics/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_kinematics/setup.py -------------------------------------------------------------------------------- /src/universal_robot/ur_kinematics/src/ur_kin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_kinematics/src/ur_kin.cpp -------------------------------------------------------------------------------- /src/universal_robot/ur_kinematics/src/ur_kin_py.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_kinematics/src/ur_kin_py.cpp -------------------------------------------------------------------------------- /src/universal_robot/ur_kinematics/src/ur_kinematics/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/universal_robot/ur_kinematics/src/ur_kinematics/test_analytical_ik.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_kinematics/src/ur_kinematics/test_analytical_ik.py -------------------------------------------------------------------------------- /src/universal_robot/ur_kinematics/src/ur_moveit_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_kinematics/src/ur_moveit_plugin.cpp -------------------------------------------------------------------------------- /src/universal_robot/ur_kinematics/ur_moveit_plugins.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_kinematics/ur_moveit_plugins.xml -------------------------------------------------------------------------------- /src/universal_robot/ur_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /src/universal_robot/ur_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /src/universal_robot/ur_msgs/msg/Analog.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_msgs/msg/Analog.msg -------------------------------------------------------------------------------- /src/universal_robot/ur_msgs/msg/Digital.msg: -------------------------------------------------------------------------------- 1 | uint8 pin 2 | bool state 3 | -------------------------------------------------------------------------------- /src/universal_robot/ur_msgs/msg/IOStates.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_msgs/msg/IOStates.msg -------------------------------------------------------------------------------- /src/universal_robot/ur_msgs/msg/MasterboardDataMsg.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_msgs/msg/MasterboardDataMsg.msg -------------------------------------------------------------------------------- /src/universal_robot/ur_msgs/msg/RobotModeDataMsg.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_msgs/msg/RobotModeDataMsg.msg -------------------------------------------------------------------------------- /src/universal_robot/ur_msgs/msg/RobotStateRTMsg.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_msgs/msg/RobotStateRTMsg.msg -------------------------------------------------------------------------------- /src/universal_robot/ur_msgs/msg/ToolDataMsg.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_msgs/msg/ToolDataMsg.msg -------------------------------------------------------------------------------- /src/universal_robot/ur_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_msgs/package.xml -------------------------------------------------------------------------------- /src/universal_robot/ur_msgs/srv/SetIO.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_msgs/srv/SetIO.srv -------------------------------------------------------------------------------- /src/universal_robot/ur_msgs/srv/SetPayload.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_msgs/srv/SetPayload.srv -------------------------------------------------------------------------------- /src/universal_robot/ur_msgs/srv/SetSpeedSliderFraction.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/universal_robot/ur_msgs/srv/SetSpeedSliderFraction.srv -------------------------------------------------------------------------------- /src/urwh_ikfast_arm_plugin/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/urwh_ikfast_arm_plugin/CMakeLists.txt -------------------------------------------------------------------------------- /src/urwh_ikfast_arm_plugin/include/ikfast.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/urwh_ikfast_arm_plugin/include/ikfast.h -------------------------------------------------------------------------------- /src/urwh_ikfast_arm_plugin/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/urwh_ikfast_arm_plugin/package.xml -------------------------------------------------------------------------------- /src/urwh_ikfast_arm_plugin/src/urwh_arm_ikfast_moveit_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/urwh_ikfast_arm_plugin/src/urwh_arm_ikfast_moveit_plugin.cpp -------------------------------------------------------------------------------- /src/urwh_ikfast_arm_plugin/src/urwh_arm_ikfast_solver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/urwh_ikfast_arm_plugin/src/urwh_arm_ikfast_solver.cpp -------------------------------------------------------------------------------- /src/urwh_ikfast_arm_plugin/update_ikfast_plugin.sh: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/urwh_ikfast_arm_plugin/update_ikfast_plugin.sh -------------------------------------------------------------------------------- /src/urwh_ikfast_arm_plugin/urwh_arm_moveit_ikfast_plugin_description.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zzy5510/UR5-grasp-and-kinect-demo-on-gazebo/HEAD/src/urwh_ikfast_arm_plugin/urwh_arm_moveit_ikfast_plugin_description.xml --------------------------------------------------------------------------------