def main():
    parser = argparse.ArgumentParser()
    parser.add_argument(
        "--multi-process",
        action="store_true",
        help="""If set run only frontend with multi-process
                        robot data.  Otherwise run everything within a single
                        process.""",
    )
    args = parser.parse_args()

    if args.multi_process:
        # In multi-process case assume that the backend is running in a
        # separate process and only set up the frontend here.
        robot_data = robot_interfaces.solo_eight.MultiProcessData(
            "solo8", False
        )
        frontend = robot_interfaces.solo_eight.Frontend(robot_data)
    else:
        # In single-process case run both frontend and backend in this process
        # (using the `Robot` helper class).
        robot = robot_fingers.Robot(
            robot_interfaces.solo_eight,
            robot_fingers.create_solo_eight_backend,
            "soloeight.yml",
        )
        robot.initialize()
        frontend = robot.frontend

    # move around
    print("Running")
    run_choreography(frontend)
def main():
    parser = argparse.ArgumentParser()
    parser.add_argument("--multi-process",
                        action="store_true",
                        help="""If set run only frontend with multi-process
                        robot data.  Otherwise run everything within a single
                        process.""")
    parser.add_argument("--log", type=str)
    args = parser.parse_args()

    if args.multi_process:
        # In multi-process case assume that the backend is running in a
        # separate process and only set up the frontend here.
        robot_data = robot_interfaces.trifinger.MultiProcessData(
            "trifinger", False)
        frontend = robot_interfaces.trifinger.Frontend(robot_data)
    else:
        # In single-process case run both frontend and backend in this process
        # (using the `Robot` helper class).
        robot = robot_fingers.Robot(robot_interfaces.trifinger,
                                    robot_fingers.create_trifinger_backend,
                                    "trifingerpro.yml")
        if args.log:
            logger = robot_interfaces.trifinger.Logger(robot.robot_data, 100)
            logger.start(args.log)

        robot.initialize()
        frontend = robot.frontend

    # move around
    run_choreography(frontend)
Пример #3
0
    def __init__(self, env):
        """
        This wrapper makes the environment to execute actions on the real robot
        instead, to be used when performing sim2real experiments.

        :param env: (causal_world.CausalWorld) the environment to convert.
        """
        self._env = env
        self._real_robot = robot_fingers.Robot(
            robot_interfaces.trifinger, robot_fingers.create_trifinger_backend,
            "trifinger.yml")
        self._real_robot.initialize()
        self._frontend = self._real_robot.frontend
        self._repetitions = 1000.0 / (self._env._simulation_time /
                                      self._env._skip_frame)
Пример #4
0
def main():
    robot_type = {
        "fingerone": (
            robot_interfaces.finger,
            robot_fingers.create_real_finger_backend,
            "finger.yml",
        ),
        "trifingerone": (
            robot_interfaces.trifinger,
            robot_fingers.create_trifinger_backend,
            "trifinger.yml",
        ),
        "fingeredu": (
            robot_interfaces.finger,
            robot_fingers.create_real_finger_backend,
            "fingeredu.yml",
        ),
        "trifingeredu": (
            robot_interfaces.trifinger,
            robot_fingers.create_trifinger_backend,
            "trifingeredu.yml",
        ),
        "trifingerpro": (
            robot_interfaces.trifinger,
            robot_fingers.create_trifinger_backend,
            "trifingerpro.yml",
        ),
    }

    parser = argparse.ArgumentParser(description=__doc__)
    parser.add_argument("robot_type", choices=robot_type.keys())
    args = parser.parse_args()

    robot = robot_fingers.Robot(*robot_type[args.robot_type])

    print("")
    print("")
    input("Manually move robot to zero position.  Then press Enter.")
    robot.initialize()

    print("")
    print("Finished. The 'Offset' corresponds to the home offset.")
Пример #5
0
def main():
    config_file = get_robot_config(position_limits=False)

    # robot = robot_fingers.Robot.create_by_name("trifingerpro")
    robot = robot_fingers.Robot(
        robot_interfaces.trifinger,
        robot_fingers.create_trifinger_backend,
        config_file,
    )
    robot.initialize()

    print("End stop test")
    end_stop_check(robot)
    print("Position reachability test")
    run_self_test(robot)
    print("Reset cube position")
    reset_object(robot)

    # terminate the robot
    del robot

    print("Check if cube is found")
    check_if_cube_is_there()
Пример #6
0
from ament_index_python.packages import get_package_share_directory
import pinocchio
import robot_interfaces
import robot_fingers

if __name__ == "__main__":
    urdf_pkg_path = get_package_share_directory("robot_properties_manipulator")
    urdf_path = os.path.join(urdf_pkg_path, "urdf", "finger.urdf")

    model = pinocchio.buildModelFromUrdf(urdf_path)
    data = model.createData()
    tip_link_id = model.getFrameId("finger_tip_link")

    robot = robot_fingers.Robot(
        robot_interfaces.finger,
        robot_fingers.create_real_finger_backend,
        "finger.yml",
    )
    robot.initialize()

    action = robot.Action()
    while True:
        t = robot.frontend.append_desired_action(action)
        joint_positions = robot.frontend.get_observation(t).position

        # compute the forward kinematics
        pinocchio.framesForwardKinematics(model, data, joint_positions)

        # get the position of the tip link
        pos = data.oMf[tip_link_id].translation