This class describes an audio client.
More...
#include <libacoustic_touch.h>
|
class | ChucKPacketListener |
| This nested class describes a chuck packet listener. A nested class is also a member variable of the enclosing class and has the same access rights as the other members. More...
|
|
This class describes an audio client.
◆ AcousticTouchInterface()
AcousticTouchInterface::AcousticTouchInterface |
( |
string |
mde, |
|
|
bool |
withGUI |
|
) |
| |
Initiatializes the clients, then has a different behavior depending on the mode selected.
- Parameters
-
[in] | mde | The mode of the system. Options are 'train', 'classify' or just 'touch_activity'. |
[in] | amount | The amount of microphones. |
[in] | withGUI | To use or not Graphical interface to plot the features in real time. |
◆ ~AcousticTouchInterface()
AcousticTouchInterface::~AcousticTouchInterface |
( |
| ) |
|
Destroy the Acoustic Touch Interface:: Acoustic Touch Interface object.
◆ capacitiveCallback()
void AcousticTouchInterface::capacitiveCallback |
( |
const arduino_msgs::sensorStates::ConstPtr & |
msg | ) |
|
Receives and parses a ROS message containing the capacitive sensors' state.
- Parameters
-
◆ classifReadyCallback()
void AcousticTouchInterface::classifReadyCallback |
( |
const std_msgs::Empty::ConstPtr & |
msg | ) |
|
Changes once the classifier node has finished building its estimators.
- Parameters
-
◆ getShellOutput()
vector< std::string > AcousticTouchInterface::getShellOutput |
( |
const std::string |
cmd | ) |
|
Returns the output of a shell command as a vector.
- Parameters
-
- Returns
- The shell output.
◆ loadSettings()
void AcousticTouchInterface::loadSettings |
( |
| ) |
|
Loads settings and serves as a secondary initialization of attributes, after the constructor.
◆ oscCallback()
void AcousticTouchInterface::oscCallback |
( |
int |
mic_num | ) |
|
This function is meant to be in a thread. It initializes the OSC protocol listeners and waits for messages to process.
- Parameters
-
[in] | mic_num | The mic number |
◆ sendOscMsg()
void AcousticTouchInterface::sendOscMsg |
( |
string |
address, |
|
|
int |
msg |
|
) |
| |
Sends an osc message to ALL ChucK nodes.
- Parameters
-
[in] | address | The url address (e.g. "acoustic_touch/capacitive") |
[in] | msg | An integer containing the message |
◆ sendSrv()
void AcousticTouchInterface::sendSrv |
( |
| ) |
|
◆ setTrainLabels()
void AcousticTouchInterface::setTrainLabels |
( |
string |
label_name | ) |
|
Sets the service attributes.
- Parameters
-
[in] | label_name | The label name |
◆ showMenu()
void AcousticTouchInterface::showMenu |
( |
| ) |
|
◆ shutDown()
void AcousticTouchInterface::shutDown |
( |
| ) |
|
Sends a shutdown signal to all the system.
◆ aspin_
ros::AsyncSpinner AcousticTouchInterface::aspin_ |
|
private |
◆ cap_state_
int AcousticTouchInterface::cap_state_ |
|
private |
◆ capacitive_sub_
ros::Subscriber AcousticTouchInterface::capacitive_sub_ |
|
private |
◆ chuck_handler_
◆ chuck_listeners_
◆ class_labels_
XmlRpc::XmlRpcValue AcousticTouchInterface::class_labels_ |
|
private |
◆ classif_ready_sub_
ros::Subscriber AcousticTouchInterface::classif_ready_sub_ |
|
private |
◆ classif_state_
bool AcousticTouchInterface::classif_state_ |
|
private |
◆ client_
ros::ServiceClient AcousticTouchInterface::client_ |
|
private |
◆ gesture_end_pub_
ros::Publisher AcousticTouchInterface::gesture_end_pub_ |
|
private |
◆ gesture_start_pub_
ros::Publisher AcousticTouchInterface::gesture_start_pub_ |
|
private |
◆ ip_endpoints_
◆ label_names_
vector<string> AcousticTouchInterface::label_names_ |
|
private |
◆ loop_rate_
ros::Rate AcousticTouchInterface::loop_rate_ |
|
private |
◆ loud_noise_pub_
ros::Publisher AcousticTouchInterface::loud_noise_pub_ |
|
private |
◆ mic_amount_
int AcousticTouchInterface::mic_amount_ |
|
private |
◆ mics_
XmlRpc::XmlRpcValue AcousticTouchInterface::mics_ |
|
private |
◆ mode_
const string AcousticTouchInterface::mode_ |
|
private |
◆ nh_
ros::NodeHandle AcousticTouchInterface::nh_ |
|
private |
◆ osc_mutex_
mutex AcousticTouchInterface::osc_mutex_ |
|
private |
◆ osc_threads_
vector<thread> AcousticTouchInterface::osc_threads_ |
|
private |
◆ robot_
string AcousticTouchInterface::robot_ |
|
private |
◆ srv_
acoustic_touch_recognition::MenuOptions AcousticTouchInterface::srv_ |
|
private |
◆ udp_sockets_
◆ with_GUI_
bool AcousticTouchInterface::with_GUI_ |
|
private |
The documentation for this class was generated from the following files: