From cacb82ac8403db8d5eae119c12faf751ebbe0e71 Mon Sep 17 00:00:00 2001 From: Erik Andresen Date: Sat, 11 Jul 2015 19:47:08 +0200 Subject: [PATCH] renamed move_base.py to wt_node.py --- launch/3dsensor.launch | 2 +- launch/wild_thumper.launch | 12 ++++++++---- scripts/{move_base.py => wt_node.py} | 4 ++-- 3 files changed, 11 insertions(+), 7 deletions(-) rename scripts/{move_base.py => wt_node.py} (99%) diff --git a/launch/3dsensor.launch b/launch/3dsensor.launch index 8276bb6..61f622a 100644 --- a/launch/3dsensor.launch +++ b/launch/3dsensor.launch @@ -7,7 +7,7 @@ - + diff --git a/launch/wild_thumper.launch b/launch/wild_thumper.launch index fbd17ec..b0aa2ea 100644 --- a/launch/wild_thumper.launch +++ b/launch/wild_thumper.launch @@ -1,5 +1,7 @@ + + @@ -8,16 +10,18 @@ - - + + + - + - + + diff --git a/scripts/move_base.py b/scripts/wt_node.py similarity index 99% rename from scripts/move_base.py rename to scripts/wt_node.py index 0d68ce9..72c0412 100755 --- a/scripts/move_base.py +++ b/scripts/wt_node.py @@ -15,7 +15,7 @@ WHEEL_DIST = 0.248 class MoveBase: def __init__(self): - rospy.init_node('wild_thumper_move_base') + rospy.init_node('wild_thumper') rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived) rospy.Subscriber("imu", Imu, self.imuReceived) enable_odom_tf = rospy.get_param("~enable_odom_tf", True) @@ -133,7 +133,7 @@ class MoveBase: # next, we'll publish the odometry message over ROS odom = Odometry() odom.header.stamp = current_time - odom.header.frame_id = "/odom" + odom.header.frame_id = "odom" # set the position odom.pose.pose.position.x = posx -- 2.39.2