diff --git a/turtlebot_stdr/launch/turtlebot_in_stdr.launch b/turtlebot_stdr/launch/turtlebot_in_stdr.launch index cf045db..5f71112 100644 --- a/turtlebot_stdr/launch/turtlebot_in_stdr.launch +++ b/turtlebot_stdr/launch/turtlebot_in_stdr.launch @@ -1,10 +1,9 @@ @@ -12,7 +11,7 @@ - + @@ -52,6 +51,12 @@ + + + + + + @@ -85,5 +90,7 @@ + + diff --git a/turtlebot_stdr/nodes/tf_connector.py b/turtlebot_stdr/nodes/tf_connector.py index 5c6d10d..099fd71 100755 --- a/turtlebot_stdr/nodes/tf_connector.py +++ b/turtlebot_stdr/nodes/tf_connector.py @@ -8,19 +8,19 @@ class Remapper(object): def __init__(self): self.br = tf.TransformBroadcaster() + rospy.Subscriber("/tf", TFMessage, self.tf_remapper) def tf_remapper(self, msg): - a = 1 - if msg.transforms[0].header.frame_id == "/robot0": - self.br.sendTransform((0, 0, 0), - tf.transformations.quaternion_from_euler(0, 0, 0), - rospy.Time.now(), - "base_footprint", - "robot0") + if msg.transforms[0].header.frame_id == "/robot0": + self.br.sendTransform((0, 0, 0), + tf.transformations.quaternion_from_euler(0, 0, 0), + rospy.Time.now(), + "base_footprint", + "robot0") + if __name__ == '__main__': rospy.init_node('remapper_nav') remapper = Remapper() - rospy.Subscriber("/tf", TFMessage, remapper.tf_remapper) rospy.spin() diff --git a/turtlebot_stdr/robot/turtlebot.yaml b/turtlebot_stdr/robot/turtlebot.yaml index 2585360..5e81443 100644 --- a/turtlebot_stdr/robot/turtlebot.yaml +++ b/turtlebot_stdr/robot/turtlebot.yaml @@ -8,7 +8,7 @@ robot: - initial_pose: x: 2.0 y: 2.0 - theta: 0 + theta: 0.0 - laser: laser_specifications: max_angle: 0.5 diff --git a/turtlebot_stdr/rviz/robot_navigation.rviz b/turtlebot_stdr/rviz/robot_navigation.rviz index 9d1f680..ae1177b 100644 --- a/turtlebot_stdr/rviz/robot_navigation.rviz +++ b/turtlebot_stdr/rviz/robot_navigation.rviz @@ -288,64 +288,7 @@ Visualization Manager: Max Intensity: 285 Min Color: 0; 0; 0 Min Intensity: 2 - Name: LaserScan (ir sensors) - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.05 - Style: Flat Squares - Topic: /ir_scan - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/LaserScan - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: LaserScan (virtual sensor) - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.02 - Style: Flat Squares - Topic: /virtual_sensor_scan - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 + Name: PointCloud (bumpers) Position Transformer: XYZ Queue Size: 10