From: Erik Andresen Date: Sun, 18 Oct 2015 07:20:23 +0000 (+0200) Subject: new urdf for arm X-Git-Url: https://defiant.homedns.org/gitweb/?p=arm_ros_conn.git;a=commitdiff_plain;h=88aa19cc672e02cf19405a39691ef9f63b1acef5 new urdf for arm --- diff --git a/arm.launch b/arm.launch deleted file mode 100644 index 9e120c7..0000000 --- a/arm.launch +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/launch/arm.launch b/launch/arm.launch new file mode 100644 index 0000000..3be44ff --- /dev/null +++ b/launch/arm.launch @@ -0,0 +1,7 @@ + + + + + + + diff --git a/scripts/arm_ros_conn.py b/scripts/arm_ros_conn.py index ff06cdf..9ca59f2 100755 --- a/scripts/arm_ros_conn.py +++ b/scripts/arm_ros_conn.py @@ -2,24 +2,15 @@ # -*- coding: iso-8859-15 -*- import rospy -import tf -from nav_msgs.msg import Odometry class ARMRosConn(): def __init__(self): rospy.init_node('arm') - rospy.Subscriber("odom", Odometry, self.odom_received) - self.tf_broadcaster = tf.broadcaster.TransformBroadcaster() - rate = rospy.Rate(10) while not rospy.is_shutdown(): rate.sleep() - 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, rospy.Time.now(), "base_link", "odom") if __name__ == '__main__': ARMRosConn() diff --git a/urdf/arm.urdf b/urdf/arm.urdf new file mode 100644 index 0000000..24587c0 --- /dev/null +++ b/urdf/arm.urdf @@ -0,0 +1,135 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +