]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
added 3dsensor
authorErik Andresen <erik@vontaene.de>
Sat, 13 Jun 2015 17:45:41 +0000 (19:45 +0200)
committerErik Andresen <erik@vontaene.de>
Sat, 13 Jun 2015 17:45:41 +0000 (19:45 +0200)
launch/3dsensor.launch [new file with mode: 0644]
package.xml
scripts/move_base.py

diff --git a/launch/3dsensor.launch b/launch/3dsensor.launch
new file mode 100644 (file)
index 0000000..8276bb6
--- /dev/null
@@ -0,0 +1,13 @@
+<?xml version="1.0"?>
+<launch>
+       <include file="$(find openni2_launch)/launch/openni2.launch">
+               <arg name="depth_processing" value="true" />
+               <arg name="rgb_processing" value="false" />
+               <arg name="depth_registered_processing" value="false" />
+       </include>
+
+       <node pkg="nodelet" type="nodelet" name="depthimage_to_laserscan" args="load depthimage_to_laserscan/DepthImageToLaserScanNodelet /camera/camera_nodelet_manager" output="screen">
+               <remap from="/camera/image" to="/camera/depth/image_raw"/>
+               <remap from="/camera/scan" to="/scan"/>
+       </node>
+</launch>
index 6911afefac1fab5d77cd471cb299f49bcc33cab7..2093ebd90d423c7f0ab2af3eb5c8f9425aa57fd8 100644 (file)
   <build_depend>roscpp</build_depend>
   <build_depend>std_msgs</build_depend>
   <build_depend>image_transport</build_depend>
+  <build_depend>openni2_camera</build_depend>
   <run_depend>hector_sensors_description</run_depend>
+  <run_depend>openni2_launch</run_depend>
+  <run_depend>depthimage_to_laserscan</run_depend>
 
   <!-- The export tag contains other, unspecified, tags -->
   <export>
index 6c066f391f9b50a70c24f2a77a8ac335894f263b..0beaf2668801f27a7a66a1a0a54a755b755646bd 100755 (executable)
@@ -24,6 +24,7 @@ class MoveBase:
                self.set_speed(0, 0)
                rospy.loginfo("Init done")
                i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
+               self.handicap_last = (-1, -1)
                self.run()
        
        def run(self):
@@ -42,18 +43,18 @@ class MoveBase:
                        rate.sleep()
 
        def set_motor_handicap(self, front, aft): # percent
-               i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft))
+               if self.handicap_last != (front, aft):
+                       i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft))
+                       self.handicap_last = (front, aft)
 
        def imuReceived(self, msg):
                (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
                if pitch > 30*pi/180:
-                       val = (100/90)*abs(pitch)*180/pi
-                       print "aft handicap", val
-                       self.set_motor_handicap(0, val)
+                       val = (100.0/65)*abs(pitch)*180/pi
+                       self.set_motor_handicap(0, int(val))
                elif pitch < -30*pi/180:
-                       val = (100/90)*abs(pitch)*180/pi
-                       print "front handicap", val
-                       self.set_motor_handicap(val, 0)
+                       val = (100.0/65)*abs(pitch)*180/pi
+                       self.set_motor_handicap(int(val), 0)
                else:
                        self.set_motor_handicap(0, 0)