├── README.md ├── UR5-robotiq85_gripper-gazebo ├── CMakeLists.txt ├── README.md ├── gjt_ur │ ├── gjt_ur_description │ │ ├── CMakeLists.txt │ │ ├── cfg │ │ │ └── view_robot.rviz │ │ ├── launch │ │ │ ├── ur5_upload.launch │ │ │ ├── ur5_upload_robotiq85_gripper.launch │ │ │ ├── view_ur5.launch │ │ │ └── view_ur5_robotiq85_gripper.launch │ │ ├── meshes │ │ │ └── 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 │ │ ├── package.xml │ │ └── urdf │ │ │ ├── 1common.gazebo.xacro │ │ │ ├── common.gazebo.xacro │ │ │ ├── ur.gazebo.xacro │ │ │ ├── ur.transmission.xacro │ │ │ ├── ur5.urdf.xacro │ │ │ ├── ur5_joint_limited_robot.urdf.xacro │ │ │ ├── ur5_robot.urdf.xacro │ │ │ ├── ur5_robot_robotiq85_gripper.urdf.xacro │ │ │ └── vaccum_gripper.xacro │ └── gjt_ur_gazebo │ │ ├── CMakeLists.txt │ │ ├── controller │ │ ├── arm_controller_ur5.yaml │ │ └── joint_state_controller.yaml │ │ ├── launch │ │ ├── controller_utils.launch │ │ ├── model_test.launch │ │ ├── ur5.launch │ │ └── ur5_joint_limited.launch │ │ ├── package.xml │ │ ├── src │ │ └── roboticsgroup_gazebo_plugins │ │ │ ├── CHANGELOG.rst │ │ │ ├── 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 │ │ ├── tests │ │ └── roslaunch_test.xml │ │ └── urdf │ │ ├── add_beer.sdf │ │ ├── banana.urdf │ │ ├── beer │ │ ├── materials │ │ │ ├── scripts │ │ │ │ └── beer.material │ │ │ └── textures │ │ │ │ └── beer.png │ │ ├── model-1_4.sdf │ │ ├── model.config │ │ └── model.sdf │ │ ├── block.urdf │ │ ├── cafe_table │ │ ├── materials │ │ │ └── textures │ │ │ │ ├── Maple.jpg │ │ │ │ └── Wood_Floor_Dark.jpg │ │ ├── meshes │ │ │ └── cafe_table.dae │ │ ├── model-1_4.sdf │ │ ├── model.config │ │ └── model.sdf │ │ ├── coke_can │ │ ├── materials │ │ │ └── textures │ │ │ │ └── coke_can.png │ │ ├── meshes │ │ │ └── coke_can.dae │ │ ├── model-1_2.sdf │ │ ├── model-1_3.sdf │ │ ├── model-1_4.sdf │ │ ├── model.config │ │ └── model.sdf │ │ ├── cylinder.urdf │ │ ├── dropbox.urdf │ │ ├── long_block.urdf │ │ ├── meshes │ │ ├── banana.dae │ │ └── dropbox.dae │ │ ├── table_marble │ │ ├── materials │ │ │ ├── scripts │ │ │ │ └── table_lightmap.material │ │ │ └── textures │ │ │ │ ├── marble.png │ │ │ │ ├── marble_black.png │ │ │ │ ├── table_lightmap.png │ │ │ │ └── table_lightmap_black.png │ │ ├── meshes │ │ │ └── table_lightmap.dae │ │ ├── model-1_4.sdf │ │ ├── model.config │ │ └── model.sdf │ │ └── test.urdf └── 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_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 │ ├── 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 ├── gazebo-pkgs ├── Dockerfile ├── LICENSE ├── README.md ├── TODO.md ├── gazebo_grasp_plugin_ros │ ├── CMakeLists.txt │ ├── README.md │ ├── msg │ │ └── GazeboGraspEvent.msg │ ├── package.xml │ └── src │ │ └── grasp_event_republisher.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_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 ├── gripper_breakdown_solution-master ├── README.md └── gazebo_plugins │ ├── gazebo_grasp_plugin │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── gazebo_grasp_plugin │ │ │ ├── GazeboGraspFix.h │ │ │ └── GazeboGraspGripper.h │ ├── msgs │ │ ├── CMakeLists.txt │ │ └── grasp_event.proto │ ├── package.xml │ └── src │ │ ├── GazeboGraspFix.cpp │ │ └── GazeboGraspGripper.cpp │ ├── gazebo_version_helpers │ ├── CMakeLists.txt │ ├── include │ │ └── gazebo_version_helpers │ │ │ └── GazeboVersionHelpers.h │ ├── package.xml │ └── src │ │ └── GazeboVersionHelpers.cpp │ ├── household_objects_database_msgs │ ├── .travis.yml │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── msg │ │ ├── DatabaseModelPose.msg │ │ ├── DatabaseModelPoseList.msg │ │ ├── DatabaseReturnCode.msg │ │ └── DatabaseScan.msg │ ├── package.xml │ └── srv │ │ ├── GetModelDescription.srv │ │ ├── GetModelList.srv │ │ ├── GetModelMesh.srv │ │ ├── GetModelScans.srv │ │ ├── SaveScan.srv │ │ └── TranslateRecognitionId.srv │ ├── manipulation_msgs │ ├── .travis.yml │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── action │ │ └── GraspPlanning.action │ ├── msg │ │ ├── CartesianGains.msg │ │ ├── ClusterBoundingBox.msg │ │ ├── Grasp.msg │ │ ├── GraspPlanningErrorCode.msg │ │ ├── GraspResult.msg │ │ ├── GraspableObject.msg │ │ ├── GraspableObjectList.msg │ │ ├── GripperTranslation.msg │ │ ├── ManipulationPhase.msg │ │ ├── ManipulationResult.msg │ │ ├── PlaceLocation.msg │ │ ├── PlaceLocationResult.msg │ │ └── SceneRegion.msg │ ├── package.xml │ └── srv │ │ └── GraspPlanning.srv │ └── roboticsgroup_gazebo_plugins │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── LICENSE │ ├── 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 └── image.png /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/README.md -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/CMakeLists.txt -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/README.md -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/CMakeLists.txt -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/cfg/view_robot.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/cfg/view_robot.rviz -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/launch/ur5_upload.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/launch/ur5_upload.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/launch/ur5_upload_robotiq85_gripper.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/launch/ur5_upload_robotiq85_gripper.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/launch/view_ur5.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/launch/view_ur5.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/launch/view_ur5_robotiq85_gripper.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/launch/view_ur5_robotiq85_gripper.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/collision/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/collision/base.stl -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/collision/forearm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/collision/forearm.stl -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/collision/shoulder.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/collision/shoulder.stl -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/collision/upperarm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/collision/upperarm.stl -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/collision/wrist1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/collision/wrist1.stl -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/collision/wrist2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/collision/wrist2.stl -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/collision/wrist3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/collision/wrist3.stl -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/visual/base.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/visual/base.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/visual/forearm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/visual/forearm.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/visual/shoulder.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/visual/shoulder.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/visual/upperarm.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/visual/upperarm.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/visual/wrist1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/visual/wrist1.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/visual/wrist2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/visual/wrist2.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/visual/wrist3.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/meshes/ur5/visual/wrist3.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/package.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/1common.gazebo.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/1common.gazebo.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/common.gazebo.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/common.gazebo.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/ur.gazebo.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/ur.gazebo.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/ur.transmission.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/ur.transmission.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/ur5.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/ur5.urdf.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/ur5_joint_limited_robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/ur5_joint_limited_robot.urdf.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/ur5_robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/ur5_robot.urdf.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/ur5_robot_robotiq85_gripper.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/ur5_robot_robotiq85_gripper.urdf.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/vaccum_gripper.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_description/urdf/vaccum_gripper.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/CMakeLists.txt -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/controller/arm_controller_ur5.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/controller/arm_controller_ur5.yaml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/controller/joint_state_controller.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/controller/joint_state_controller.yaml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/launch/controller_utils.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/launch/controller_utils.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/launch/model_test.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/launch/model_test.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/launch/ur5.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/launch/ur5.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/launch/ur5_joint_limited.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/launch/ur5_joint_limited.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/package.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/CHANGELOG.rst -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/CMakeLists.txt -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/README.md -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/include/roboticsgroup_gazebo_plugins/disable_link_plugin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/include/roboticsgroup_gazebo_plugins/disable_link_plugin.h -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/include/roboticsgroup_gazebo_plugins/mimic_joint_plugin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/include/roboticsgroup_gazebo_plugins/mimic_joint_plugin.h -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/package.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/src/disable_link_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/src/disable_link_plugin.cpp -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/src/mimic_joint_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/src/roboticsgroup_gazebo_plugins/src/mimic_joint_plugin.cpp -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/tests/roslaunch_test.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/tests/roslaunch_test.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/add_beer.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/add_beer.sdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/banana.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/banana.urdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/beer/materials/scripts/beer.material: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/beer/materials/scripts/beer.material -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/beer/materials/textures/beer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/beer/materials/textures/beer.png -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/beer/model-1_4.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/beer/model-1_4.sdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/beer/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/beer/model.config -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/beer/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/beer/model.sdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/block.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/block.urdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/cafe_table/materials/textures/Maple.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/cafe_table/materials/textures/Maple.jpg -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/cafe_table/materials/textures/Wood_Floor_Dark.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/cafe_table/materials/textures/Wood_Floor_Dark.jpg -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/cafe_table/meshes/cafe_table.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/cafe_table/meshes/cafe_table.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/cafe_table/model-1_4.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/cafe_table/model-1_4.sdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/cafe_table/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/cafe_table/model.config -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/cafe_table/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/cafe_table/model.sdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/coke_can/materials/textures/coke_can.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/coke_can/materials/textures/coke_can.png -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/coke_can/meshes/coke_can.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/coke_can/meshes/coke_can.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/coke_can/model-1_2.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/coke_can/model-1_2.sdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/coke_can/model-1_3.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/coke_can/model-1_3.sdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/coke_can/model-1_4.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/coke_can/model-1_4.sdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/coke_can/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/coke_can/model.config -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/coke_can/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/coke_can/model.sdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/cylinder.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/cylinder.urdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/dropbox.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/dropbox.urdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/long_block.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/long_block.urdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/meshes/banana.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/meshes/banana.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/meshes/dropbox.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/meshes/dropbox.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/materials/scripts/table_lightmap.material: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/materials/scripts/table_lightmap.material -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/materials/textures/marble.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/materials/textures/marble.png -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/materials/textures/marble_black.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/materials/textures/marble_black.png -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/materials/textures/table_lightmap.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/materials/textures/table_lightmap.png -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/materials/textures/table_lightmap_black.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/materials/textures/table_lightmap_black.png -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/meshes/table_lightmap.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/meshes/table_lightmap.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/model-1_4.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/model-1_4.sdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/model.config -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/table_marble/model.sdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/test.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/gjt_ur/gjt_ur_gazebo/urdf/test.urdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/LICENSE -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/README.md -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_bringup/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_bringup/CMakeLists.txt -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_bringup/launch/robotiq_85.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_bringup/launch/robotiq_85.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_bringup/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_bringup/package.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_bringup/rviz/robotiq_85.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_bringup/rviz/robotiq_85.rviz -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/CMakeLists.txt -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/launch/display.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/launch/display.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/launch/upload_robotiq_85_gripper.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/launch/upload_robotiq_85_gripper.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/collision/kinova_robotiq_coupler.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/collision/kinova_robotiq_coupler.stl -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/collision/robotiq_85_base_link.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/collision/robotiq_85_base_link.stl -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/collision/robotiq_85_finger_link.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/collision/robotiq_85_finger_link.stl -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/collision/robotiq_85_finger_tip_link.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/collision/robotiq_85_finger_tip_link.stl -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/collision/robotiq_85_inner_knuckle_link.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/collision/robotiq_85_inner_knuckle_link.stl -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/collision/robotiq_85_knuckle_link.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/collision/robotiq_85_knuckle_link.stl -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/visual/kinova_robotiq_coupler.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/visual/kinova_robotiq_coupler.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/visual/robotiq_85_base_link.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/visual/robotiq_85_base_link.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/visual/robotiq_85_finger_link.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/visual/robotiq_85_finger_link.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/visual/robotiq_85_finger_tip_link.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/visual/robotiq_85_finger_tip_link.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/visual/robotiq_85_inner_knuckle_link.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/visual/robotiq_85_inner_knuckle_link.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/visual/robotiq_85_knuckle_link.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/meshes/visual/robotiq_85_knuckle_link.dae -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/package.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/urdf.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/urdf.rviz -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/urdf/kinova_robotiq_85_gripper.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/urdf/kinova_robotiq_85_gripper.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/urdf/robotiq_85_gripper.transmission.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/urdf/robotiq_85_gripper.transmission.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/urdf/robotiq_85_gripper.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/urdf/robotiq_85_gripper.urdf.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/urdf/robotiq_85_gripper.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/urdf/robotiq_85_gripper.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/urdf/robotiq_85_gripper_sim_base.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/urdf/robotiq_85_gripper_sim_base.urdf.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/urdf/robotiq_85_kinova_coupler.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_description/urdf/robotiq_85_kinova_coupler.urdf.xacro -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/CMakeLists.txt -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/bin/robotiq_85_driver: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/bin/robotiq_85_driver -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/bin/robotiq_85_test: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/bin/robotiq_85_test -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/package.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/setup.py -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/src/robotiq_85/__init__.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/src/robotiq_85/gripper_io.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/src/robotiq_85/gripper_io.py -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/src/robotiq_85/modbus_crc.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/src/robotiq_85/modbus_crc.py -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/src/robotiq_85/robotiq_85_driver.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/src/robotiq_85/robotiq_85_driver.py -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/src/robotiq_85/robotiq_85_gripper.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/src/robotiq_85/robotiq_85_gripper.py -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/src/robotiq_85/robotiq_85_gripper_test.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_driver/src/robotiq_85/robotiq_85_gripper_test.py -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_gripper/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_gripper/CMakeLists.txt -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_gripper/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_gripper/package.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/.setup_assistant -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/CMakeLists.txt -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/config/controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/config/controllers.yaml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/config/fake_controllers.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/config/fake_controllers.yaml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/config/joint_limits.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/config/joint_limits.yaml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- 1 | {} -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/config/ompl_planning.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/config/ompl_planning.yaml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/config/robotiq_85_gripper.srdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/config/robotiq_85_gripper.srdf -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/default_warehouse_db.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/demo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/demo.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/fake_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/fake_moveit_controller_manager.launch.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/joystick_control.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/joystick_control.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/move_group.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/move_group.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/moveit.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/moveit.rviz -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/moveit_rviz.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/ompl_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/ompl_planning_pipeline.launch.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/planning_context.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/planning_context.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/planning_pipeline.launch.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/robotiq_85_gripper_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/robotiq_85_gripper_moveit_controller_manager.launch.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/robotiq_85_gripper_moveit_sensor_manager.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/robotiq_85_gripper_moveit_sensor_manager.launch.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/robotiq_85_moveit_planning_execution.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/robotiq_85_moveit_planning_execution.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/run_benchmark_ompl.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/sensor_manager.launch.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/setup_assistant.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/trajectory_execution.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/trajectory_execution.launch.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/warehouse.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/launch/warehouse_settings.launch.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_moveit_config/package.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_msgs/msg/GripperCmd.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_msgs/msg/GripperCmd.msg -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_msgs/msg/GripperStat.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_msgs/msg/GripperStat.msg -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_msgs/package.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/CMakeLists.txt -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/controller/gripper_controller_robotiq.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/controller/gripper_controller_robotiq.yaml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/controller/joint_state_controller.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/controller/joint_state_controller.yaml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/launch/controller_utils.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/launch/controller_utils.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/launch/robotiq_85.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/launch/robotiq_85.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/launch/robotiq_85_moveit_rviz_test.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/launch/robotiq_85_moveit_rviz_test.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/launch/robotiq_85_moveit_sim.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/launch/robotiq_85_moveit_sim.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/launch/test_kinematics.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/launch/test_kinematics.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/package.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/scripts/robotiq_85_moveit_test.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_gazebo/scripts/robotiq_85_moveit_test.py -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_simulation/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_simulation/CMakeLists.txt -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_simulation/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/robotiq_85_simulation/robotiq_85_simulation/package.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/si_utils/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/si_utils/CMakeLists.txt -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/si_utils/launch/test.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/si_utils/launch/test.launch -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/si_utils/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/si_utils/package.xml -------------------------------------------------------------------------------- /UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/si_utils/scripts/timed_roslaunch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/UR5-robotiq85_gripper-gazebo/robotiq_85_gripper/si_utils/scripts/timed_roslaunch -------------------------------------------------------------------------------- /gazebo-pkgs/Dockerfile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/Dockerfile -------------------------------------------------------------------------------- /gazebo-pkgs/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/LICENSE -------------------------------------------------------------------------------- /gazebo-pkgs/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/README.md -------------------------------------------------------------------------------- /gazebo-pkgs/TODO.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/TODO.md -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_grasp_plugin_ros/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_grasp_plugin_ros/CMakeLists.txt -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_grasp_plugin_ros/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_grasp_plugin_ros/README.md -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_grasp_plugin_ros/msg/GazeboGraspEvent.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_grasp_plugin_ros/msg/GazeboGraspEvent.msg -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_grasp_plugin_ros/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_grasp_plugin_ros/package.xml -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_grasp_plugin_ros/src/grasp_event_republisher.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_grasp_plugin_ros/src/grasp_event_republisher.cpp -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_state_plugins/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_state_plugins/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_state_plugins/CMakeLists.txt -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_state_plugins/config/GazeboMapPublisher.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_state_plugins/config/GazeboMapPublisher.yaml -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_state_plugins/config/GazeboObjectInfo.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_state_plugins/config/GazeboObjectInfo.yaml -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_state_plugins/config/WorldPlugins.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_state_plugins/config/WorldPlugins.yaml -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_state_plugins/include/gazebo_state_plugins/GazeboMapPublisher.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_state_plugins/include/gazebo_state_plugins/GazeboMapPublisher.h -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_state_plugins/include/gazebo_state_plugins/GazeboObjectInfo.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_state_plugins/include/gazebo_state_plugins/GazeboObjectInfo.h -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_state_plugins/launch/plugin_loader.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_state_plugins/launch/plugin_loader.launch -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_state_plugins/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_state_plugins/package.xml -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_state_plugins/src/GazeboMapPublisher.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_state_plugins/src/GazeboMapPublisher.cpp -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_state_plugins/src/GazeboObjectInfo.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_state_plugins/src/GazeboObjectInfo.cpp -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_state_plugins/test/object_info_request.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_state_plugins/test/object_info_request.cpp -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/CHANGELOG.rst -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/CMakeLists.txt -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/config/FakeObjectRecognizer.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/config/FakeObjectRecognizer.yaml -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/config/ObjectTFBroadcaster.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/config/ObjectTFBroadcaster.yaml -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/include/gazebo_test_tools/FakeObjectRecognizer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/include/gazebo_test_tools/FakeObjectRecognizer.h -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/include/gazebo_test_tools/gazebo_cube_spawner.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/include/gazebo_test_tools/gazebo_cube_spawner.h -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/launch/fake_object_recognizer.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/launch/fake_object_recognizer.launch -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/launch/gazebo_fake_object_recognition.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/launch/gazebo_fake_object_recognition.launch -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/launch/object_tf_broadcaster.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/launch/object_tf_broadcaster.launch -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/launch/spawn_and_recognize_cube.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/launch/spawn_and_recognize_cube.launch -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/package.xml -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/src/FakeObjectRecognizer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/src/FakeObjectRecognizer.cpp -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/src/SetGazeboPhysicsClient.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/src/SetGazeboPhysicsClient.cpp -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/src/cube_spawner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/src/cube_spawner.cpp -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/src/cube_spawner_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/src/cube_spawner_node.cpp -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/src/fake_object_recognizer_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/src/fake_object_recognizer_node.cpp -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/srv/RecognizeGazeboObject.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/srv/RecognizeGazeboObject.srv -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_test_tools/test/fake_object_recognizer_cmd.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_test_tools/test/fake_object_recognizer_cmd.cpp -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_world_plugin_loader/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_world_plugin_loader/CHANGELOG.rst -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_world_plugin_loader/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_world_plugin_loader/CMakeLists.txt -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_world_plugin_loader/config/WorldPluginsTemplate.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_world_plugin_loader/config/WorldPluginsTemplate.config -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_world_plugin_loader/include/gazebo_world_plugin_loader/GazeboPluginLoader.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_world_plugin_loader/include/gazebo_world_plugin_loader/GazeboPluginLoader.h -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_world_plugin_loader/launch/plugin_loader_template.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_world_plugin_loader/launch/plugin_loader_template.launch -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_world_plugin_loader/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_world_plugin_loader/package.xml -------------------------------------------------------------------------------- /gazebo-pkgs/gazebo_world_plugin_loader/src/GazeboPluginLoader.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gazebo-pkgs/gazebo_world_plugin_loader/src/GazeboPluginLoader.cpp -------------------------------------------------------------------------------- /general-message-pkgs/Dockerfile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/Dockerfile -------------------------------------------------------------------------------- /general-message-pkgs/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/LICENSE -------------------------------------------------------------------------------- /general-message-pkgs/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/README.md -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs/msg/Object.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs/msg/Object.msg -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs/msg/ObjectPose.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs/msg/ObjectPose.msg -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs/package.xml -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs/srv/ObjectInfo.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs/srv/ObjectInfo.srv -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs/srv/RegisterObject.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs/srv/RegisterObject.srv -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs_tools/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs_tools/CHANGELOG.rst -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs_tools/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs_tools/CMakeLists.txt -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs_tools/config/ObjectTFBroadcaster.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs_tools/config/ObjectTFBroadcaster.yaml -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs_tools/include/object_msgs_tools/ObjectFunctions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs_tools/include/object_msgs_tools/ObjectFunctions.h -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs_tools/include/object_msgs_tools/ObjectTFBroadcaster.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs_tools/include/object_msgs_tools/ObjectTFBroadcaster.h -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs_tools/launch/object_tf_broadcaster.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs_tools/launch/object_tf_broadcaster.launch -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs_tools/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs_tools/package.xml -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs_tools/src/ObjectFunctions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs_tools/src/ObjectFunctions.cpp -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs_tools/src/ObjectTFBroadcaster.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs_tools/src/ObjectTFBroadcaster.cpp -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs_tools/src/object_tf_broadcaster_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs_tools/src/object_tf_broadcaster_node.cpp -------------------------------------------------------------------------------- /general-message-pkgs/object_msgs_tools/src/register_object_client.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/object_msgs_tools/src/register_object_client.cpp -------------------------------------------------------------------------------- /general-message-pkgs/path_navigation_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/path_navigation_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /general-message-pkgs/path_navigation_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/path_navigation_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /general-message-pkgs/path_navigation_msgs/action/PathExecution.action: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/path_navigation_msgs/action/PathExecution.action -------------------------------------------------------------------------------- /general-message-pkgs/path_navigation_msgs/action/TransformPathExecution.action: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/path_navigation_msgs/action/TransformPathExecution.action -------------------------------------------------------------------------------- /general-message-pkgs/path_navigation_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/general-message-pkgs/path_navigation_msgs/package.xml -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/README.md -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/CHANGELOG.rst -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/CMakeLists.txt -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/include/gazebo_grasp_plugin/GazeboGraspFix.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/include/gazebo_grasp_plugin/GazeboGraspFix.h -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/include/gazebo_grasp_plugin/GazeboGraspGripper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/include/gazebo_grasp_plugin/GazeboGraspGripper.h -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/msgs/CMakeLists.txt -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/msgs/grasp_event.proto: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/msgs/grasp_event.proto -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/package.xml -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/src/GazeboGraspFix.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/src/GazeboGraspFix.cpp -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/src/GazeboGraspGripper.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/gazebo_grasp_plugin/src/GazeboGraspGripper.cpp -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/gazebo_version_helpers/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/gazebo_version_helpers/CMakeLists.txt -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/gazebo_version_helpers/include/gazebo_version_helpers/GazeboVersionHelpers.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/gazebo_version_helpers/include/gazebo_version_helpers/GazeboVersionHelpers.h -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/gazebo_version_helpers/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/gazebo_version_helpers/package.xml -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/gazebo_version_helpers/src/GazeboVersionHelpers.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/gazebo_version_helpers/src/GazeboVersionHelpers.cpp -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/.travis.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/.travis.yml -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/msg/DatabaseModelPose.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/msg/DatabaseModelPose.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/msg/DatabaseModelPoseList.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/msg/DatabaseModelPoseList.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/msg/DatabaseReturnCode.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/msg/DatabaseReturnCode.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/msg/DatabaseScan.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/msg/DatabaseScan.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/package.xml -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/srv/GetModelDescription.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/srv/GetModelDescription.srv -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/srv/GetModelList.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/srv/GetModelList.srv -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/srv/GetModelMesh.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/srv/GetModelMesh.srv -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/srv/GetModelScans.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/srv/GetModelScans.srv -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/srv/SaveScan.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/srv/SaveScan.srv -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/srv/TranslateRecognitionId.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/household_objects_database_msgs/srv/TranslateRecognitionId.srv -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/.travis.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/.travis.yml -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/action/GraspPlanning.action: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/action/GraspPlanning.action -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/CartesianGains.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/CartesianGains.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/ClusterBoundingBox.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/ClusterBoundingBox.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/Grasp.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/Grasp.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/GraspPlanningErrorCode.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/GraspPlanningErrorCode.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/GraspResult.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/GraspResult.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/GraspableObject.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/GraspableObject.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/GraspableObjectList.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/GraspableObjectList.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/GripperTranslation.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/GripperTranslation.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/ManipulationPhase.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/ManipulationPhase.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/ManipulationResult.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/ManipulationResult.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/PlaceLocation.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/PlaceLocation.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/PlaceLocationResult.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/PlaceLocationResult.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/SceneRegion.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/msg/SceneRegion.msg -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/package.xml -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/srv/GraspPlanning.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/manipulation_msgs/srv/GraspPlanning.srv -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/CHANGELOG.rst -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/CMakeLists.txt -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/LICENSE -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/README.md -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/include/roboticsgroup_gazebo_plugins/disable_link_plugin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/include/roboticsgroup_gazebo_plugins/disable_link_plugin.h -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/include/roboticsgroup_gazebo_plugins/mimic_joint_plugin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/include/roboticsgroup_gazebo_plugins/mimic_joint_plugin.h -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/package.xml -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/src/disable_link_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/src/disable_link_plugin.cpp -------------------------------------------------------------------------------- /gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/src/mimic_joint_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/gripper_breakdown_solution-master/gazebo_plugins/roboticsgroup_gazebo_plugins/src/mimic_joint_plugin.cpp -------------------------------------------------------------------------------- /image.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Geo-JTao/UR5_gripper_camera_gazebo/HEAD/image.png --------------------------------------------------------------------------------