From 822c05d03c09295fb9687b3f58a9b9d7fbd3d170 Mon Sep 17 00:00:00 2001 From: Erik Andresen Date: Wed, 4 Sep 2013 12:13:19 +0200 Subject: [PATCH] Configurable robo_explorer --- explorer_configuration.launch | 8 ++++++-- scripts/robo_explorer.py | 11 +++++++---- 2 files changed, 13 insertions(+), 6 deletions(-) diff --git a/explorer_configuration.launch b/explorer_configuration.launch index f9e4302..71d23bd 100644 --- a/explorer_configuration.launch +++ b/explorer_configuration.launch @@ -1,9 +1,13 @@ - - + + + + + + diff --git a/scripts/robo_explorer.py b/scripts/robo_explorer.py index 73e2ae8..039fbd4 100755 --- a/scripts/robo_explorer.py +++ b/scripts/robo_explorer.py @@ -16,8 +16,6 @@ class RoboExplorer: def __init__(self): rospy.init_node('robo_explorer') - self.wheel_dist = 0.188 # 18.8cm - self.wheel_size = 0.051*0.5 # 5.1cm; gear ration=0.5 self.speed = (0, 0) self.x = 0 self.y = 0 @@ -29,6 +27,10 @@ class RoboExplorer: self.y_last = 0 self.alpha_last = 0 + self.enable_ultrasonic_laser = int(rospy.get_param('~ultrasonic_laser', "1")) + self.wheel_dist = float(rospy.get_param('~wheel_dist', "0.188")) + self.wheel_size = float(rospy.get_param('~wheel_size', "0.0255")) + self.pub_motor = rospy.Publisher("ft/set_motor", Motor) self.pub_scan = rospy.Publisher("scan", LaserScan) self.pub_odom = rospy.Publisher("odom", Odometry) @@ -44,7 +46,8 @@ class RoboExplorer: self.update_odometry(msg, current_time) if (current_time - self.last_time).to_nsec() > 100e6: # send every 100ms self.send_odometry(msg, current_time) - self.send_laser_scan(msg, current_time) + if self.enable_ultrasonic_laser: + self.send_laser_scan(msg, current_time) self.last_time = current_time def update_odometry(self, msg, current_time): @@ -131,7 +134,7 @@ class RoboExplorer: scan.angle_min = -opening_angle scan.angle_max = opening_angle scan.angle_increment = (2*opening_angle)/num_points - scan.time_increment = 0.001/num_points + scan.time_increment = 0.0 scan.range_min = 0.0 scan.range_max = 4.0 for i in range(num_points): -- 2.39.2