## 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
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
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
global_costmap:
- global_frame: /map
+ global_frame: map
robot_base_frame: base_footprint
static_map: true
publish_frequency: 1.0
# 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
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
<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>
-#!/usr/bin/ruby -w
+#!/usr/bin/ruby
require 'gst'
require 'pry'
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)
@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)
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
<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>