]> defiant.homedns.org Git - arm_ros_conn.git/commitdiff
using rosbridge instead of own json server
authorErik Andresen <erik@vontaene.de>
Fri, 20 Feb 2015 23:30:47 +0000 (00:30 +0100)
committerErik Andresen <erik@vontaene.de>
Fri, 20 Feb 2015 23:30:47 +0000 (00:30 +0100)
arm.launch
move_base.launch
scripts/arm_ros_conn.py
scripts/pyshared [deleted submodule]

index 9cdfe9b1a9f2c19a0354585495abcf00cff02600..877df4c4edd1d55b05412461ec543c4398b67b03 100644 (file)
@@ -1,5 +1,7 @@
 <?xml version="1.0"?>
 <launch>
+       <include file="$(find rosbridge_server)/launch/rosbridge_websocket.launch" /> 
+
        <include file="$(find openni2_launch)/launch/openni2.launch">
                <arg name="rgb_processing" value="false" />
                <arg name="debayer_processing" value="false" />
index cd1ef67c6869446f9ce8426a283926688ab2b214..1ef9f37d577c83875ad00aa42ac785a9fc2cbd5b 100644 (file)
@@ -1,7 +1,5 @@
 <?xml version="1.0"?>
 <launch>
-       <node pkg="arm" type="arm_ros_conn.py" name="arm_ros_conn" output="screen" />
-
        <!-- Run the map server -->
        <node name="map_server" pkg="map_server" type="map_server" args="$(find arm)/config/map.png 0.01" />
 
index 67561b3b8dfb13111e329c91ea22400dc583e231..9bfe92da845ef12b097d61918c1f443b2e661ea5 100755 (executable)
@@ -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 (submodule)
index d73e753..0000000
+++ /dev/null
@@ -1 +0,0 @@
-Subproject commit d73e753a4c2c8a9bb79ada177d1cb122a08cabeb