]> defiant.homedns.org Git - arm_ros_conn.git/commitdiff
urdf cleanup
authorErik Andresen <erik@vontaene.de>
Fri, 20 Feb 2015 23:32:05 +0000 (00:32 +0100)
committerErik Andresen <erik@vontaene.de>
Fri, 20 Feb 2015 23:32:05 +0000 (00:32 +0100)
scripts/arm_ros_conn.py
urdf/arm.urdf.xacro

index 9bfe92da845ef12b097d61918c1f443b2e661ea5..ff06cdf8264a28c5c0f749162e01cbf0d91176ab 100755 (executable)
@@ -19,7 +19,7 @@ class ARMRosConn():
        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")
+               self.tf_broadcaster.sendTransform(pos, orientation, rospy.Time.now(), "base_link", "odom")
 
 if __name__ == '__main__':
        ARMRosConn()
index 8e7b3d5c414c5e5cdfbbbbc08ffda457761c4649..dd7b0f197fe80eefb85337a5929ab47a41928137 100644 (file)
                <origin xyz="0.195 0.0 0.165" rpy="0 0 0"/>
        </xacro:asus_camera>
 
-       <link name="scan">
-       </link>
-
-       <joint name="scan_joint" type="fixed">
-               <parent link="camera_depth_frame"/>
-               <child link="scan"/>
-               <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
-       </joint>
-
        <joint name="front_wheel_joint" type="fixed">
                <parent link="base_link"/>
                <child link="front_wheel"/>