Skip to content

Commit

Permalink
Fix audio_common_msgs for ROS2
Browse files Browse the repository at this point in the history
  • Loading branch information
ad-daniel committed Dec 23, 2022
1 parent 5092cc5 commit dae3cde
Show file tree
Hide file tree
Showing 6 changed files with 25 additions and 3 deletions.
2 changes: 2 additions & 0 deletions projects/opendr_ws_2/src/opendr_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"msg/OpenDRPose2DKeypoint.msg"
"msg/OpenDRPose3D.msg"
"msg/OpenDRPose3DKeypoint.msg"
"msg/AudioData.msg"
"msg/AudioInfo.msg"
"srv/OpenDRSingleObjectTracking.srv"
"srv/ImgToMesh.srv"
DEPENDENCIES std_msgs shape_msgs sensor_msgs vision_msgs
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
uint8[] data
12 changes: 12 additions & 0 deletions projects/opendr_ws_2/src/opendr_interface/msg/AudioInfo.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
# This message contains the audio meta data

# Number of channels
uint8 channels
# Sampling rate [Hz]
uint32 sample_rate
# Audio format (e.g. S16LE)
string sample_format
# Amount of audio data per second [bits/s]
uint32 bitrate
# Audio coding format (e.g. WAVE, MP3)
string coding_format
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,10 @@
from rclpy.node import Node
import message_filters
from sensor_msgs.msg import Image as ROS_Image
from audio_common_msgs.msg import AudioData
if os.environ.get('ROS_DISTRO').lower() in ['foxy', 'humble']:
from opendr_interface.msg import AudioData
else:
from audio_common_msgs.msg import AudioData
from vision_msgs.msg import Classification2D

from opendr_bridge import ROS2Bridge
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,14 @@
import argparse
import torch
import numpy as np
import os

import rclpy
from rclpy.node import Node
from audio_common_msgs.msg import AudioData
if os.environ.get('ROS_DISTRO').lower() in ['foxy', 'humble']:
from opendr_interface.msg import AudioData
else:
from audio_common_msgs.msg import AudioData
from vision_msgs.msg import Classification2D

from opendr_bridge import ROS2Bridge
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -315,7 +315,7 @@ def eval(self, val_dataset, val_loader=None, epoch=0, monte_carlo_dropout=True,
:type val_data_filename: str, optional
:param val_labels_filename: the file name of val labels which is placed in the dataset path.
:type val_labels_filename: str, optional
:param save_score: if set to True, it saves the classification score of all samples in differenc classes
:param save_score: if set to True, it saves the classification score of all samples in different classes
in a log file. Default to False.
:type save_score: bool, optional
:param wrong_file: if set to True, it saves the results of wrongly classified samples. Default to False.
Expand Down

0 comments on commit dae3cde

Please sign in to comment.