]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
urdf: Add gazebo laser configuration
authorErik Andresen <erik@vontaene.de>
Tue, 16 Jul 2019 19:08:35 +0000 (21:08 +0200)
committerErik Andresen <erik@vontaene.de>
Tue, 16 Jul 2019 19:08:35 +0000 (21:08 +0200)
CMakeLists.txt
config/costmap_exploration.yaml
config/global_costmap_params.yaml
config/robot_localization.yaml
data/power_consumption.txt
package.xml
scripts/pocketsphinx.rb
urdf/wild_thumper.urdf.xacro

index c83bb8648ed0db14f9f0709a677064e57bcc71eb..689434c552e4f10639ebd028ab3b150eb0115d33 100644 (file)
@@ -4,7 +4,7 @@ project(wild_thumper)
 ## Find catkin macros and libraries
 ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
 ## is used, also find other catkin packages
-find_package(catkin REQUIRED sensor_msgs cv_bridge roscpp rospy std_msgs image_transport dynamic_reconfigure message_generation)
+find_package(catkin REQUIRED sensor_msgs cv_bridge roscpp rospy std_msgs image_transport dynamic_reconfigure message_generation rosruby)
 find_package(OpenCV)
 
 ## System dependencies are found with CMake's conventions
@@ -67,6 +67,9 @@ generate_messages(
   std_msgs  # Or other packages containing msgs
 )
 
+rosruby_setup()
+rosruby_generate_messages(fiducial_msgs)
+
 generate_dynamic_reconfigure_options(
   config/path_following.cfg
   config/wt_node.cfg
index 84c88efd4e137b9993a1b3f08568377e93588739..4ce6692c7b4ec076616a13d107ad7efb408e17b7 100644 (file)
@@ -18,7 +18,7 @@ plugins:
 
 static_layer:
   # Can pull data from gmapping, map_server or a non-rolling costmap
-  map_topic: /map
+  map_topic: map
   # map_topic: move_base/global_costmap/costmap
   subscribe_to_updates: true
 
index 04e296d756fe016ffa902a99d08f09887dd3e524..af07509b424cb46cb9cbdf6d5fb89195b3edaa4f 100644 (file)
@@ -1,5 +1,5 @@
 global_costmap:
-  global_frame: /map
+  global_frame: map
   robot_base_frame: base_footprint
   static_map: true
   publish_frequency: 1.0
index 82d5fff34d9f547cfc3d0a57e069803e1242ec56..bce9d7466b012d5ed373181739ef0f08ae2dc5a7 100644 (file)
@@ -120,7 +120,7 @@ imu0_remove_gravitational_acceleration: true
 # if the node is unhappy with any settings or data.
 print_diagnostics: true
 
-# If true, will dynamically scale the process_noise_covariance based on the robot?s velocity. This is useful, e.g., when you want your
+# If true, will dynamically scale the process_noise_covariance based on the robot's velocity. This is useful, e.g., when you want your
 # robots estimate error covariance to stop growing when the robot is stationary. Defaults to false.
 dynamic_process_noise_covariance: true
 
index 17e663f87f3d2b560d7669a83afff6fbd22ec718..99cdc50b880e6aaca8d77453d64f88b6c03e303e 100644 (file)
@@ -21,3 +21,15 @@ Hummingboard Idle (no Openni2): 0.65A
 Hummingboard Nav: 0.8A
 RPI3 Idle (no Openni2): 0.58A
 RPI3 Nav: 0.71A
+
+Sensor:
+----------
+Kein Sensor: 0.34A
+Idle Xtion: 0.67A (+0.16A)
+Run Xtion: 0.74A (+0.29A)
+
+Idle rplidar2: 0.66A (+0.26A)
+Run rplidar2: 0.93A (+0.60A)
+
+Idle rplidar1: +0.05A
+Run rplidar1: +0.25A
index 69fe021b76591c370c018df0f7782c083128d26e..0c6850753a3f91386e2baa44fcc25cd23540d38f 100644 (file)
@@ -54,6 +54,8 @@
   <run_depend>depthimage_to_laserscan</run_depend>
   <run_depend>message_runtime</run_depend>
   <run_depend>rosruby</run_depend>
+  <run_depend>amcl</run_depend>
+  <run_depend>gmapping</run_depend>
 
   <!-- The export tag contains other, unspecified, tags -->
   <export>
index c2a87fbb09601557126e6fc52696c130c15d7a2a..d8e7bef5109edf17db13f5061d0276050c5bdad2 100755 (executable)
@@ -1,4 +1,4 @@
-#!/usr/bin/ruby -w
+#!/usr/bin/ruby
 
 require 'gst'
 require 'pry'
@@ -40,8 +40,10 @@ class Speak
                                binding.pry # open console
                                loop.quit
                        when Gst::MessageType::ELEMENT
-                               if message.src.name == "asr_kws" and message.structure.get_value(:final).value
-                                       keyword_detect(message.structure.get_value(:hypothesis).value, message.structure.get_value(:confidence).value)
+                               if message.src.name == "asr_kws"
+                                       if message.structure.get_value(:final).value
+                                               keyword_detect(message.structure.get_value(:hypothesis).value, message.structure.get_value(:confidence).value)
+                                       end
                                elsif message.src.name == "asr_jsgf"
                                        if message.structure.get_value(:final).value
                                                final_result(message.structure.get_value(:hypothesis).value, message.structure.get_value(:confidence).value)
@@ -60,13 +62,13 @@ class Speak
                @pipeline.play
        end
 
-       # Enables/Disables the jsgf pipeline
+       # Enables/Disables the jsgf pipeline branch
        def enable_jsgf(bEnable)
                valve = @pipeline.get_by_name('valve_jsgf')
                valve.set_property("drop", !bEnable)
        end
 
-       # Result of jsgf pipeline
+       # Result of jsgf pipeline branch
        def final_result(hyp, confidence)
                @logger.info "final: " + hyp + " " + confidence.to_s
                enable_jsgf(false)
@@ -88,7 +90,7 @@ class Speak
 end
 
 if __FILE__ == $0
-       node = ROS::Node.new('wild_thumper/pocketsphinx')
+       node = ROS::Node.new('pocketsphinx')
        app = Speak.new(node)
        loop = GLib::MainLoop.new(nil, false)
        begin
index 5d5f9b7b23366dc5d5e8c2279e16bd26a01db062..2f00fd63efd18c6e3fc73169f1321d417d51048f 100644 (file)
        <xacro:range_sensor name="sonar_backward" ros_topic="range_backward" update_rate="10" minRange="0.04" maxRange="0.5" fov="${20*PI/180}" radiation="ultrasound" />
        <xacro:range_sensor name="ir_left" ros_topic="range_left" update_rate="10" minRange="0.04" maxRange="0.3" fov="${5*PI/180}" radiation="infrared" />
        <xacro:range_sensor name="ir_right" ros_topic="range_right" update_rate="10" minRange="0.04" maxRange="0.3" fov="${5*PI/180}" radiation="infrared" />
+
+       <gazebo reference="lidar">
+               <sensor type="ray" name="head_rplidar_a2_sensor">
+                       <pose>0 0 0 0 0 0</pose>
+                       <visualize>false</visualize>
+                       <update_rate>12</update_rate>
+                       <ray>
+                               <scan>
+                                       <horizontal>
+                                               <samples>360</samples>
+                                               <resolution>1</resolution>
+                                               <min_angle>-3.12413907051</min_angle>
+                                               <max_angle>3.14159274101</max_angle>
+                                       </horizontal>
+                               </scan>
+                               <range>
+                                       <min>0.15</min>
+                                       <max>16.0</max>
+                                       <resolution>0.01</resolution>
+                               </range>
+                               <noise>
+                                       <type>gaussian</type>
+                                       <mean>0.0</mean>
+                                       <stddev>0.01</stddev>
+                               </noise>
+                       </ray>
+                       <plugin name="gazebo_ros_head_rplidar_a2_controller" filename="libgazebo_ros_laser.so">
+                               <topicName>/scan</topicName>
+                               <frameName>lidar</frameName>
+                       </plugin>
+               </sensor>
+       </gazebo>
 </robot>