From: Erik Andresen Date: Thu, 5 Sep 2013 16:32:43 +0000 (+0200) Subject: updated values X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_roboint.git;a=commitdiff_plain;h=d92b24d6eb3acc301f4f384fc40263f0444ed553 updated values --- diff --git a/README b/README index 8e6dd95..c5ea435 100644 --- a/README +++ b/README @@ -46,3 +46,5 @@ Commands: # rostopic pub -1 cmd_vel geometry_msgs/Twist '[0.1, 0, 0]' '[0, 0, 0.0]' Turn: # rostopic pub -1 cmd_vel geometry_msgs/Twist '[0.1, 0, 0]' '[0, 0, 0.4]' +-Keyboard Control: +# rosrun pr2_teleop teleop_pr2_keyboard diff --git a/explorer_configuration.launch b/explorer_configuration.launch index 5aadc57..edfdc1c 100644 --- a/explorer_configuration.launch +++ b/explorer_configuration.launch @@ -5,9 +5,9 @@ - - - - + + + + diff --git a/scripts/robo_explorer.py b/scripts/robo_explorer.py index f39c9c4..24584e7 100755 --- a/scripts/robo_explorer.py +++ b/scripts/robo_explorer.py @@ -29,10 +29,10 @@ class RoboExplorer: # fake laser scan with ultra sonic range finder self.enable_ultrasonic_laser = bool(rospy.get_param('~ultrasonic_laser', "True")) - # Distance between both wheels in meter (18.8cm) - self.wheel_dist = float(rospy.get_param('~wheel_dist', "0.188")) - # Size of wheel Diameter in meter (5.1cm) * gear ratio (0.5) = 2.55cm - self.wheel_size = float(rospy.get_param('~wheel_size', "0.0255")) + # Distance between both wheels in meter (18.55cm) + self.wheel_dist = float(rospy.get_param('~wheel_dist', "0.1855")) + # Size of wheel Diameter in meter (5.15cm) * gear ratio (0.5) = 2.575cm + self.wheel_size = float(rospy.get_param('~wheel_size', "0.02575")) # Speed to PWM equation gradiant (The m in pwm = speed*m+b) self.speed_gradiant = float(rospy.get_param('~speed_gradiant', "64.3")) # Speed to PWM equation constant (The b in pwm = speed*m+b)