From 24d33a5f1743b9eb2e9a309317edbc8e56eee226 Mon Sep 17 00:00:00 2001 From: Erik Andresen Date: Sat, 21 Feb 2015 00:30:47 +0100 Subject: [PATCH] using rosbridge instead of own json server --- arm.launch | 2 ++ move_base.launch | 2 -- scripts/arm_ros_conn.py | 71 ++++------------------------------------- scripts/pyshared | 1 - 4 files changed, 8 insertions(+), 68 deletions(-) delete mode 160000 scripts/pyshared diff --git a/arm.launch b/arm.launch index 9cdfe9b..877df4c 100644 --- a/arm.launch +++ b/arm.launch @@ -1,5 +1,7 @@ + + diff --git a/move_base.launch b/move_base.launch index cd1ef67..1ef9f37 100644 --- a/move_base.launch +++ b/move_base.launch @@ -1,7 +1,5 @@ - - diff --git a/scripts/arm_ros_conn.py b/scripts/arm_ros_conn.py index 67561b3..9bfe92d 100755 --- a/scripts/arm_ros_conn.py +++ b/scripts/arm_ros_conn.py @@ -3,82 +3,23 @@ import rospy import tf -import prctl -#import cProfile -import threading -from pyshared.json_client import JsonClient -from geometry_msgs.msg import Twist from nav_msgs.msg import Odometry 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) + rospy.Subscriber("odom", Odometry, self.odom_received) self.tf_broadcaster = tf.broadcaster.TransformBroadcaster() - 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(10) while not rospy.is_shutdown(): - self.send_odometry() - 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 - self.command("set engine speed %f %f" % (trans, rot)) + def odom_received(self, msg): + pos = (msg.pose.pose.position.x, msg.pose.pose.position.y, msg.pose.pose.position.z) + orientation = (msg.pose.pose.orientation.x, msg.pose.pose.orientation.y, msg.pose.pose.orientation.z, msg.pose.pose.orientation.w) + self.tf_broadcaster.sendTransform(pos, orientation, msg.header.stamp, "base_link", "odom") if __name__ == '__main__': ARMRosConn() diff --git a/scripts/pyshared b/scripts/pyshared deleted file mode 160000 index d73e753..0000000 --- a/scripts/pyshared +++ /dev/null @@ -1 +0,0 @@ -Subproject commit d73e753a4c2c8a9bb79ada177d1cb122a08cabeb -- 2.39.2