]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
-added dynamic reconfiguration for wt_node
authorErik Andresen <erik@vontaene.de>
Fri, 18 Nov 2016 20:14:53 +0000 (21:14 +0100)
committerErik Andresen <erik@vontaene.de>
Fri, 18 Nov 2016 20:14:53 +0000 (21:14 +0100)
-tune max sonar range with dynamic reconfigure
-clip sonar range to max

CMakeLists.txt
config/razor.yaml
config/wt_node.cfg [new file with mode: 0755]
launch/teleop.launch
scripts/wt_node.py

index fe6d50a30b98386c5f5c5aacbe9b5722553c0b81..2b9c8733ca316ffd93a18ab54fdf2301174fdc10 100644 (file)
@@ -68,6 +68,7 @@ generate_messages(
 
 generate_dynamic_reconfigure_options(
   config/path_following.cfg
 
 generate_dynamic_reconfigure_options(
   config/path_following.cfg
+  config/wt_node.cfg
 )
 
 ###################################
 )
 
 ###################################
index cb811489041b44e820db603bcb82afc05fef83b9..3186e944a50b3a0f93cd10cdeb2a3784e506d210 100644 (file)
@@ -23,8 +23,8 @@ magn_z_max: 596
 
 # extended calibration
 calibration_magn_use_extended: true
 
 # extended calibration
 calibration_magn_use_extended: true
-magn_ellipsoid_center: [328.442, 29.7813, -414.405]
-magn_ellipsoid_transform: [[0.912198, -0.0995186, 0.00347704], [-0.0995186, 0.879227, 0.0332387], [0.00347704, 0.0332387, 0.892227]]
+magn_ellipsoid_center: [275.555, 42.7157, -390.911]
+magn_ellipsoid_transform: [[0.933345, -0.0570043, 0.0301076], [-0.0570043, 0.950937, 0.0283306], [0.0301076, 0.0283306, 0.965042]]
 
 # AHRS to robot calibration
 imu_yaw_calibration: 0.0
 
 # AHRS to robot calibration
 imu_yaw_calibration: 0.0
diff --git a/config/wt_node.cfg b/config/wt_node.cfg
new file mode 100755 (executable)
index 0000000..45ad4eb
--- /dev/null
@@ -0,0 +1,10 @@
+#!/usr/bin/env python
+
+from dynamic_reconfigure.parameter_generator_catkin import *
+
+gen = ParameterGenerator()
+
+gen.add("range_sensor_clip",   bool_t,         0, "Clip range sensor values to max range", True)
+gen.add("range_sensor_max",    double_t,       0, "Range sensor max range", 0.5, 0.4, 6)
+
+exit(gen.generate("wild_thumper", "wild_thumper", "WildThumper"))
index 371ba016a9ca8b63943aaf1ea75a883d0c7282c0..18f083cdec64a81705874873b8c573afdb731153 100644 (file)
@@ -2,7 +2,7 @@
 <launch>
        <node pkg="turtlebot_teleop" type="turtlebot_teleop_joy" name="turtlebot_teleop_joystick" respawn="true">
                <param name="scale_linear" value="0.2"/>
 <launch>
        <node pkg="turtlebot_teleop" type="turtlebot_teleop_joy" name="turtlebot_teleop_joystick" respawn="true">
                <param name="scale_linear" value="0.2"/>
-               <param name="scale_angular" value="-0.1"/>
+               <param name="scale_angular" value="-0.2"/>
                <param name="axis_deadman" value="3"/>
                <param name="axis_linear" value="1"/>
                <param name="axis_angular" value="0"/>
                <param name="axis_deadman" value="3"/>
                <param name="axis_linear" value="1"/>
                <param name="axis_angular" value="0"/>
index 2de2f590141a0960a47d8bd6f14033accc73e0f2..7254c1d38ad4573961862f0af7850e87872d417b 100755 (executable)
@@ -14,6 +14,8 @@ from nav_msgs.msg import Odometry
 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
 from sensor_msgs.msg import Imu, Range
 from wild_thumper.msg import LedStripe
 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
 from sensor_msgs.msg import Imu, Range
 from wild_thumper.msg import LedStripe
+from dynamic_reconfigure.server import Server
+from wild_thumper.cfg import WildThumperConfig
 
 WHEEL_DIST = 0.248
 
 
 WHEEL_DIST = 0.248
 
@@ -55,6 +57,7 @@ class MoveBase:
                        self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
                else:
                        self.tf_broadcaster = None
                        self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
                else:
                        self.tf_broadcaster = None
+               self.dyn_conf = Server(WildThumperConfig, self.execute_dyn_reconf)
                self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
                self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
                self.pub_range_fwd = rospy.Publisher("range_forward", Range, queue_size=16)
                self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
                self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
                self.pub_range_fwd = rospy.Publisher("range_forward", Range, queue_size=16)
@@ -96,6 +99,11 @@ class MoveBase:
                                self.cmd_vel = None
                        rate.sleep()
 
                                self.cmd_vel = None
                        rate.sleep()
 
+       def execute_dyn_reconf(self, config, level):
+               self.bClipRangeSensor = config["range_sensor_clip"]
+               self.range_sensor_max = config["range_sensor_max"]
+               return config
+
        def set_motor_handicap(self, front, aft): # percent
                if front > 100: front = 100
                if aft > 100: aft = 100
        def set_motor_handicap(self, front, aft): # percent
                if front > 100: front = 100
                if aft > 100: aft = 100
@@ -261,6 +269,8 @@ class MoveBase:
                return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0
 
        def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
                return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0
 
        def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
+               if self.bClipRangeSensor and dist > max_range:
+                       dist = max_range
                msg = Range()
                msg.header.stamp = rospy.Time.now()
                msg.header.frame_id = frame_id
                msg = Range()
                msg.header.stamp = rospy.Time.now()
                msg.header.frame_id = frame_id
@@ -286,13 +296,13 @@ class MoveBase:
        def get_dist_forward(self):
                if self.pub_range_fwd.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x15)
        def get_dist_forward(self):
                if self.pub_range_fwd.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x15)
-                       self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 40)
+                       self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
                        self.start_dist_srf(0x5) # get next value
 
        def get_dist_backward(self):
                if self.pub_range_bwd.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x17)
                        self.start_dist_srf(0x5) # get next value
 
        def get_dist_backward(self):
                if self.pub_range_bwd.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x17)
-                       self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, 6, 40)
+                       self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
                        self.start_dist_srf(0x7) # get next value
        
        def led_stripe_received(self, msg):
                        self.start_dist_srf(0x7) # get next value
        
        def led_stripe_received(self, msg):