]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
added range sensor messages
authorErik Andresen <erik@vontaene.de>
Fri, 10 Jul 2015 18:28:54 +0000 (20:28 +0200)
committerErik Andresen <erik@vontaene.de>
Fri, 10 Jul 2015 18:28:54 +0000 (20:28 +0200)
scripts/move_base.py
urdf/wild_thumper.urdf.xacro

index 09f823b576dd790073b949f52c784ed85ad5dc3f..8f14c6c1f63f203512b0652e918ba9591f454c15 100755 (executable)
@@ -9,7 +9,7 @@ from math import *
 from geometry_msgs.msg import Twist
 from nav_msgs.msg import Odometry
 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
 from geometry_msgs.msg import Twist
 from nav_msgs.msg import Odometry
 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
-from sensor_msgs.msg import Imu
+from sensor_msgs.msg import Imu, Range
 
 WHEEL_DIST = 0.248
 
 
 WHEEL_DIST = 0.248
 
@@ -25,6 +25,10 @@ class MoveBase:
                        self.tf_broadcaster = None
                self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
                self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
                        self.tf_broadcaster = None
                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_range_bwd = rospy.Publisher("range_backward", Range, queue_size=16)
+               self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16)
+               self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16)
                self.set_speed(0, 0)
                rospy.loginfo("Init done")
                i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
                self.set_speed(0, 0)
                rospy.loginfo("Init done")
                i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
@@ -40,10 +44,10 @@ class MoveBase:
                        self.get_tle_err()
                        self.get_odom()
                        self.get_voltage()
                        self.get_tle_err()
                        self.get_odom()
                        self.get_voltage()
-                       #self.get_dist_forward()
-                       #self.get_dist_backward()
-                       #self.get_dist_left()
-                       #self.get_dist_right()
+                       self.get_dist_forward()
+                       self.get_dist_backward()
+                       self.get_dist_left()
+                       self.get_dist_right()
                        rate.sleep()
 
        def set_motor_handicap(self, front, aft): # percent
                        rate.sleep()
 
        def set_motor_handicap(self, front, aft): # percent
@@ -200,18 +204,37 @@ class MoveBase:
 
                return struct.unpack(">H", s)[0]/1000.0
 
 
                return struct.unpack(">H", s)[0]/1000.0
 
+       def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
+               msg = Range()
+               msg.header.stamp = rospy.Time.now()
+               msg.header.frame_id = frame_id
+               msg.radiation_type = typ
+               msg.field_of_view = fov_deg*pi/180
+               msg.min_range = min_range
+               msg.max_range = max_range
+               msg.range = dist
+               pub.publish(msg)
+
        def get_dist_left(self):
        def get_dist_left(self):
-               dist = self.get_dist_ir(0x1)
+               if self.pub_range_left.get_num_connections() > 0:
+                       dist = self.get_dist_ir(0x1)
+                       self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, dist, 0.1, 0.8, 5)
 
        def get_dist_right(self):
 
        def get_dist_right(self):
-                dist = self.get_dist_ir(0x3)
+               if self.pub_range_right.get_num_connections() > 0:
+                       dist = self.get_dist_ir(0x3)
+                       self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, dist, 0.1, 0.8, 5)
 
        def get_dist_forward(self):
 
        def get_dist_forward(self):
-               dist = self.get_dist_srf(0x5)
+               if self.pub_range_fwd.get_num_connections() > 0:
+                       dist = self.get_dist_srf(0x5)
+                       self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 60)
 
        def get_dist_backward(self):
 
        def get_dist_backward(self):
-               dist = self.get_dist_srf(0x7)
-
+               if self.pub_range_bwd.get_num_connections() > 0:
+                       dist = self.get_dist_srf(0x7)
+                       self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, 6, 60)
+               
 
 if __name__ == "__main__":
        MoveBase()
 
 if __name__ == "__main__":
        MoveBase()
index c783cffff36792da7c39d78102995dd0bf82f1a5..4e78a879cb48e63d75398287f0fe659410edeb65 100644 (file)
@@ -5,7 +5,7 @@
 
        <link name="base_link">
                <visual>
 
        <link name="base_link">
                <visual>
-                       <origin xyz="0.09 -0.02 0.07" rpy="${PI} 0 ${-PI/2}"/>
+                       <origin xyz="0.09 -0.022 0.07" rpy="${PI} 0 ${-PI/2}"/>
                        <geometry>
                                <mesh filename="package://wild_thumper/meshes/wild_thumper_assembly_corrected.stl" scale="0.001 0.001 0.001" />
                        </geometry>
                        <geometry>
                                <mesh filename="package://wild_thumper/meshes/wild_thumper_assembly_corrected.stl" scale="0.001 0.001 0.001" />
                        </geometry>
                <origin xyz="0.107 0.0 0.04" rpy="0 0 0"/>
        </xacro:asus_camera>
 
                <origin xyz="0.107 0.0 0.04" rpy="0 0 0"/>
        </xacro:asus_camera>
 
+       <link name="sonar_forward">
+               <visual>
+                       <geometry>
+                               <box size="0.016 0.044 0.02"/>
+                       </geometry>
+                       <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
+                       <material name="green">
+                               <color rgba="0 1 0 0.8"/>
+                       </material>
+               </visual>
+       </link>
+
+       <link name="sonar_backward">
+               <visual>
+                       <geometry>
+                               <box size="0.016 0.044 0.02"/>
+                       </geometry>
+                       <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
+                       <material name="green">
+                               <color rgba="0 1 0 0.8"/>
+                       </material>
+               </visual>
+       </link>
+
+       <link name="ir_left">
+               <visual>
+                       <geometry>
+                               <box size="0.015 0.015 0.046"/>
+                       </geometry>
+                       <origin xyz="${-0.015/2} 0 0" rpy="0 0 0"/>
+                       <material name="black">
+                               <color rgba="0 0 0 1"/>
+                       </material>
+               </visual>
+       </link>
+
+       <link name="ir_right">
+               <visual>
+                       <geometry>
+                               <box size="0.015 0.015 0.046"/>
+                       </geometry>
+                       <origin xyz="${-0.015/2} 0 0" rpy="0 0 0"/>
+                       <material name="black">
+                               <color rgba="0 0 0 1"/>
+                       </material>
+               </visual>
+       </link>
+
        <joint name="imu_joint" type="fixed">
                <parent link="base_link"/>
                <child link="base_imu_link"/>
        <joint name="imu_joint" type="fixed">
                <parent link="base_link"/>
                <child link="base_imu_link"/>
                <child link="base_link"/>
                <origin xyz="0.0 0.0 0.13" rpy="0 0 0"/>
        </joint>
                <child link="base_link"/>
                <origin xyz="0.0 0.0 0.13" rpy="0 0 0"/>
        </joint>
+
+       <joint name="sonar_forward_joint" type="fixed">
+               <parent link="base_link"/>
+               <child link="sonar_forward"/>
+               <origin xyz="0.115 0.0 -0.012" rpy="0 0 0"/>
+       </joint>
+
+       <joint name="sonar_backward_joint" type="fixed">
+               <parent link="base_link"/>
+               <child link="sonar_backward"/>
+               <origin xyz="-0.115 0.0 -0.012" rpy="0 ${PI} 0"/>
+       </joint>
+
+       <joint name="ir_left_joint" type="fixed">
+               <parent link="base_link"/>
+               <child link="ir_left"/>
+               <origin xyz="0.0 ${0.072+0.015} -0.045" rpy="0 0 ${PI/2}"/>
+       </joint>
+
+       <joint name="ir_right_joint" type="fixed">
+               <parent link="base_link"/>
+               <child link="ir_right"/>
+               <origin xyz="0.0 ${-0.072-0.015} -0.045" rpy="0 0 ${-PI/2}"/>
+       </joint>
 </robot>
 </robot>