]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
Move forward sonars 2cm more apart
authorErik Andresen <erik@vontaene.de>
Sat, 3 Jun 2017 17:39:51 +0000 (19:39 +0200)
committerErik Andresen <erik@vontaene.de>
Sat, 3 Jun 2017 17:39:51 +0000 (19:39 +0200)
scripts/wt_node.py
urdf/wild_thumper.urdf.xacro

index fcb20be43f2a8fd1795b19a66590a7c79ea70873..5215d49ca5d3e7dd68fb751181f0fac9d8f197cd 100755 (executable)
@@ -325,7 +325,7 @@ class MoveBase:
                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.start_dist_srf(0x9) # get next value
+                       self.start_dist_srf(0xb) # get next value
        
        def led_stripe_received(self, msg):
                for led in msg.leds:
index 15beab2b4ecd43be03558df6204729bb65f9c6da..47039b6dfca1512d1c9fdd3b5dae2ccdd1158762 100644 (file)
        <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.05 -0.012" rpy="0 0 0"/>
        </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.05 -0.012" rpy="0 0 0"/>
        </joint>
 
        <joint name="sonar_backward_joint" type="fixed">