Skip to content

Commit 733a8e8

Browse files
committed
frame_ids should have no prepended slashes
1 parent c7ed743 commit 733a8e8

File tree

4 files changed

+6
-6
lines changed

4 files changed

+6
-6
lines changed

README.md

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,7 @@ Give a 2D-goal in rviz to start path planning algorithm
7474

7575
Depends on:
7676

77-
[mobile_robot_simulator](https://github.com/mrath/mobile_robot_simulator.git) that integrates /cmd_vel into a /base_link TF-frame and an odometry publisher
77+
[mobile_robot_simulator](https://github.com/mrath/mobile_robot_simulator.git) that integrates /cmd_vel into a base_link TF-frame and an odometry publisher
7878

7979
[tracking_pid](https://github.com/nobleo/tracking_pid/) Global path tracking controller
8080

@@ -172,4 +172,4 @@ More information: <a href="http://rosin-project.eu">rosin-project.eu</a>
172172
alt="eu_flag" height="45" align="left" >
173173

174174
This project has received funding from the European Union’s Horizon 2020
175-
research and innovation programme under grant agreement no. 732287.
175+
research and innovation programme under grant agreement no. 732287.

test/full_coverage_path_planner/test_full_coverage_path_planner.launch

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@
4141

4242
<!--We need a map to fully cover-->
4343
<node name="grid_server" pkg="map_server" type="map_server" args="$(arg map)">
44-
<param name="frame_id" value="/map"/>
44+
<param name="frame_id" value="map"/>
4545
</node>
4646

4747
<!--Tracking_pid cannot just accept a nav_msgs/Path, it can only go to a PoseStamped,

test/full_coverage_path_planner/test_full_coverage_path_planner_plugin.launch

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@
2525

2626
<!--We need a map to fully cover-->
2727
<node name="grid_server" pkg="map_server" type="map_server" args="$(arg map)">
28-
<param name="frame_id" value="/map"/>
28+
<param name="frame_id" value="map"/>
2929
</node>
3030

3131
<!-- Mobile robot simulator -->

test/full_coverage_path_planner/test_full_coverage_path_planner_system.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -45,8 +45,8 @@ def test_tracking_pid(self):
4545
"""
4646
p1_msg = rospy.wait_for_message("trajectory", traj_point, timeout=5)
4747
p1_yaw = self.quaternion_to_yaw(p1_msg.pose.pose.orientation)
48-
self.listener.waitForTransform('/map', '/base_link', rospy.Time(0), rospy.Duration(1.0))
49-
(trans1, rot1) = self.listener.lookupTransform('/map', '/base_link', rospy.Time(0))
48+
self.listener.waitForTransform('map', 'base_link', rospy.Time(0), rospy.Duration(1.0))
49+
(trans1, rot1) = self.listener.lookupTransform('map', 'base_link', rospy.Time(0))
5050
rospy.sleep(2.0)
5151
p2_msg = rospy.wait_for_message("trajectory", traj_point, timeout=5)
5252
p2_yaw = self.quaternion_to_yaw(p2_msg.pose.pose.orientation)

0 commit comments

Comments
 (0)