diff --git a/spider_control/control.py b/spider_control/control.py index e842377d45917f88db3caeb168440d09719b6eae..fe18034ecf77d65f1d0d314da6e329f7f170d391 100644 --- a/spider_control/control.py +++ b/spider_control/control.py @@ -1,4 +1,4 @@ -#!/usr/bin/venv python +#!/usr/bin/env python import tensorflow as tf import numpy as np import roslib @@ -7,7 +7,7 @@ roslib.load_manifest('spider_control') import pylab as plt import math import threading -from geometry_msgs.msgs import Pose, Point +from geometry_msgs.msgs import * import rospy, yaml, sys from osrf_msgs.msg import JointCommands from sensor_msgs.msg import JointState @@ -111,7 +111,7 @@ def listener(): tactile_7 = tactile_sub[6] tactile_8 = tactile_sub[7] rospy.spin() - return (tactile_1, tactile_2, tactile_3, tactile_4, tactile_5, tactile_6, tactile_7, tactile_8) + return tactile_1, tactile_2, tactile_3, tactile_4, tactile_5, tactile_6, tactile_7, tactile_8 @@ -126,7 +126,7 @@ def call_return_joint_states(joint_names): for (ind, joint_name) in enumerate(joint_names): if(not resp.found[ind]): print"joint %s not found"%joint_name - return (resp.position, resp.velocity, resp.effort) + return resp.position, resp.velocity, resp.effort def talker(jointname , position): pub1 = rospy.Publisher('joint_states', JointState, queue_size = 10)