Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fixed map and costmap misalignement due to wrong frame_id #36

Merged
merged 7 commits into from
Dec 2, 2014
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 10 additions & 3 deletions turtlebot_stdr/launch/turtlebot_in_stdr.launch
Original file line number Diff line number Diff line change
@@ -1,18 +1,17 @@
<!--
Turtlebot navigation simulation:
- stdr
- map_server
- move_base
- static map
- amcl
- map_server
- rviz view
-->
<launch>
<arg name="base" default="$(optenv TURTLEBOT_BASE kobuki)"/> <!-- create, rhoomba -->
<arg name="stacks" default="$(optenv TURTLEBOT_STACKS hexagons)"/> <!-- circles, hexagons -->
<arg name="3d_sensor" default="$(optenv TURTLEBOT_3D_SENSOR kinect)"/> <!-- kinect, asus_xtion_pro -->
<arg name="laser_topic" default="robot0/laser_0"/> <!-- default laser topic in stdr for 1 robot -->
<arg name="odom_topic" default="robot0/odom"/> <!--env default odom topic in stdr for 1 robot -->
<arg name="odom_topic" default="robot0/odom"/>
<arg name="odom_frame_id" default="map"/>
<arg name="base_frame_id" default="robot0"/>
<arg name="global_frame_id" default="world"/>
Expand Down Expand Up @@ -52,6 +51,12 @@
<remap from="cmd_vel_mux/output" to="mobile_base/commands/velocity"/>
</node>

<!-- ****** Maps ***** -->
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)">
<param name="frame_id" value="$(arg global_frame_id)"/>
</node>


<!-- ************** Navigation *************** -->
<include file="$(find turtlebot_navigation)/launch/includes/move_base.launch.xml">
<arg name="odom_topic" value="$(arg odom_topic)"/>
Expand Down Expand Up @@ -85,5 +90,7 @@
<!-- **************** Visualisation **************** -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find turtlebot_stdr)/rviz/robot_navigation.rviz"/>




</launch>
16 changes: 8 additions & 8 deletions turtlebot_stdr/nodes/tf_connector.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()
2 changes: 1 addition & 1 deletion turtlebot_stdr/robot/turtlebot.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
59 changes: 1 addition & 58 deletions turtlebot_stdr/rviz/robot_navigation.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down