#!/usr/bin/env python # -*- coding: utf-8 -*- from __future__ import division __author__ = "Rodrigo Muñoz , David Valenzuela Urrutia" __email__ = "[email protected] , [email protected]" # ROS import rospy from kuka_driver.kuka_commander import KukaCommander if __name__ == "__main__": rospy.init_node("kuka_commander") kuka = KukaCommander() kuka.set_vel(80) kuka.home() rospy.sleep(0.5) kuka.ptp( [ 0.10772384992907114, 0.7154650789473394, -0.8016527609008506, -6.087224938771763e-06, 1.0266153515233172e-05, 6.821469104602556e-05, ] ) # OPEN DOOR rospy.sleep(0.5) kuka.ptp( [ 0.10770660596114645,
def main(): rospy.init_node('gripper_rutina') kuka = KukaCommander() kuka.set_vel(40) kuka.home() rate = rospy.Rate(1) # 1hz gripper= Gripper() gripper.start() NombreRutina=raw_input("Ingrese nombre de la rutina a seguir: ") rospy.loginfo(" Realizando Rutina: "+ NombreRutina) Rutina=open(NombreRutina + ".txt","r") for orden in Rutina: if orden[0:3]=="fin": rospy.loginfo("Fin de la Rutina") break if orden=="home": kuka.home() rospy.loginfo("kuka home") rospy.sleep(3.0) if orden[0:3]=="vel": kuka.set_vel(int(orden[3:6])) rospy.loginfo("Velocidad Kuka : " + orden[3:6]) rospy.sleep(1.0) if orden[0]=="#": pass if orden[0:4]=="open": gripper.open() rospy.loginfo("Gripper Open") if orden[0:5]=="close": gripper.close() rospy.loginfo("Gripper Close") if orden[0:5]=="sleep": rospy.loginfo("sleep:"+ str(orden[6:(len(orden))])) rospy.sleep(float(orden[6:(len(orden))])) if orden[0:3]=="ptp": punto=map(float,orden[4:len(orden)-2].split( ',')) kuka.ptp(punto) rospy.loginfo("kuka.ptp("+str(punto)+")") rospy.sleep(1.0) else: pass Rutina.close() gripper.shutdown()