X-Git-Url: https://defiant.homedns.org/gitweb/?a=blobdiff_plain;f=scripts%2Farm_ros_conn.py;h=c4ab470bf71d21b4f110f36adba824f1b3db4fca;hb=edabbb4c0b2db743965845d5b82b755af4d7a4dc;hp=29462c89c5a86010e5b6bb2e9d1849c85167db42;hpb=15d0cdc058609e614c21cefef358829b46a77155;p=arm_ros_conn.git diff --git a/scripts/arm_ros_conn.py b/scripts/arm_ros_conn.py index 29462c8..c4ab470 100755 --- a/scripts/arm_ros_conn.py +++ b/scripts/arm_ros_conn.py @@ -2,83 +2,36 @@ # -*- coding: iso-8859-15 -*- import rospy -import tf -import prctl -#import cProfile -import threading -from json_client import JsonClient -from geometry_msgs.msg import Twist -from nav_msgs.msg import Odometry +import arm +from sensor_msgs.msg import JointState class ARMRosConn(): def __init__(self): rospy.init_node('arm') - prctl.set_name("arm_ros_bridge") - self.__lock_cmd = threading.Lock() - self.pComm = JsonClient(("arm", 10002)) - rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived) - self.sub_scan = None - self.motion_enabled_last = None - self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16) - self.tf_broadcaster = tf.broadcaster.TransformBroadcaster() + arm.switch(0) + arm.switch(2) + arm.set_hall_mode(3, 0) + arm.set_hall_mode(5, 0) + arm.set_tolerance(3, 0) + arm.set_tolerance(5, 0) + self.pub_joint_states = rospy.Publisher("joint_states", JointState, queue_size=16) self.run() - def command(self, cmd): - with self.__lock_cmd: - return self.pComm.write(cmd) - def run(self): - rate = rospy.Rate(10.0) - #pr = cProfile.Profile() - #pr.enable() + rate = rospy.Rate(20) while not rospy.is_shutdown(): - self.send_odometry() - + self.publish_joint_states() rate.sleep() - #pr.disable() - #pr.dump_stats("/tmp/test.stats") - - def send_odometry(self): - current_time = rospy.Time.now() - lPos, fAngle, lSpeed = self.command("get engine pose") - - # since all odometry is 6DOF we'll need a quaternion created from yaw - odom_quat = tf.transformations.quaternion_from_euler(0, 0, fAngle) - - # first, we'll publish the transform over tf - self.tf_broadcaster.sendTransform((lPos[0], lPos[1], 0.0), odom_quat, current_time, "base_link", "odom") - - # next, we'll publish the odometry message over ROS - odom = Odometry() - odom.header.stamp = current_time - odom.header.frame_id = "/odom" - - # set the position - odom.pose.pose.position.x = lPos[0] - odom.pose.pose.position.y = lPos[1] - odom.pose.pose.position.z = 0.0 - odom.pose.pose.orientation.x = odom_quat[0] - odom.pose.pose.orientation.y = odom_quat[1] - odom.pose.pose.orientation.z = odom_quat[2] - odom.pose.pose.orientation.w = odom_quat[3] - - # set the velocity - odom.child_frame_id = "base_link" - odom.twist.twist.linear.x = lSpeed[0] - odom.twist.twist.linear.y = 0.0 - odom.twist.twist.angular.z = lSpeed[1] - - # publish the message - self.pub_odom.publish(odom) - - # test with rostopic pub -1 cmd_vel geometry_msgs/Twist '[0, 0, 0]' '[0, 0, 0]' - def cmdVelReceived(self, msg): - trans = msg.linear.x - rot = msg.angular.z + + def publish_joint_states(self): + joint_state = JointState() + joint_state.header.stamp = rospy.Time.now() + joint_state.name = ["base_to_link1", "link_1_2_joint", "link_2_3_joint", "gripper_joint_1", "gripper_joint_2", "left_gripper_joint", "right_gripper_joint"] + joint_state.position = [arm.get_angle(0), arm.get_angle(1), arm.get_angle(2), arm.get_angle(3), arm.get_angle(4), arm.get_angle(5)/2, arm.get_angle(5)/2] + self.pub_joint_states.publish(joint_state) - self.command("set engine speed %f %f" % (trans, rot)) if __name__ == '__main__': ARMRosConn()