]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
Makre range sensor fov configureable
authorErik Andresen <erik@vontaene.de>
Wed, 6 Sep 2017 16:09:48 +0000 (18:09 +0200)
committerErik Andresen <erik@vontaene.de>
Wed, 6 Sep 2017 16:09:48 +0000 (18:09 +0200)
config/wt_node.cfg
scripts/wt_node.py

index aad0d5498c4007d96bb46234abf0021151690c78..fe8798cde3fd980c4bdfaf0f96dc84cb6107398b 100755 (executable)
@@ -6,6 +6,7 @@ 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.04, 4)
+gen.add("range_sensor_fov",    double_t,       0, "Range sensor field of view (deg)", 30, 1, 90)
 gen.add("odom_covar_xy",       double_t,       0, "Odometry covariance: translation", 1e-3, 1e-6, 1)
 gen.add("odom_covar_angle",    double_t,       0, "Odometry covariance: rotation", 1.00, 1e-6, 6.2832)
 gen.add("rollover_protect",    bool_t,         0, "Enable motor rollover protection on pitch", True)
index 5fc2e2d53155630563bf342d12769c9d3861de27..ab58496fca7b6f0220fe05216632f3d8c0811a4e 100755 (executable)
@@ -122,6 +122,7 @@ class MoveBase:
        def execute_dyn_reconf(self, config, level):
                self.bClipRangeSensor = config["range_sensor_clip"]
                self.range_sensor_max = config["range_sensor_max"]
+               self.range_sensor_fov = config["range_sensor_fov"]
                self.odom_covar_xy = config["odom_covar_xy"]
                self.odom_covar_angle = config["odom_covar_angle"]
                self.rollover_protect = config["rollover_protect"]
@@ -335,7 +336,7 @@ class MoveBase:
        def get_dist_forward_left(self):
                if self.pub_range_fwd_left.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x15)
-                       self.send_range(self.pub_range_fwd_left, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
+                       self.send_range(self.pub_range_fwd_left, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
 
        def update_dist_forward_left(self):
                if self.pub_range_fwd_left.get_num_connections() > 0:
@@ -344,7 +345,7 @@ class MoveBase:
        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, self.range_sensor_max, 30)
+                       self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
 
        def update_dist_backward(self):
                if self.pub_range_bwd.get_num_connections() > 0:
@@ -353,7 +354,7 @@ class MoveBase:
        def get_dist_forward_right(self):
                if self.pub_range_fwd_right.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x19)
-                       self.send_range(self.pub_range_fwd_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
+                       self.send_range(self.pub_range_fwd_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
 
        def update_dist_forward_right(self):
                if self.pub_range_fwd_right.get_num_connections() > 0: