From ffe8ec42bc41d93a9129b6f11c641698d24b27ab Mon Sep 17 00:00:00 2001 From: erik Date: Tue, 27 Aug 2013 13:29:04 +0200 Subject: [PATCH] added readme --- README.txt | 23 +++++++++++++++++++++++ config/costmap_common_params.yaml | 4 ++-- scripts/robo_explorer.py | 13 ++++++------- 3 files changed, 31 insertions(+), 9 deletions(-) create mode 100644 README.txt diff --git a/README.txt b/README.txt new file mode 100644 index 0000000..e1fd423 --- /dev/null +++ b/README.txt @@ -0,0 +1,23 @@ +Requirements: +========== +Use Robo Explorer with Wheels instead of Tracks: +Tracks are too inaccurate for Odometry. +I used the Setup from Mobile Robots 2. + +Commands: +========== +-When running a component (eg. rviz) remote: +# export ROS_MASTER_URI=http://192.168.0.2:11311 +# export ROS_IP=$OWN_IP +-Start Explorer: +# roslaunch explorer_configuration.launch +-Start Navigation Stack: +# roslaunch move_base.launch +-Start RViz: +# rosrun rviz rviz +-Manually setting of Translation/Rotation speed: +# rostopic pub -1 cmd_vel geometry_msgs/Twist '[0.0, 0, 0]' '[0, 0, 0.0]' + +Notes: +========== +Laserscan is faked by the sonar sensor. diff --git a/config/costmap_common_params.yaml b/config/costmap_common_params.yaml index 0224ad9..ca84cc0 100644 --- a/config/costmap_common_params.yaml +++ b/config/costmap_common_params.yaml @@ -2,8 +2,8 @@ obstacle_range: 2.5 raytrace_range: 3.0 #footprint: [[x0, y0], [x1, y1], ... [xn, yn]] robot_radius: 0.105 -inflation_radius: 0.55 +inflation_radius: 0.15 observation_sources: laser_scan_sensor -laser_scan_sensor: {sensor_frame: base_scan, data_type: LaserScan, topic: base_scan, marking: true, clearing: true} +laser_scan_sensor: {sensor_frame: scan, data_type: LaserScan, topic: scan, marking: true, clearing: true} diff --git a/scripts/robo_explorer.py b/scripts/robo_explorer.py index 693a8d0..cfc23fa 100755 --- a/scripts/robo_explorer.py +++ b/scripts/robo_explorer.py @@ -23,7 +23,6 @@ class RoboExplorer: self.last_in = None self.tf_broadcaster = tf.TransformBroadcaster() self.last_time = rospy.Time.now() - self.input_count = 0 self.x_last = 0 self.y_last = 0 self.alpha_last = 0 @@ -39,13 +38,12 @@ class RoboExplorer: def inputsReceived(self, msg): current_time = rospy.Time.now() - self.input_count+=1 self.update_odometry(msg, current_time) - if self.input_count >= 10: - self.input_count = 0 + 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) + self.last_time = current_time def update_odometry(self, msg, current_time): in_now = msg.input[1:3] @@ -85,7 +83,6 @@ class RoboExplorer: vx = (self.x - self.x_last) / dt vy = (self.y - self.y_last) / dt valpha = (self.alpha - self.alpha_last) / dt - self.last_time = current_time self.x_last = self.x self.y_last = self.y self.alpha_last = self.alpha @@ -124,7 +121,7 @@ class RoboExplorer: self.tf_broadcaster.sendTransform((0.06, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "scan", "base_link") # actually ultra sonic range finder - num_points = 30 + num_points = 60 # The base planner needs at least 30 points to work in the default config opening_angle = 30*pi/180 # each side scan = LaserScan() scan.header.stamp = current_time @@ -132,7 +129,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.1/num_points + scan.time_increment = 0.001/num_points scan.range_min = 0.0 scan.range_max = 4.0 for i in range(num_points): @@ -170,6 +167,8 @@ class RoboExplorer: if speed_r < -7: speed_r = -7 elif speed_r > 7: speed_r = 7 + #print "Speed wanted: %.2f %.2f, set: %d %d" % (trans, rot*180/pi, round(speed_l), round(speed_r)) + outmsg = Motor() outmsg.num = 1 outmsg.speed = round(speed_l) -- 2.39.5