Skip to content

Commit

Permalink
Publish diagnostic
Browse files Browse the repository at this point in the history
  • Loading branch information
Tacha-S committed Dec 25, 2024
1 parent 06c280a commit d205f8a
Show file tree
Hide file tree
Showing 3 changed files with 29 additions and 4 deletions.
2 changes: 2 additions & 0 deletions audio_capture/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(audio_common_msgs REQUIRED)
find_package(diagnostic_updater REQUIRED)
find_package(PkgConfig)
pkg_check_modules(GST1.0 gstreamer-1.0 REQUIRED)
find_package(Boost REQUIRED COMPONENTS thread)
Expand All @@ -26,6 +27,7 @@ ament_target_dependencies(${PROJECT_NAME}
rclcpp
rclcpp_components
audio_common_msgs
diagnostic_updater
)

target_link_libraries(${PROJECT_NAME} ${GST1.0_LIBRARIES} ${Boost_LIBRARIES})
Expand Down
2 changes: 2 additions & 0 deletions audio_capture/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,15 @@

<build_depend>audio_common_msgs</build_depend>
<build_depend>boost</build_depend>
<build_depend>diagnostic_updater</build_depend>
<build_depend>rclcpp</build_depend>
<build_depend>rclcpp_components</build_depend>

<build_depend>libgstreamer1.0-dev</build_depend>
<build_depend>libgstreamer-plugins-base1.0-dev</build_depend>

<exec_depend>audio_common_msgs</exec_depend>
<exec_depend>diagnostic_updater</exec_depend>
<exec_depend>launch_xml</exec_depend>
<exec_depend>rclcpp</exec_depend>
<exec_depend>rclcpp_components</exec_depend>
Expand Down
29 changes: 25 additions & 4 deletions audio_capture/src/audio_capture_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@
#include <gst/app/gstappsink.h>
#include <boost/thread.hpp>

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <diagnostic_updater/publisher.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_components/register_node_macro.hpp>

Expand All @@ -17,7 +19,8 @@ namespace audio_capture
public:
AudioCaptureNode(const rclcpp::NodeOptions &options)
:
Node("audio_capture_node", options)
Node("audio_capture_node", options),
updater_(this)
{
gst_init(nullptr, nullptr);

Expand Down Expand Up @@ -55,9 +58,23 @@ namespace audio_capture
this->get_parameter("device", device);

_pub = this->create_publisher<audio_common_msgs::msg::AudioData>("audio", 10);
_pub_stamped = this->create_publisher<audio_common_msgs::msg::AudioDataStamped>("audio_stamped", 10);
_pub_info = this->create_publisher<audio_common_msgs::msg::AudioInfo>("audio_info", 1);

rclcpp::Publisher<audio_common_msgs::msg::AudioDataStamped>::SharedPtr pub_stamped =
this->create_publisher<audio_common_msgs::msg::AudioDataStamped>("audio_stamped", 10);

this->declare_parameter<double>("desired_rate", 100.0);
_desired_rate = this->get_parameter("desired_rate").as_double();
this->declare_parameter<double>("diagnostic_tolerance", 0.1);
auto tolerance = this->get_parameter("diagnostic_tolerance").as_double();

updater_.setHardwareID("microphone");
_diagnosed_pub_stamped =
std::make_shared<diagnostic_updater::DiagnosedPublisher<audio_common_msgs::msg::AudioDataStamped>>(
pub_stamped, updater_,
diagnostic_updater::FrequencyStatusParam(&_desired_rate, &_desired_rate, tolerance, 10),
diagnostic_updater::TimeStampStatusParam());

_loop = g_main_loop_new(NULL, false);
_pipeline = gst_pipeline_new("ros_pipeline");
GstClock *clock = gst_system_clock_obtain();
Expand Down Expand Up @@ -201,7 +218,7 @@ namespace audio_capture

void publishStamped( const audio_common_msgs::msg::AudioDataStamped &msg )
{
_pub_stamped->publish(msg);
_diagnosed_pub_stamped->publish(msg);
}

static GstFlowReturn onNewBuffer (GstAppSink *appsink, gpointer userData)
Expand Down Expand Up @@ -252,7 +269,6 @@ namespace audio_capture

private:
rclcpp::Publisher<audio_common_msgs::msg::AudioData>::SharedPtr _pub;
rclcpp::Publisher<audio_common_msgs::msg::AudioDataStamped>::SharedPtr _pub_stamped;
rclcpp::Publisher<audio_common_msgs::msg::AudioInfo>::SharedPtr _pub_info;

rclcpp::TimerBase::SharedPtr _timer_info;
Expand All @@ -264,6 +280,11 @@ namespace audio_capture
int _bitrate, _channels, _depth, _sample_rate;
GMainLoop *_loop;
std::string _format, _sample_format;

diagnostic_updater::Updater updater_;
double _desired_rate;
std::shared_ptr<diagnostic_updater::DiagnosedPublisher<audio_common_msgs::msg::AudioDataStamped>>
_diagnosed_pub_stamped;
};
}

Expand Down

0 comments on commit d205f8a

Please sign in to comment.