Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add services for get/set volume (new version of #97) #110

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,8 @@ set(
src/services/robot_config.cpp
src/services/set_language.cpp
src/services/get_language.cpp
src/services/set_volume.cpp
src/services/get_volume.cpp
)

set(
Expand Down
1 change: 1 addition & 0 deletions CMakeLists_catkin.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ find_package(catkin COMPONENTS
image_transport
kdl_parser
naoqi_bridge_msgs
nao_interaction_msgs
naoqi_libqi
naoqi_libqicore
robot_state_publisher
Expand Down
51 changes: 51 additions & 0 deletions src/helpers/driver_helpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -223,6 +223,57 @@ std::string& getLanguage( const qi::SessionPtr& session )
return language;
}

/** Function that sets volume for robot
*/
static std_srvs::Empty& setVolumeLocal( const qi::SessionPtr& session, nao_interaction_msgs::SetAudioMasterVolumeRequest req)
{
static qi::Url robot_url;

robot_url = session->url();

std::cout << "Receiving service call of setting volume" << std::endl;
qi::AnyObject p_audio_device = session->service("ALAudioDevice");
p_audio_device.call<void>("setOutputVolume", req.master_volume.data);
}

const bool& setVolume( const qi::SessionPtr& session, nao_interaction_msgs::SetAudioMasterVolumeRequest req)
{
try{
setVolumeLocal(session, req);
return true;
}
catch(const std::exception& e){
return false;
}
}

/** Function that gets volume for robot
*/
static int& getVolumeLocal( const qi::SessionPtr& session )
{
static qi::Url robot_url;
static int volume;

robot_url = session->url();

std::cout << "Receiving service call of getting volume" << std::endl;
qi::AnyObject p_audio_device = session->service("ALAudioDevice");
volume = p_audio_device.call<int>("getOutputVolume");
return volume;
}

const int& getVolume( const qi::SessionPtr& session)
{
static int volume;
try{
volume = getVolumeLocal(session);
return volume;
}
catch(const std::exception& e){
return volume;
}
}

} // driver
} // helpers
} // naoqi
9 changes: 9 additions & 0 deletions src/helpers/driver_helpers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,12 @@

#include <naoqi_bridge_msgs/SetString.h>

#include <nao_interaction_msgs/SetAudioMasterVolume.h>

#include <nao_interaction_msgs/GetAudioMasterVolume.h>

#include <std_srvs/Empty.h>

#include <qi/applicationsession.hpp>

namespace naoqi
Expand All @@ -42,6 +48,9 @@ bool& setLanguage( const qi::SessionPtr& session, naoqi_bridge_msgs::SetStringRe

std::string& getLanguage( const qi::SessionPtr& session );

const bool& setVolume( const qi::SessionPtr& session, nao_interaction_msgs::SetAudioMasterVolumeRequest req );

const int& getVolume( const qi::SessionPtr& session );
} // driver
} // helpers
} // naoqi
Expand Down
4 changes: 4 additions & 0 deletions src/naoqi_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,8 @@
#include "services/robot_config.hpp"
#include "services/set_language.hpp"
#include "services/get_language.hpp"
#include "services/set_volume.hpp"
#include "services/get_volume.hpp"

/*
* RECORDERS
Expand Down Expand Up @@ -893,6 +895,8 @@ void Driver::registerDefaultServices()
registerService( boost::make_shared<service::RobotConfigService>("get_robot_config", "/naoqi_driver/get_robot_config", sessionPtr_) );
registerService( boost::make_shared<service::SetLanguageService>("set_language", "/naoqi_driver/set_language", sessionPtr_) );
registerService( boost::make_shared<service::GetLanguageService>("get_language", "/naoqi_driver/get_language", sessionPtr_) );
registerService( boost::make_shared<service::SetVolumeService>("set volume service", "/naoqi_driver/set_master_volume", sessionPtr_) );
registerService( boost::make_shared<service::GetVolumeService>("get volume service", "/naoqi_driver/get_master_volume", sessionPtr_) );
}

std::vector<std::string> Driver::getAvailableConverters()
Expand Down
45 changes: 45 additions & 0 deletions src/services/get_volume.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
/*
* Copyright 2017 Aldebaran
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include "get_volume.hpp"
#include "../helpers/driver_helpers.hpp"

namespace naoqi
{
namespace service
{

GetVolumeService::GetVolumeService( const std::string& name, const std::string& topic, const qi::SessionPtr& session )
: name_(name),
topic_(topic),
session_(session)
{}

void GetVolumeService::reset( ros::NodeHandle& nh )
{
service_ = nh.advertiseService(topic_, &GetVolumeService::callback, this);
}

bool GetVolumeService::callback( nao_interaction_msgs::GetAudioMasterVolumeRequest& req, nao_interaction_msgs::GetAudioMasterVolumeResponse& resp )
{
resp.master_volume.data = helpers::driver::getVolume(session_);
return true;
}


}
}
67 changes: 67 additions & 0 deletions src/services/get_volume.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
/*
* Copyright 2017 Aldebaran
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/


#ifndef GET_VOLUME_SERVICE_HPP
#define GET_VOLUME_SERVICE_HPP

#include <iostream>

#include <ros/node_handle.h>
#include <ros/service_server.h>

#include <nao_interaction_msgs/GetAudioMasterVolume.h>
#include <qi/session.hpp>

namespace naoqi
{
namespace service
{

class GetVolumeService
{
public:
GetVolumeService( const std::string& name, const std::string& topic, const qi::SessionPtr& session );

~GetVolumeService(){};

std::string name() const
{
return name_;
}

std::string topic() const
{
return topic_;
}

void reset( ros::NodeHandle& nh );

bool callback( nao_interaction_msgs::GetAudioMasterVolumeRequest& req, nao_interaction_msgs::GetAudioMasterVolumeResponse& resp );


private:
const std::string name_;
const std::string topic_;

const qi::SessionPtr& session_;
ros::ServiceServer service_;
};

} // service
} // naoqi
#endif
50 changes: 50 additions & 0 deletions src/services/set_volume.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
/*
* Copyright 2017 Aldebaran
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include "set_volume.hpp"
#include "../helpers/driver_helpers.hpp"

namespace naoqi
{
namespace service
{

SetVolumeService::SetVolumeService( const std::string& name, const std::string& topic, const qi::SessionPtr& session )
: name_(name),
topic_(topic),
session_(session)
{}

void SetVolumeService::reset( ros::NodeHandle& nh )
{
service_ = nh.advertiseService(topic_, &SetVolumeService::callback, this);
}

bool SetVolumeService::callback( nao_interaction_msgs::SetAudioMasterVolumeRequest& req, nao_interaction_msgs::SetAudioMasterVolumeResponse& resp )
{
if (req.master_volume.data < 0 or req.master_volume.data > 100){
return true;
}
else{
helpers::driver::setVolume(session_, req);
return true;
}
}


}
}
67 changes: 67 additions & 0 deletions src/services/set_volume.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
/*
* Copyright 2017 Aldebaran
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/


#ifndef SET_VOLUME_SERVICE_HPP
#define SET_VOLUME_SERVICE_HPP

#include <iostream>

#include <ros/node_handle.h>
#include <ros/service_server.h>

#include <nao_interaction_msgs/SetAudioMasterVolume.h>
#include <qi/session.hpp>

namespace naoqi
{
namespace service
{

class SetVolumeService
{
public:
SetVolumeService( const std::string& name, const std::string& topic, const qi::SessionPtr& session );

~SetVolumeService(){};

std::string name() const
{
return name_;
}

std::string topic() const
{
return topic_;
}

void reset( ros::NodeHandle& nh );

bool callback( nao_interaction_msgs::SetAudioMasterVolumeRequest& req, nao_interaction_msgs::SetAudioMasterVolumeResponse& resp );


private:
const std::string name_;
const std::string topic_;

const qi::SessionPtr& session_;
ros::ServiceServer service_;
};

} // service
} // naoqi
#endif