Skip to content

Commit

Permalink
Merge branch 'master' into invert-mask-image
Browse files Browse the repository at this point in the history
  • Loading branch information
k-okada authored Apr 25, 2023
2 parents 4727a25 + 88b39cc commit 8e08f4d
Show file tree
Hide file tree
Showing 18 changed files with 133 additions and 28 deletions.
13 changes: 13 additions & 0 deletions audio_to_spectrogram/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -157,3 +157,16 @@ roslaunch audio_to_spectrogram sample_audio_to_spectrogram.launch
- `~spectrum` (`jsk_recognition_msgs/Spectrum`)

Spectrum data calculated from audio by FFT.

- ### Parameters
- `~plot_amp_min` (`Double`, default: `0.0`)

Minimum value of amplitude in plot

- `~plot_amp_max` (`Double`, default: `20.0`)

Maximum value of amplitude in plot

- `~queue_size` (`Int`, default: `1`)

Queue size of spectrum subscriber
1 change: 1 addition & 0 deletions audio_to_spectrogram/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
<exec_depend condition="$ROS_PYTHON_VERSION == 3">python3-matplotlib</exec_depend>
<exec_depend>sensor_msgs</exec_depend>

<test_depend>jsk_tools</test_depend>
<test_depend>roslaunch</test_depend>
<test_depend>rostest</test_depend>

Expand Down
19 changes: 18 additions & 1 deletion audio_to_spectrogram/scripts/audio_amplitude_plot.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,14 @@

from __future__ import division

from distutils.version import LooseVersion
import pkg_resources
import cv_bridge
from dynamic_reconfigure.server import Server
from jsk_topic_tools import ConnectionBasedTransport
import matplotlib
from audio_to_spectrogram import check_matplotlib_version; check_matplotlib_version()
matplotlib.use('Agg')
import matplotlib.pyplot as plt
import numpy as np
import rospy
Expand Down Expand Up @@ -42,10 +47,22 @@ def start_timer(self):
if rate == 0:
rospy.logwarn('You cannot set 0 as the rate; change it to 10.')
rate = 10
self.timer = rospy.Timer(rospy.Duration(1.0 / rate), self.timer_cb)

timer_kwargs = dict(
period=rospy.Duration(1.0 / rate),
callback=self.timer_cb,
oneshot=False,
)
if (LooseVersion(pkg_resources.get_distribution('rospy').version) >=
LooseVersion('1.12.0')) and rospy.get_param('/use_sim_time', None):
# on >=kinetic, it raises ROSTimeMovedBackwardsException
# when we use rosbag play --loop.
timer_kwargs['reset'] = True
self.timer = rospy.Timer(**timer_kwargs)

def stop_timer(self):
self.timer.shutdown()
self.timer = None

def subscribe(self):
self.audio_buffer.subscribe()
Expand Down
15 changes: 14 additions & 1 deletion audio_to_spectrogram/scripts/audio_to_spectrum.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

import numpy as np
import rospy
from distutils.version import LooseVersion
import pkg_resources

from audio_common_msgs.msg import AudioData
from jsk_recognition_msgs.msg import Spectrum
Expand Down Expand Up @@ -45,7 +47,18 @@ def __init__(self):
'~spectrum', Spectrum, queue_size=1)
self.pub_spectrum_filtered = rospy.Publisher(
'~spectrum_filtered', Spectrum, queue_size=1)
rospy.Timer(rospy.Duration(1. / self.fft_exec_rate), self.timer_cb)

timer_kwargs = dict(
period=rospy.Duration(1.0 / self.fft_exec_rate),
callback=self.timer_cb,
oneshot=False,
)
if (LooseVersion(pkg_resources.get_distribution('rospy').version) >=
LooseVersion('1.12.0')) and rospy.get_param('/use_sim_time', None):
# on >=kinetic, it raises ROSTimeMovedBackwardsException
# when we use rosbag play --loop.
timer_kwargs['reset'] = True
self.timer = rospy.Timer(**timer_kwargs)

def timer_cb(self, timer):
if len(self.audio_buffer) != self.audio_buffer.audio_buffer_len:
Expand Down
19 changes: 16 additions & 3 deletions audio_to_spectrogram/scripts/spectrum_plot.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,9 @@

import cv_bridge
from jsk_topic_tools import ConnectionBasedTransport
import matplotlib
from audio_to_spectrogram import check_matplotlib_version; check_matplotlib_version()
matplotlib.use('Agg')
import matplotlib.pyplot as plt
import numpy as np
import rospy
Expand All @@ -19,13 +22,22 @@ class SpectrumPlot(ConnectionBasedTransport):

def __init__(self):
super(SpectrumPlot, self).__init__()
self.plot_amp_min = rospy.get_param('~plot_amp_min', 0.0)
self.plot_amp_max = rospy.get_param('~plot_amp_max', 20.0)
self.queue_size = rospy.get_param('~queue_size', 1)
# Set matplotlib config
self.fig = plt.figure(figsize=(8, 5))
self.fig.suptitle('Spectrum plot', size=12)
self.fig.subplots_adjust(left=0.1, right=0.95, top=0.90, bottom=0.1,
wspace=0.2, hspace=0.6)
self.ax = self.fig.add_subplot(1, 1, 1)
self.ax.grid(True)
# self.fig.suptitle('Spectrum plot', size=12)
self.ax.set_title('Spectrum plot', fontsize=12)
# Use self.ax.set_title() instead of
# self.fig.suptitle() to use self.fig.tight_layout()
# preventing characters from being cut off
# cf. https://tm23forest.com/contents/matplotlib-tightlayout-with-figure-suptitle
# https://matplotlib.org/2.2.4/tutorials/intermediate/tight_layout_guide.html
self.ax.set_xlabel('Frequency [Hz]', fontsize=12)
self.ax.set_ylabel('Amplitude', fontsize=12)
self.line, = self.ax.plot([0, 0], label='Amplitude of Spectrum')
Expand All @@ -35,7 +47,7 @@ def __init__(self):

def subscribe(self):
self.sub_spectrum = rospy.Subscriber(
'~spectrum', Spectrum, self._cb, queue_size=1000)
'~spectrum', Spectrum, self._cb, queue_size=self.queue_size)

def unsubscribe(self):
self.sub_spectrum.unregister()
Expand All @@ -46,8 +58,9 @@ def _cb(self, msg):
self.freq = np.array(msg.frequency)
self.line.set_data(self.freq, self.amp)
self.ax.set_xlim((self.freq.min(), self.freq.max()))
self.ax.set_ylim((0.0, 20))
self.ax.set_ylim((self.plot_amp_min, self.plot_amp_max))
self.ax.legend(loc='upper right')
self.fig.tight_layout()
if self.pub_img.get_num_connections() > 0:
bridge = cv_bridge.CvBridge()
img = convert_matplotlib_to_img(self.fig)
Expand Down
18 changes: 14 additions & 4 deletions audio_to_spectrogram/scripts/spectrum_to_spectrogram.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
from cv_bridge import CvBridge
import numpy as np
import rospy
from distutils.version import LooseVersion
import pkg_resources

from jsk_recognition_msgs.msg import Spectrum
from sensor_msgs.msg import Image
Expand Down Expand Up @@ -34,10 +36,18 @@ def __init__(self):
'~spectrogram', Image, queue_size=1)
publish_rate = rospy.get_param(
'~publish_rate', float(self.image_width / self.spectrogram_period))
rospy.Timer(
rospy.Duration(
1.0 / publish_rate),
self.timer_cb)

timer_kwargs = dict(
period=rospy.Duration(1.0 / publish_rate),
callback=self.timer_cb,
oneshot=False,
)
if (LooseVersion(pkg_resources.get_distribution('rospy').version) >=
LooseVersion('1.12.0')) and rospy.get_param('/use_sim_time', None):
# on >=kinetic, it raises ROSTimeMovedBackwardsException
# when we use rosbag play --loop.
timer_kwargs['reset'] = True
self.timer = rospy.Timer(**timer_kwargs)
self.bridge = CvBridge()

def audio_cb(self, msg):
Expand Down
5 changes: 3 additions & 2 deletions audio_to_spectrogram/src/audio_to_spectrogram/__init__.py
Original file line number Diff line number Diff line change
@@ -1,2 +1,3 @@
from .audio_buffer import AudioBuffer
from .convert_matplotlib import convert_matplotlib_to_img
from audio_to_spectrogram.audio_buffer import AudioBuffer
from audio_to_spectrogram.compat import check_matplotlib_version
from audio_to_spectrogram.convert_matplotlib import convert_matplotlib_to_img
25 changes: 25 additions & 0 deletions audio_to_spectrogram/src/audio_to_spectrogram/compat.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
import os
import subprocess
import warnings

import matplotlib


def check_matplotlib_version(
python_version=os.getenv('ROS_PYTHON_VERSION')):
if python_version == '2':
python = 'python'
else:
python = 'python{}'.format(python_version)
out = subprocess.check_output(
['dpkg', '-L', '{}-matplotlib'.format(python)])
if isinstance(out, bytes):
out = out.decode('utf-8')
matplotlib_filelists = out.split()
if os.path.dirname(matplotlib.__file__) in matplotlib_filelists:
return True
else:
warnings.warn(
"It looks like you are using pip's matplotlib. "
"Apt's matplotlib is recommended.")
return False
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@

import numpy as np
import PIL
import PIL.Image


def convert_matplotlib_to_img(fig):
Expand Down
4 changes: 4 additions & 0 deletions audio_to_spectrogram/test/audio_to_spectrogram.test
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,10 @@
<rosparam>
topic_0: /spectrum_to_spectrogram/spectrogram
timeout_0: 30
topic_1: /audio_amplitude_plot/output/viz
timeout_1: 30
topic_2: /spectrum_plot/output/viz
timeout_2: 30
</rosparam>
</test>

Expand Down
2 changes: 1 addition & 1 deletion doc/jsk_perception/nodes/aws_detect_faces.rst
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ Subscribing Topic
Publishing Topic
----------------

* ``~faces`` (``opencv_msgs/FaceArrayStamped``)
* ``~faces`` (``opencv_apps/FaceArrayStamped``)

Detected face positions, facial landmarks, emotions, presence of beard, sunglasses, and so on.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,6 @@ Sample is `sample_rect_array_in_panorama_to_bounding_box_array.launch`

## Subscribing Topics

* `~panorama_image` (`sensor_msgs/Image`)

Panorama image topic.

* `~panorama_info` (`jsk_recognition_msgs/PanoramaInfo`)

Panorama info topic.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,22 +50,22 @@ def __init__(self):
self._dimensions_labels = rospy.get_param( '~dimensions_labels', {} )
self._duration_timeout = rospy.get_param( '~duration_timeout', 0.05 )

try:
msg_panorama_image = rospy.wait_for_message(
'~panorama_image', Image, 10)
msg_panorama_info = rospy.wait_for_message(
'~panorama_info', PanoramaInfo, 10)
except (rospy.ROSException, rospy.ROSInterruptException) as e:
rospy.logerr('{}'.format(e))
sys.exit(1)
msg_panorama_info = None
while (not rospy.is_shutdown() and msg_panorama_info is None):
try:
msg_panorama_info = rospy.wait_for_message(
'~panorama_info', PanoramaInfo, 10)
except (rospy.ROSException, rospy.ROSInterruptException) as e:
rospy.logerr('~panorama_info is not subscribed...')
rospy.logerr('waiting ~panorama_info for more 10 seconds')

self._frame_panorama = msg_panorama_info.header.frame_id
self._theta_min = msg_panorama_info.theta_min
self._theta_max = msg_panorama_info.theta_max
self._phi_min = msg_panorama_info.phi_min
self._phi_max = msg_panorama_info.phi_max
self._image_height = msg_panorama_image.height
self._image_width = msg_panorama_image.width
self._image_height = msg_panorama_info.image_height
self._image_width = msg_panorama_info.image_width

self._tf_buffer = tf2_ros.Buffer()
self._tf_listener = tf2_ros.TransformListener(self._tf_buffer)
Expand Down
2 changes: 2 additions & 0 deletions jsk_perception/sample/sample_dual_fisheye_to_panorama.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
<arg name="fovd" default="185.0" doc="Camera's Field of View [degree]" />
<arg name="save_unwarped" default="false" doc="Save unwarped fisheye images. This is useful to create MLS grids." />
<arg name="resolution_mode" default="high" doc="Resolution mode, 'high' or 'low'" />
<arg name="vital_rate" default="1.0" doc="Rate to determine if the nodelet is in health." />
<arg name="image_transport" default="raw"/>

<node name="dual_fisheye_to_panorama"
Expand All @@ -21,6 +22,7 @@
command="load"
file="$(find jsk_perception)/config/dual_fisheye_to_panorama/$(arg resolution_mode)_resolution_config.yaml"
subst_value="true"/>
<param name="vital_rate" value="$(arg vital_rate)" />
</node>

<group if="$(arg gui)">
Expand Down
2 changes: 2 additions & 0 deletions jsk_perception/sample/sample_insta360_air.launch
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
<arg name="panorama_resolution_mode" default="high" />
<arg name="panorama_image_transport" default="raw"/>

<arg name="vital_rate" default="1.0" />
<arg name="gui" default="true" />

<!-- Publish camera image -->
Expand Down Expand Up @@ -101,6 +102,7 @@
<arg name="save_unwarped" value="$(arg save_unwarped)" />
<arg name="resolution_mode" value="$(arg panorama_resolution_mode)" />
<arg name="image_transport" value="$(arg panorama_image_transport)" />
<arg name="vital_rate" value="$(arg vital_rate)" />
</include>

<group if="$(arg gui)">
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,6 @@
type="rect_array_in_panorama_to_bounding_box_array.py"
name="rect_array_in_panorama_to_bounding_box_array"
>
<remap from="~panorama_image" to="$(arg INPUT_PANORAMA_IMAGE)" />
<remap from="~panorama_info" to="$(arg INPUT_PANORAMA_INFO)" />
<remap from="~input_class" to="$(arg INPUT_CLASS)" />
<remap from="~input_rects" to="$(arg INPUT_RECTS)" />
Expand Down
2 changes: 2 additions & 0 deletions jsk_perception/src/dual_fisheye_to_panorama.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,8 @@ namespace jsk_perception
msg_panorama_info_.theta_max = M_PI;
msg_panorama_info_.phi_min = -M_PI;
msg_panorama_info_.phi_max = M_PI;
msg_panorama_info_.image_height = output_image_height_;
msg_panorama_info_.image_width = output_image_width_;

onInitPostProcess();
}
Expand Down
8 changes: 7 additions & 1 deletion jsk_recognition_msgs/msg/PanoramaInfo.msg
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,13 @@ std_msgs/Header header
string projection_model

#######################################################################
# Field of View Parameters #
# Image shape info #
#######################################################################
uint32 image_height
uint32 image_width

#######################################################################
# Field of View Parameters #
#######################################################################
float64 theta_min
float64 theta_max
Expand Down

0 comments on commit 8e08f4d

Please sign in to comment.