Skip to content
Snippets Groups Projects
Commit a46ce619 authored by Daniel Engelsons's avatar Daniel Engelsons
Browse files

Microphone Done

parent 9f7bcbfd
No related branches found
No related tags found
Loading
......@@ -22,9 +22,9 @@ namespace lhw_qi
LHW_QI_PUBLIC
explicit Microphone(const rclcpp::NodeOptions & options);
void initiate(qi::SessionPtr session, boost::shared_ptr<Microphone> microphone_ptr);
void initiateService(void);
void init(void);
virtual ~Microphone(void);
void process( const int & nbOfChannels,
void processRemote( const int & nbOfChannels,
const int & nbrOfSamplesByChannel,
const qi::AnyValue & timestamp,
const qi::AnyValue & buffer);
......
......@@ -16,7 +16,7 @@ namespace lhw_qi
pub_ = this->create_publisher<std_msgs::msg::Int16>("microphone_buffer", 1000);
}
QI_REGISTER_MT_OBJECT(Microphone, initiateService, process)
QI_REGISTER_MT_OBJECT(Microphone, init, processRemote)
Microphone::~Microphone(void)
{
......@@ -24,35 +24,37 @@ namespace lhw_qi
listener_.call<qi::AnyValue>("unsubscribe", "Microphone");
}
void Microphone::initiateService(void)
void Microphone::init(void)
{
listener_.call<qi::AnyValue>("setClientPreferences",
"Microphone",
48000,
0,
1);
listener_.call<qi::AnyValue>("subscribe", "Microphone");
}
void Microphone::initiate(qi::SessionPtr session, boost::shared_ptr<Microphone> microphone_ptr)
{
session_ = session;
RCUTILS_LOG_INFO("timestamp inne i initiate");
session_->waitForService("ALAudioDevice");
RCUTILS_LOG_INFO("initiate2");
listener_ = session_->service("ALAudioDevice");
session_->registerService("Microphone", qi::AnyObject( microphone_ptr ) );
RCUTILS_LOG_INFO("initiate3");
qi::AnyObject microphone = session_ -> service("Microphone");
RCUTILS_LOG_INFO("initiate4");
microphone.call<qi::AnyValue>("initiateService");
RCUTILS_LOG_INFO("initiate5");
microphone.call<qi::AnyValue>("init");
}
void Microphone::process( const int & nbOfChannels,
void Microphone::processRemote( const int & nbOfChannels,
const int & nbrOfSamplesByChannel,
const qi::AnyValue & timestamp,
const qi::AnyValue & buffer) {
......@@ -60,7 +62,7 @@ namespace lhw_qi
std::pair<char*, size_t> charBuffer = buffer.unwrap().asRaw();
//RCUTILS_LOG_INFO("buffer %s", qi::encodeJSON(qibuffer).c_str());
RCUTILS_LOG_INFO("timestamp %s", qi::encodeJSON(timestamp).c_str());
//RCUTILS_LOG_INFO("timestamp %s", qi::encodeJSON(timestamp).c_str());
auto msg = std_msgs::msg::Int16();
msg.data = *(signed short*) charBuffer.first;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment