def Robot(client=None, load_geometry=False): """Returns a UR5 robot. This method serves mainly as help for writing examples, so that the code can stay short. It is intentionally capitalized to act as an almost drop-in replacement for the constructor of :class:`compas_fab.robots.Robot`. Parameters ---------- client: object Backend client. load_geometry: bool Returns ------- :class:`compas_fab.robots.Robot` Newly created instance of a UR5 robot. Examples -------- >>> from compas_fab.robots.ur5 import Robot >>> robot = Robot() >>> robot.name 'ur5' """ urdf_filename = compas_fab.get( 'universal_robot/ur_description/urdf/ur5.urdf') srdf_filename = compas_fab.get( 'universal_robot/ur5_moveit_config/config/ur5.srdf') model = RobotModel.from_urdf_file(urdf_filename) semantics = RobotSemantics.from_srdf_file(srdf_filename, model) if load_geometry: loader = LocalPackageMeshLoader(compas_fab.get('universal_robot'), 'ur_description') model.load_geometry(loader) robot = RobotClass(model, semantics=semantics) if client: robot.client = client return robot
import os from compas.geometry import Frame from compas.robots import LocalPackageMeshLoader from compas.robots import RobotModel from compas_fab.robots import Configuration from ur_kinematics import inverse_kinematics_ur5 models_path = os.path.join(os.path.dirname(__file__), 'models') loader = LocalPackageMeshLoader(models_path, 'ur_description') model = RobotModel.from_urdf_file(loader.load_urdf('ur5.urdf')) f = Frame((0.417, 0.191, -0.005), (-0.000, 1.000, 0.000), (1.000, 0.000, 0.000)) f.point /= 0.001 sols = inverse_kinematics_ur5(f) for joint_values in sols: joint_names = model.get_configurable_joint_names() print(Configuration.from_revolute_values(joint_values, joint_names))
model.load_geometry(github) # print(model) artist = RobotModelArtist(model, layer=robot) # artist.scale(1000) # artist.draw_visual() # getallrobots(UR_packages, UR_robots) fanuc_package = ['ros-industrial/fanuc', 'fanuc_m16ib_support', 'kinetic-devel'] fanuc_robots = [ 'm16ib20' ] # getallrobots(fanuc_package,fanuc_robots,'.xacro') abb_package = ['ros-industrial/abb', 'abb_irb6600_support', 'kinetic-devel'] abb_robots = [ 'irb6640' ] # getallrobots(abb_package, abb_robots, '.urdf') # github = GithubPackageMeshLoader('ros-industrial/universal_robot', 'ur_description', 'kinetic-devel') package_path = 'universal_robot' model = RobotModel.from_urdf_file('universal_robot\ur_description\urdf\ur10_robot.urdf') loader = LocalPackageMeshLoader(package_path, 'ur_description') model.load_geometry(loader) artist = RobotModelArtist(model, layer='COMPAS FAB::Example2') artist.draw_visual() artist.draw_collision()
import time from compas.datastructures import Mesh from compas.robots import LocalPackageMeshLoader import compas_fab from compas_fab.backends.pybullet import PyBulletClient from compas_fab.robots import AttachedCollisionMesh from compas_fab.robots import CollisionMesh with PyBulletClient() as client: urdf_filepath = compas_fab.get( 'universal_robot/ur_description/urdf/ur5.urdf') loader = LocalPackageMeshLoader(compas_fab.get('universal_robot'), 'ur_description') robot = client.load_robot(urdf_filepath, [loader]) mesh = Mesh.from_stl(compas_fab.get('planning_scene/cone.stl')) cm = CollisionMesh(mesh, 'tip') acm = AttachedCollisionMesh(cm, 'ee_link') client.add_attached_collision_mesh(acm, {'mass': 0.5, 'robot': robot}) time.sleep(1) client.step_simulation() time.sleep(1) client.remove_attached_collision_mesh('tip', {'robot': robot}) time.sleep(1)
""" Creates a robot model of a UR5 robot from a URDF file. """ import os from compas.robots import RobotModel from compas.robots import LocalPackageMeshLoader from compas_fab.robots import Robot HERE = os.path.dirname(__file__) DATA = os.path.join(HERE, '../data') PATH = os.path.join(DATA, 'robot_description') package = 'ur_description' urdf_filename = os.path.join(PATH, package, "urdf", "ur5.urdf") model = RobotModel.from_urdf_file(urdf_filename) # Load external geometry files (i.e. meshes) loader = LocalPackageMeshLoader(PATH, package) model.load_geometry(loader) print(model)
DATA = os.path.join(HERE, '../data') PATH = os.path.join(DATA, 'robot_description') #package = 'ur_description' package = 'ur_setups' urdf_filename = os.path.join(PATH, package, "urdf", "ur10_with_measurement_tool.urdf") srdf_filename = os.path.join(PATH, package, "ur10_with_measurement_tool.srdf") #package = "abb_linear_axis" #urdf_filename = os.path.join(PATH, package, "urdf", "abb_linear_axis_brick_suction_tool.urdf") #srdf_filename = os.path.join(PATH, package, "abb_linear_axis_suction_tool.srdf") model = RobotModel.from_urdf_file(urdf_filename) loaders = [] loaders.append(LocalPackageMeshLoader(PATH, "ur_description")) loaders.append(LocalPackageMeshLoader(PATH, "ur_end_effectors")) #loaders.append(LocalPackageMeshLoader(PATH, "abb_linear_axis")) #loaders.append(LocalPackageMeshLoader(PATH, "abb_irb4600_40_255")) #loaders.append(LocalPackageMeshLoader(PATH, "abb_end_effectors")) model.load_geometry(*loaders) artist = None # artist = RobotArtist(model) semantics = RobotSemantics.from_srdf_file(srdf_filename, model) robot = Robot(model, artist, semantics, client=None) robot.info()
from compas_rhino.artists import RobotModelArtist from compas.robots import LocalPackageMeshLoader from compas.robots import RobotModel model = RobotModel.from_urdf_file('models/05_origins_meshes.urdf') loader = LocalPackageMeshLoader('models', 'basic') model.load_geometry(loader) artist = RobotModelArtist(model, layer='COMPAS::Robot Viz') artist.clear_layer() artist.draw_visual()