]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
fixes third sonar integration
authorErik Andresen <erik@vontaene.de>
Thu, 1 Jun 2017 19:02:58 +0000 (21:02 +0200)
committerErik Andresen <erik@vontaene.de>
Thu, 1 Jun 2017 19:02:58 +0000 (21:02 +0200)
config/analyzers.yaml
scripts/wt_node.py
urdf/wild_thumper.urdf.xacro

index 76d0bc08c5d8bf5c069761dc819aa4645e4e3928..8215e23175c40c49cc6c355d5bb504179450e41b 100644 (file)
@@ -13,8 +13,3 @@ analyzers:
                 type: diagnostic_aggregator/GenericAnalyzer
                 path: Voltage
                 startswith: 'Voltage'
                 type: diagnostic_aggregator/GenericAnalyzer
                 path: Voltage
                 startswith: 'Voltage'
-        Razor9DofImu:
-                type: diagnostic_aggregator/GenericAnalyzer
-                path: 'Imu'
-                timeout: 5.0
-                contains: ['Razor_Imu']
index bbda8488780341b9167365e8b77c5cad3477cc18..fcb20be43f2a8fd1795b19a66590a7c79ea70873 100755 (executable)
@@ -96,11 +96,11 @@ class MoveBase:
                                ir_count+=1
                        else:
                                self.get_dist_right()
                                ir_count+=1
                        else:
                                self.get_dist_right()
-                               ir_count+=1
+                               ir_count=0
 
                        if sonar_count == 0:
                                self.get_dist_forward_left()
 
                        if sonar_count == 0:
                                self.get_dist_forward_left()
-                               sonar_count=0
+                               sonar_count+=1
                        elif sonar_count == 1:
                                self.get_dist_backward()
                                sonar_count+=1
                        elif sonar_count == 1:
                                self.get_dist_backward()
                                sonar_count+=1
@@ -312,7 +312,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)
        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, "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, 30)
                        self.start_dist_srf(0x5) # get next value
 
        def get_dist_backward(self):
                        self.start_dist_srf(0x5) # get next value
 
        def get_dist_backward(self):
@@ -324,7 +324,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)
        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, "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, 30)
                        self.start_dist_srf(0x9) # get next value
        
        def led_stripe_received(self, msg):
                        self.start_dist_srf(0x9) # get next value
        
        def led_stripe_received(self, msg):
index 3cc49220f73b9fc486f90258655404fa52d36c0a..15beab2b4ecd43be03558df6204729bb65f9c6da 100644 (file)
        <joint name="sonar_forward_left_joint" type="fixed">
                <parent link="mounting_plate"/>
                <child link="sonar_forward_left"/>
        <joint name="sonar_forward_left_joint" type="fixed">
                <parent link="mounting_plate"/>
                <child link="sonar_forward_left"/>
-               <origin xyz="0.115 -0.04 -0.012" rpy="0 0 0"/>
+               <origin xyz="0.115 0.04 -0.012" rpy="0 0 0"/>
        </joint>
 
        <joint name="sonar_forward_right_joint" type="fixed">
                <parent link="mounting_plate"/>
                <child link="sonar_forward_right"/>
        </joint>
 
        <joint name="sonar_forward_right_joint" type="fixed">
                <parent link="mounting_plate"/>
                <child link="sonar_forward_right"/>
-               <origin xyz="0.115 0.04 -0.012" rpy="0 0 0"/>
+               <origin xyz="0.115 -0.04 -0.012" rpy="0 0 0"/>
        </joint>
 
        <joint name="sonar_backward_joint" type="fixed">
        </joint>
 
        <joint name="sonar_backward_joint" type="fixed">