Transférer les fichiers vers 'Code_Final'
This commit is contained in:
parent
806d21b00b
commit
4f66ded641
3 changed files with 879 additions and 0 deletions
225
Code_Final/CMakeLists.txt
Normal file
225
Code_Final/CMakeLists.txt
Normal file
|
@ -0,0 +1,225 @@
|
||||||
|
cmake_minimum_required(VERSION 3.0.2)
|
||||||
|
project(localisation CXX)
|
||||||
|
|
||||||
|
## Compile as C++11, supported in ROS Kinetic and newer
|
||||||
|
# add_compile_options(-std=c++11)
|
||||||
|
|
||||||
|
## Find catkin macros and libraries
|
||||||
|
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
|
||||||
|
## is used, also find other catkin packages
|
||||||
|
find_package(catkin REQUIRED COMPONENTS
|
||||||
|
roscpp
|
||||||
|
)
|
||||||
|
find_package(PkgConfig)
|
||||||
|
pkg_check_modules(ALSA alsa REQUIRED)
|
||||||
|
|
||||||
|
## System dependencies are found with CMake's conventions
|
||||||
|
# find_package(Boost REQUIRED COMPONENTS system)
|
||||||
|
|
||||||
|
|
||||||
|
## Uncomment this if the package has a setup.py. This macro ensures
|
||||||
|
## modules and global scripts declared therein get installed
|
||||||
|
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
|
||||||
|
# catkin_python_setup()
|
||||||
|
|
||||||
|
################################################
|
||||||
|
## Declare ROS messages, services and actions ##
|
||||||
|
################################################
|
||||||
|
|
||||||
|
## To declare and build messages, services or actions from within this
|
||||||
|
## package, follow these steps:
|
||||||
|
## * Let MSG_DEP_SET be the set of packages whose message types you use in
|
||||||
|
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
|
||||||
|
## * In the file package.xml:
|
||||||
|
## * add a build_depend tag for "message_generation"
|
||||||
|
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
|
||||||
|
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
|
||||||
|
## but can be declared for certainty nonetheless:
|
||||||
|
## * add a exec_depend tag for "message_runtime"
|
||||||
|
## * In this file (CMakeLists.txt):
|
||||||
|
## * add "message_generation" and every package in MSG_DEP_SET to
|
||||||
|
## find_package(catkin REQUIRED COMPONENTS ...)
|
||||||
|
## * add "message_runtime" and every package in MSG_DEP_SET to
|
||||||
|
## catkin_package(CATKIN_DEPENDS ...)
|
||||||
|
## * uncomment the add_*_files sections below as needed
|
||||||
|
## and list every .msg/.srv/.action file to be processed
|
||||||
|
## * uncomment the generate_messages entry below
|
||||||
|
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
|
||||||
|
|
||||||
|
## Generate messages in the 'msg' folder
|
||||||
|
# add_message_files(
|
||||||
|
# FILES
|
||||||
|
# Message1.msg
|
||||||
|
# Message2.msg
|
||||||
|
# )
|
||||||
|
|
||||||
|
## Generate services in the 'srv' folder
|
||||||
|
# add_service_files(
|
||||||
|
# FILES
|
||||||
|
# Service1.srv
|
||||||
|
# Service2.srv
|
||||||
|
# )
|
||||||
|
|
||||||
|
## Generate actions in the 'action' folder
|
||||||
|
# add_action_files(
|
||||||
|
# FILES
|
||||||
|
# Action1.action
|
||||||
|
# Action2.action
|
||||||
|
# )
|
||||||
|
|
||||||
|
## Generate added messages and services with any dependencies listed here
|
||||||
|
# generate_messages(
|
||||||
|
# DEPENDENCIES
|
||||||
|
# std_msgs # Or other packages containing msgs
|
||||||
|
# )
|
||||||
|
|
||||||
|
################################################
|
||||||
|
## Declare ROS dynamic reconfigure parameters ##
|
||||||
|
################################################
|
||||||
|
|
||||||
|
## To declare and build dynamic reconfigure parameters within this
|
||||||
|
## package, follow these steps:
|
||||||
|
## * In the file package.xml:
|
||||||
|
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
|
||||||
|
## * In this file (CMakeLists.txt):
|
||||||
|
## * add "dynamic_reconfigure" to
|
||||||
|
## find_package(catkin REQUIRED COMPONENTS ...)
|
||||||
|
## * uncomment the "generate_dynamic_reconfigure_options" section below
|
||||||
|
## and list every .cfg file to be processed
|
||||||
|
|
||||||
|
## Generate dynamic reconfigure parameters in the 'cfg' folder
|
||||||
|
# generate_dynamic_reconfigure_options(
|
||||||
|
# cfg/DynReconf1.cfg
|
||||||
|
# cfg/DynReconf2.cfg
|
||||||
|
# )
|
||||||
|
|
||||||
|
###################################
|
||||||
|
## catkin specific configuration ##
|
||||||
|
###################################
|
||||||
|
## The catkin_package macro generates cmake config files for your package
|
||||||
|
## Declare things to be passed to dependent projects
|
||||||
|
## INCLUDE_DIRS: uncomment this if your package contains header files
|
||||||
|
## LIBRARIES: libraries you create in this project that dependent projects also need
|
||||||
|
## CATKIN_DEPENDS: catkin_packages dependent projects also need
|
||||||
|
## DEPENDS: system dependencies of this project that dependent projects also need
|
||||||
|
catkin_package(
|
||||||
|
# INCLUDE_DIRS include
|
||||||
|
# LIBRARIES localisation
|
||||||
|
# CATKIN_DEPENDS roscpp
|
||||||
|
# DEPENDS system_lib
|
||||||
|
)
|
||||||
|
|
||||||
|
###########
|
||||||
|
## Build ##
|
||||||
|
###########
|
||||||
|
|
||||||
|
## Specify additional locations of header files
|
||||||
|
## Your package locations should be listed before other locations
|
||||||
|
include_directories(
|
||||||
|
# include
|
||||||
|
${catkin_INCLUDE_DIRS}
|
||||||
|
${ALSA_LIBRARIES}
|
||||||
|
${ALSA_CFLAGS_OTHER}
|
||||||
|
${ALSA_INCLUDE_DIRS}
|
||||||
|
)
|
||||||
|
|
||||||
|
## Declare a C++ library
|
||||||
|
# add_library(${PROJECT_NAME}
|
||||||
|
# src/${PROJECT_NAME}/localisation.cpp
|
||||||
|
# )
|
||||||
|
|
||||||
|
## Add cmake target dependencies of the library
|
||||||
|
## as an example, code may need to be generated before libraries
|
||||||
|
## either from message generation or dynamic reconfigure
|
||||||
|
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||||
|
|
||||||
|
## Declare a C++ executable
|
||||||
|
## With catkin_make all packages are built within a single CMake context
|
||||||
|
## The recommended prefix ensures that target names across packages don't collide
|
||||||
|
add_executable(${localisation}localisation180 src/Localisation180.cpp)
|
||||||
|
add_executable(${localisation}localisation360 src/Localisation360.cpp)
|
||||||
|
|
||||||
|
|
||||||
|
target_link_libraries (localisation180 ${ALSA_LIBRARIES})
|
||||||
|
#localisation360 ${ALSA_LIBRARIES})
|
||||||
|
target_compile_options(localisation180 PUBLIC ${ALSA_CFLAGS_OTHER})
|
||||||
|
#localisation360 PUBLIC ${ALSA_CFLAGS_OTHER})
|
||||||
|
target_include_directories(localisation180 PUBLIC ${ALSA_INCLUDE_DIRS})
|
||||||
|
#localisation360 PUBLIC ${ALSA_INCLUDE_DIRS})
|
||||||
|
target_link_libraries (localisation180 ${catkin_LIBRARIES})
|
||||||
|
#localisation360 ${catkin_LIBRARIES})
|
||||||
|
|
||||||
|
target_link_libraries (localisation360 ${ALSA_LIBRARIES})
|
||||||
|
target_compile_options(localisation360 PUBLIC ${ALSA_CFLAGS_OTHER})
|
||||||
|
target_include_directories(localisation360 PUBLIC ${ALSA_INCLUDE_DIRS})
|
||||||
|
target_link_libraries (localisation360 ${catkin_LIBRARIES})
|
||||||
|
|
||||||
|
## Rename C++ executable without prefix
|
||||||
|
## The above recommended prefix causes long target names, the following renames the
|
||||||
|
## target back to the shorter version for ease of user use
|
||||||
|
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
|
||||||
|
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
|
||||||
|
|
||||||
|
## Add cmake target dependencies of the executable
|
||||||
|
## same as for the library above
|
||||||
|
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||||
|
|
||||||
|
## Specify libraries to link a library or executable target against
|
||||||
|
# target_link_libraries(${PROJECT_NAME}_node
|
||||||
|
# ${catkin_LIBRARIES}
|
||||||
|
# )
|
||||||
|
|
||||||
|
#############
|
||||||
|
## Install ##
|
||||||
|
#############
|
||||||
|
|
||||||
|
# all install targets should use catkin DESTINATION variables
|
||||||
|
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
|
||||||
|
|
||||||
|
## Mark executable scripts (Python etc.) for installation
|
||||||
|
## in contrast to setup.py, you can choose the destination
|
||||||
|
# catkin_install_python(PROGRAMS
|
||||||
|
# scripts/my_python_script
|
||||||
|
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||||
|
# )
|
||||||
|
|
||||||
|
## Mark executables for installation
|
||||||
|
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
|
||||||
|
# install(TARGETS ${PROJECT_NAME}_node
|
||||||
|
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||||
|
# )
|
||||||
|
|
||||||
|
## Mark libraries for installation
|
||||||
|
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
|
||||||
|
# install(TARGETS ${PROJECT_NAME}
|
||||||
|
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||||
|
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||||
|
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
|
||||||
|
# )
|
||||||
|
|
||||||
|
## Mark cpp header files for installation
|
||||||
|
# install(DIRECTORY include/${PROJECT_NAME}/
|
||||||
|
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
|
||||||
|
# FILES_MATCHING PATTERN "*.h"
|
||||||
|
# PATTERN ".svn" EXCLUDE
|
||||||
|
# )
|
||||||
|
|
||||||
|
## Mark other files for installation (e.g. launch and bag files, etc.)
|
||||||
|
# install(FILES
|
||||||
|
# # myfile1
|
||||||
|
# # myfile2
|
||||||
|
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
|
||||||
|
# )
|
||||||
|
|
||||||
|
#############
|
||||||
|
## Testing ##
|
||||||
|
#############
|
||||||
|
|
||||||
|
## Add gtest based cpp test target and link libraries
|
||||||
|
# catkin_add_gtest(${PROJECT_NAME}-test test/test_localisation.cpp)
|
||||||
|
# if(TARGET ${PROJECT_NAME}-test)
|
||||||
|
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
|
||||||
|
# endif()
|
||||||
|
|
||||||
|
## Add folders to be run by python nosetests
|
||||||
|
# catkin_add_nosetests(test)
|
270
Code_Final/Localisation180.cpp
Normal file
270
Code_Final/Localisation180.cpp
Normal file
|
@ -0,0 +1,270 @@
|
||||||
|
#include <iostream>
|
||||||
|
using namespace std;
|
||||||
|
|
||||||
|
// #include <ros/ros.h>
|
||||||
|
#include "/opt/ros/kinetic/include/ros/ros.h"
|
||||||
|
#include <std_msgs/Float32.h>
|
||||||
|
#include <geometry_msgs/Twist.h>
|
||||||
|
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <math.h>
|
||||||
|
#include <limits.h>
|
||||||
|
#include <alsa/asoundlib.h>
|
||||||
|
#include "/usr/include/alsa/asoundlib.h"
|
||||||
|
#include <ros/publisher.h>
|
||||||
|
//#include "/opt/ros/kinetic/share/std_msgs/msg/Float64.msg"
|
||||||
|
|
||||||
|
//#define SAMPLE_TYPE float
|
||||||
|
//#define SAMPLE_TYPE_ALSA SND_PCM_FORMAT_FLOAT_LE
|
||||||
|
|
||||||
|
#define SAMPLE_TYPE short //sample type = type d'echantillon
|
||||||
|
#define SAMPLE_TYPE_ALSA SND_PCM_FORMAT_S16_LE
|
||||||
|
|
||||||
|
|
||||||
|
//float lin[3]= [2.0,0.0,0.0] ;
|
||||||
|
//float th[3]= [0.0,0.0,0.0] ;
|
||||||
|
float th;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* classe permettant de calculer la moyenne glissante du signal
|
||||||
|
*/
|
||||||
|
class MoyenneGlissante {
|
||||||
|
int _nbDeValeursPrMoy;
|
||||||
|
int _nbDeValeurs;
|
||||||
|
float _mean;
|
||||||
|
|
||||||
|
public:
|
||||||
|
MoyenneGlissante(int nbDeValeursPrMoy) {
|
||||||
|
_nbDeValeursPrMoy = nbDeValeursPrMoy;
|
||||||
|
_mean = 0;
|
||||||
|
_nbDeValeurs = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void nvelleValeur(SAMPLE_TYPE v) {
|
||||||
|
if (_nbDeValeurs < _nbDeValeursPrMoy)
|
||||||
|
_nbDeValeurs++;
|
||||||
|
_mean = ((_mean * (_nbDeValeurs - 1)) + v) / (float)_nbDeValeurs;
|
||||||
|
}
|
||||||
|
|
||||||
|
SAMPLE_TYPE getMean() {
|
||||||
|
return (SAMPLE_TYPE) _mean;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Cette classe calcule la direction du son entendu
|
||||||
|
*
|
||||||
|
*
|
||||||
|
* Elle utilise 2 microphones et calcule la différence de temps d'arrivée des sons entre eux pour
|
||||||
|
* estimer la localisation de la source sonore.
|
||||||
|
*/
|
||||||
|
class Localisation {
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Décalage maximum entre le micro droit et gauche en nombre d'échantillons.
|
||||||
|
* Cela dépend généralement de la fréquence d'échantillonnage et de la distance entre
|
||||||
|
* microphones
|
||||||
|
*/
|
||||||
|
static const int _nbEchantillonsDiffMax = 13; //difference max du nombre d'echantillons
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Taille du tampon sur laquelle nous allons essayer de localiser le son.
|
||||||
|
* Ceci est un certain nombre d'échantillons, et dépend de la fréquence d'échantillonnage et de la vitesse de
|
||||||
|
* changement de loc son que nous voulons détecter. Des valeurs plus faibles signifient le calcul du son
|
||||||
|
* se fait plus souvent, mais la précision est assez faible car nous calculons sur une très petite tranche de
|
||||||
|
* du son.
|
||||||
|
*/
|
||||||
|
static const int _TailleTampon = 4096;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Prenez un point pour la localisation du son est Niveau> 105% du Niveau moyen. Cela permet de calculer la
|
||||||
|
* localisation du son uniquement pour les sons "significatifs", pas le bruit de fond.
|
||||||
|
*/
|
||||||
|
static constexpr float _NiveauSonMin = 1.1f; //f de 1.05f signifie :float constant with value of 1.05
|
||||||
|
|
||||||
|
/**
|
||||||
|
* sound speed in meters per seconds
|
||||||
|
*/
|
||||||
|
static constexpr float _Vson = 344;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* sound sampling rate in Hz
|
||||||
|
*/
|
||||||
|
unsigned int _TauxEchantillonnageSon;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Distance between microphones in meters
|
||||||
|
*/
|
||||||
|
static constexpr float _DistanceMic = 0.05f;//5 cm de distance entre les deux microphones
|
||||||
|
|
||||||
|
/** An utility to compute the running average of sound power */
|
||||||
|
MoyenneGlissante* _MoyNivSonore;
|
||||||
|
|
||||||
|
/** ALSA sound input handle */
|
||||||
|
snd_pcm_t* _capture_handle;
|
||||||
|
|
||||||
|
/** sound samples input buffer */
|
||||||
|
SAMPLE_TYPE _TamponDroit[_TailleTampon];
|
||||||
|
SAMPLE_TYPE _TamponGauche[_TailleTampon];
|
||||||
|
|
||||||
|
public:
|
||||||
|
Localisation() {
|
||||||
|
_MoyNivSonore = new MoyenneGlissante(50);
|
||||||
|
_TauxEchantillonnageSon = 44100;
|
||||||
|
|
||||||
|
// sampling: 2 chanels, 44 KHz, 16 bits.
|
||||||
|
int err;
|
||||||
|
snd_pcm_hw_params_t* hw_params;
|
||||||
|
|
||||||
|
// ideally use "hw:0,0" for embedded, to limit processing. But check if card support our needs...
|
||||||
|
const char* CarteSon = "plughw:0,0";
|
||||||
|
if ((err = snd_pcm_open(&_capture_handle, CarteSon, SND_PCM_STREAM_CAPTURE, 0)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible d'ouvrir le peripherique audio %s (%s)\n", CarteSon,snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_malloc(&hw_params)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible d'allouer la structure des paramètres matériels (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_any(_capture_handle, hw_params)) < 0) {
|
||||||
|
fprintf(stderr,"Impossible d'initialiser la structure des paramètres matériels (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_set_access(_capture_handle, hw_params,SND_PCM_ACCESS_RW_NONINTERLEAVED)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir le type d'acces (%s)\n", snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_set_format(_capture_handle, hw_params,SAMPLE_TYPE_ALSA)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir le format d'echantillonnage (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_set_rate_near(_capture_handle, hw_params,&_TauxEchantillonnageSon, 0)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir le taux d'echantillonnage (%s)\n", snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_set_channels(_capture_handle, hw_params, 2))< 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir le nombre de canaux (%s)\n", snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params(_capture_handle, hw_params)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir les parametres (%s)\n", snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
snd_pcm_hw_params_free(hw_params);
|
||||||
|
|
||||||
|
if ((err = snd_pcm_prepare(_capture_handle)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de preparer l'interface audio pour utilisation (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Clean exit */
|
||||||
|
~Localisation() {
|
||||||
|
snd_pcm_close(_capture_handle);
|
||||||
|
delete _MoyNivSonore;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Boucle principale: lit un tampon, calcule la localisation de la source sonore, fait une itération.
|
||||||
|
*/
|
||||||
|
void run() {
|
||||||
|
//while (true) {
|
||||||
|
TraitementSonsSuivants();
|
||||||
|
//}
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
/**
|
||||||
|
* C'est le cœur de la localisation de la source sonore: il prend les sons échantillonnés
|
||||||
|
* Droit / Gauche, et calcule leurs différences tout en retardant de plus en plus un canal.<br/>
|
||||||
|
* => le retard pour lequel la différence est minime est le vrai retard
|
||||||
|
* entre les sons Droit / Gauche, dont on peut déduire la source sonore
|
||||||
|
* localisation
|
||||||
|
*/
|
||||||
|
void TraitementSonsSuivants() {
|
||||||
|
SAMPLE_TYPE* bufs[2];
|
||||||
|
bufs[0] = _TamponDroit;
|
||||||
|
bufs[1] = _TamponGauche;
|
||||||
|
int err;
|
||||||
|
if ((err = snd_pcm_readn(_capture_handle, (void**) bufs, _TailleTampon))!= _TailleTampon) {
|
||||||
|
fprintf(stderr, "Echec de la lecture de l'interface audio (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
// compute the sound level (i.e. "loudness" of the sound):
|
||||||
|
SAMPLE_TYPE Niveau = CalculNiv(_TamponDroit, _TamponGauche);
|
||||||
|
// update the average sound level with this new measure:
|
||||||
|
_MoyNivSonore->nvelleValeur(Niveau);
|
||||||
|
// relative sound level of this sample compared to average:
|
||||||
|
float NivRelatif = (float) Niveau / (float) _MoyNivSonore->getMean();
|
||||||
|
//cout << "level " << level << ", relative " << NivRelatif << endl;
|
||||||
|
|
||||||
|
int minDiff = INT_MAX;
|
||||||
|
int minDiffTime = -1;
|
||||||
|
// glisse sur l'axe du temps pour trouver la différence sonore minimum entre les microphones Droit et Gauche
|
||||||
|
for (int t = -_nbEchantillonsDiffMax; t < _nbEchantillonsDiffMax; t++) {
|
||||||
|
// calcule la somme des différences pour simuler une mesure de corrélation croisée:
|
||||||
|
int diff = 0;
|
||||||
|
for (int i = _nbEchantillonsDiffMax; i < _TailleTampon - _nbEchantillonsDiffMax - 1; i++) {
|
||||||
|
diff += abs(_TamponGauche[i] - _TamponDroit[i + t]);
|
||||||
|
}
|
||||||
|
if (diff < minDiff) {
|
||||||
|
minDiff = diff;
|
||||||
|
minDiffTime = t;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Si le son est assez fort et pas extrême (= ce qui entraine généralement de fausses
|
||||||
|
// mesures), alors on le dessine:
|
||||||
|
if ((NivRelatif > _NiveauSonMin) && (minDiffTime > -_nbEchantillonsDiffMax) && (minDiffTime < _nbEchantillonsDiffMax)) {
|
||||||
|
// computation of angle depending on diff time, sampling rates,
|
||||||
|
// and geometry
|
||||||
|
float angle = -(float) asin((minDiffTime * _Vson) / (_TauxEchantillonnageSon* _DistanceMic));
|
||||||
|
if (angle<2 && angle >-2){ //Empeche de renvoyer la valeur -nan lorsque le son est jugé trop faible.
|
||||||
|
cout << angle << ";" << NivRelatif << endl;
|
||||||
|
th = angle;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Calcule du niveau sonore moyen (la puissance) pour les canaux gauche et droit.
|
||||||
|
*/
|
||||||
|
SAMPLE_TYPE CalculNiv(SAMPLE_TYPE Droit[], SAMPLE_TYPE Gauche[]) {
|
||||||
|
float Niveau = 0;
|
||||||
|
for (int i = 0; i < _TailleTampon; i++) {
|
||||||
|
float s = (Gauche[i] + Droit[i]) / 2;
|
||||||
|
Niveau += (s * s);
|
||||||
|
}
|
||||||
|
Niveau /= _TailleTampon;
|
||||||
|
Niveau = sqrt(Niveau);
|
||||||
|
return (SAMPLE_TYPE) Niveau;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
int main(int argc, char *argv[]) {
|
||||||
|
ros::init(argc, argv, "localisation_v2");
|
||||||
|
ros::NodeHandle nh;
|
||||||
|
ros::Publisher cmd_velo = nh.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel", 1000);
|
||||||
|
geometry_msgs::Twist theta;
|
||||||
|
|
||||||
|
Localisation soundLoc;
|
||||||
|
|
||||||
|
while (ros::ok()){
|
||||||
|
soundLoc.run();
|
||||||
|
theta.angular.z = th;
|
||||||
|
//theta.linear.x = 0.1;
|
||||||
|
cmd_velo.publish(theta);
|
||||||
|
}
|
||||||
|
exit(0);
|
||||||
|
}
|
||||||
|
|
384
Code_Final/Localisation360.cpp
Normal file
384
Code_Final/Localisation360.cpp
Normal file
|
@ -0,0 +1,384 @@
|
||||||
|
#include <iostream>
|
||||||
|
using namespace std;
|
||||||
|
|
||||||
|
#include "/opt/ros/kinetic/include/ros/ros.h"
|
||||||
|
#include <geometry_msgs/Twist.h>
|
||||||
|
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <math.h>
|
||||||
|
#include <limits.h>
|
||||||
|
#include <alsa/asoundlib.h>
|
||||||
|
#include "/usr/include/alsa/asoundlib.h"
|
||||||
|
|
||||||
|
//#define SAMPLE_TYPE float
|
||||||
|
//#define SAMPLE_TYPE_ALSA SND_PCM_FORMAT_FLOAT_LE
|
||||||
|
|
||||||
|
#define SAMPLE_TYPE short //sample type = type d'echantillon
|
||||||
|
#define SAMPLE_TYPE_ALSA SND_PCM_FORMAT_S16_LE
|
||||||
|
float th;
|
||||||
|
/**
|
||||||
|
* classe permettant de calculer la moyenne glissante du signal
|
||||||
|
*/
|
||||||
|
class MoyenneGlissante {
|
||||||
|
int _nbDeValeursPrMoy;
|
||||||
|
int _nbDeValeurs;
|
||||||
|
float _mean;
|
||||||
|
|
||||||
|
public:
|
||||||
|
MoyenneGlissante(int nbDeValeursPrMoy) {
|
||||||
|
_nbDeValeursPrMoy = nbDeValeursPrMoy;
|
||||||
|
_mean = 0;
|
||||||
|
_nbDeValeurs = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void nvelleValeur(SAMPLE_TYPE v) {
|
||||||
|
if (_nbDeValeurs < _nbDeValeursPrMoy)
|
||||||
|
_nbDeValeurs++;
|
||||||
|
_mean = ((_mean * (_nbDeValeurs - 1)) + v) / (float)_nbDeValeurs;
|
||||||
|
}
|
||||||
|
|
||||||
|
SAMPLE_TYPE getMean() {
|
||||||
|
return (SAMPLE_TYPE) _mean;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Cette classe calcule la direction du son entendu
|
||||||
|
*
|
||||||
|
*
|
||||||
|
* Elle utilise 2 microphones et calcule la différence de temps d'arrivée des sons entre eux pour
|
||||||
|
* estimer la localisation de la source sonore.
|
||||||
|
*/
|
||||||
|
class Localisation {
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Décalage maximum entre le micro droit et gauche en nombre d'échantillons.
|
||||||
|
* Cela dépend généralement de la fréquence d'échantillonnage et de la distance entre
|
||||||
|
* microphones
|
||||||
|
*/
|
||||||
|
static const int _nbEchantillonsDiffMax = 13; //difference max du nombre d'echantillons
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Taille du tampon sur laquelle nous allons essayer de localiser le son.
|
||||||
|
* Ceci est un certain nombre d'échantillons, et dépend de la fréquence d'échantillonnage et de la vitesse de
|
||||||
|
* changement de loc son que nous voulons détecter. Des valeurs plus faibles signifient le calcul du son
|
||||||
|
* se fait plus souvent, mais la précision est assez faible car nous calculons sur une très petite tranche de
|
||||||
|
* du son.
|
||||||
|
*/
|
||||||
|
static const int _TailleTampon = 4096;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Prenez un point pour la localisation du son est Niveau> 105% du Niveau moyen. Cela permet de calculer la
|
||||||
|
* localisation du son uniquement pour les sons "significatifs", pas le bruit de fond.
|
||||||
|
*/
|
||||||
|
static constexpr float _NiveauSonMin = 1.1f; //f de 1.05f signifie :float constant with value of 1.05
|
||||||
|
|
||||||
|
/**
|
||||||
|
* sound speed in meters per seconds
|
||||||
|
*/
|
||||||
|
static constexpr float _Vson = 344;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* sound sampling rate in Hz
|
||||||
|
*/
|
||||||
|
unsigned int _TauxEchantillonnageSon;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Distance between microphones in meters
|
||||||
|
*/
|
||||||
|
static constexpr float _DistanceMic = 0.05f;//5 cm de distance entre les deux microphones
|
||||||
|
|
||||||
|
/** An utility to compute the running average of sound power */
|
||||||
|
MoyenneGlissante* _MoyNivSonore;
|
||||||
|
|
||||||
|
/** ALSA sound input handle */
|
||||||
|
snd_pcm_t* _capture_handle;
|
||||||
|
snd_pcm_t* _capture_handle2;
|
||||||
|
|
||||||
|
/** sound samples input buffer */
|
||||||
|
SAMPLE_TYPE _TamponDroit[_TailleTampon];
|
||||||
|
SAMPLE_TYPE _TamponGauche[_TailleTampon];
|
||||||
|
SAMPLE_TYPE _TamponAvant[_TailleTampon];
|
||||||
|
|
||||||
|
public:
|
||||||
|
Localisation() {
|
||||||
|
_MoyNivSonore = new MoyenneGlissante(50);
|
||||||
|
_TauxEchantillonnageSon = 44100;
|
||||||
|
|
||||||
|
// sampling: 2 chanels, 44 KHz, 16 bits.
|
||||||
|
int err;
|
||||||
|
snd_pcm_hw_params_t* hw_params;
|
||||||
|
snd_pcm_hw_params_t* hw_params2;
|
||||||
|
|
||||||
|
// ideally use "hw:0,0" for embedded, to limit processing. But check if card support our needs...
|
||||||
|
const char* CarteSon = "plughw:0,0";
|
||||||
|
const char* CarteSon2 = "plughw:1,0";
|
||||||
|
// open_____________________
|
||||||
|
if ((err = snd_pcm_open(&_capture_handle, CarteSon, SND_PCM_STREAM_CAPTURE, 0)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible d'ouvrir le peripherique audio %s (%s)\n", CarteSon,snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_open(&_capture_handle2, CarteSon2, SND_PCM_STREAM_CAPTURE, 0)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible d'ouvrir le peripherique audio %s (%s)\n", CarteSon,snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
//malloc_____________________
|
||||||
|
if ((err = snd_pcm_hw_params_malloc(&hw_params)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible d'allouer la structure des paramètres matériels (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_malloc(&hw_params2)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible d'allouer la structure des paramètres matériels (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
//any_____________________
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_any(_capture_handle, hw_params)) < 0) {
|
||||||
|
fprintf(stderr,"Impossible d'initialiser la structure des paramètres matériels (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_any(_capture_handle2, hw_params2)) < 0) {
|
||||||
|
fprintf(stderr,"Impossible d'initialiser la structure des paramètres matériels (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
//access_____________________
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_set_access(_capture_handle, hw_params,SND_PCM_ACCESS_RW_NONINTERLEAVED)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir le type d'acces (%s)\n", snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_set_access(_capture_handle2, hw_params2,SND_PCM_ACCESS_RW_NONINTERLEAVED)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir le type d'acces (%s)\n", snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
//format _____________________
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_set_format(_capture_handle, hw_params,SAMPLE_TYPE_ALSA)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir le format d'echantillonnage (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_set_format(_capture_handle2, hw_params2,SAMPLE_TYPE_ALSA)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir le format d'echantillonnage (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
//rate near _____________________
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_set_rate_near(_capture_handle, hw_params,&_TauxEchantillonnageSon, 0)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir le taux d'echantillonnage (%s)\n", snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_set_rate_near(_capture_handle2, hw_params2,&_TauxEchantillonnageSon, 0)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir le taux d'echantillonnage (%s)\n", snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
//set channels_____________________
|
||||||
|
if ((err = snd_pcm_hw_params_set_channels(_capture_handle, hw_params, 2))< 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir le nombre de canaux (%s)\n", snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params_set_channels(_capture_handle2, hw_params2, 1))< 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir le nombre de canaux (%s)\n", snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
//hwparams _____________________
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params(_capture_handle, hw_params)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir les parametres (%s)\n", snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_hw_params(_capture_handle2, hw_params2)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de definir les parametres (%s)\n", snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
snd_pcm_hw_params_free(hw_params);
|
||||||
|
snd_pcm_hw_params_free(hw_params2);
|
||||||
|
|
||||||
|
//prepare _____________________
|
||||||
|
|
||||||
|
if ((err = snd_pcm_prepare(_capture_handle)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de preparer l'interface audio pour utilisation (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_prepare(_capture_handle2)) < 0) {
|
||||||
|
fprintf(stderr, "Impossible de preparer l'interface audio pour utilisation (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Clean exit */
|
||||||
|
~Localisation() {
|
||||||
|
snd_pcm_close(_capture_handle);
|
||||||
|
snd_pcm_close(_capture_handle2);
|
||||||
|
delete _MoyNivSonore;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Boucle principale: lit un tampon, calcule la localisation de la source sonore, fait une itération.
|
||||||
|
*/
|
||||||
|
void run() {
|
||||||
|
//while (true) {
|
||||||
|
TraitementSonsSuivants();
|
||||||
|
//}
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
/**
|
||||||
|
* C'est le cœur de la localisation de la source sonore: il prend les sons échantillonnés
|
||||||
|
* Droit / Gauche, et calcule leurs différences tout en retardant de plus en plus un canal.<br/>
|
||||||
|
* => le retard pour lequel la différence est minime est le vrai retard
|
||||||
|
* entre les sons Droit / Gauche, dont on peut déduire la source sonore
|
||||||
|
* localisation
|
||||||
|
*/
|
||||||
|
void TraitementSonsSuivants() {
|
||||||
|
SAMPLE_TYPE* bufs[3];
|
||||||
|
bufs[0] = _TamponDroit;
|
||||||
|
bufs[1] = _TamponGauche;
|
||||||
|
bufs[2] = _TamponAvant;
|
||||||
|
int err;
|
||||||
|
if ((err = snd_pcm_readn(_capture_handle, (void**) bufs, _TailleTampon))!= _TailleTampon) {
|
||||||
|
fprintf(stderr, "Echec de la lecture de l'interface audio (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((err = snd_pcm_readn(_capture_handle2, (void**) bufs, _TailleTampon))!= _TailleTampon) {
|
||||||
|
fprintf(stderr, "Echec de la lecture de l'interface audio (%s)\n",snd_strerror(err));
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
// compute the sound level (i.e. "loudness" of the sound):
|
||||||
|
SAMPLE_TYPE Niveau = CalculNiv(_TamponDroit, _TamponGauche ,_TamponAvant);
|
||||||
|
// update the average sound level with this new measure:
|
||||||
|
_MoyNivSonore->nvelleValeur(Niveau);
|
||||||
|
// relative sound level of this sample compared to average:
|
||||||
|
float NivRelatif = (float) Niveau / (float) _MoyNivSonore->getMean();
|
||||||
|
//cout << "level " << level << ", relative " << NivRelatif << endl;
|
||||||
|
|
||||||
|
int minDiff = INT_MAX;
|
||||||
|
int minDiff2 = INT_MAX;
|
||||||
|
int minDiff3 = INT_MAX;
|
||||||
|
int minDiffTime = -1;
|
||||||
|
int minDiffTime2 = -1;
|
||||||
|
int minDiffTime3 = -1;
|
||||||
|
// glisse sur l'axe du temps pour trouver la différence sonore minimum entre les microphones Droit et Gauche
|
||||||
|
for (int t = -_nbEchantillonsDiffMax; t < _nbEchantillonsDiffMax; t++) {
|
||||||
|
// calcule la somme des différences pour simuler une mesure de corrélation croisée:
|
||||||
|
int diff = 0;
|
||||||
|
int diff2 = 0;
|
||||||
|
int diff3 = 0;
|
||||||
|
for (int i = _nbEchantillonsDiffMax; i < _TailleTampon - _nbEchantillonsDiffMax - 1; i++) {
|
||||||
|
diff += abs(_TamponGauche[i] - _TamponDroit[i + t]);
|
||||||
|
diff2 += abs(_TamponGauche[i] - _TamponAvant[i + t]);
|
||||||
|
diff3 += abs(_TamponAvant[i] - _TamponDroit[i + t]);
|
||||||
|
}
|
||||||
|
if (diff < minDiff) {
|
||||||
|
minDiff = diff;
|
||||||
|
minDiffTime = t;
|
||||||
|
}
|
||||||
|
if (diff2 < minDiff2) {
|
||||||
|
minDiff2 = diff2;
|
||||||
|
minDiffTime2 = t;
|
||||||
|
}
|
||||||
|
if (diff3 < minDiff3) {
|
||||||
|
minDiff3 = diff3;
|
||||||
|
minDiffTime3 = t;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if (minDiffTime<minDiffTime2 && minDiffTime<minDiffTime3) {
|
||||||
|
// Si le son est assez fort et pas extrême (= ce qui entraine généralement de fausses
|
||||||
|
// mesures), alors on le dessine:
|
||||||
|
if ((NivRelatif > _NiveauSonMin) && (minDiffTime > -_nbEchantillonsDiffMax) && (minDiffTime < _nbEchantillonsDiffMax)) {
|
||||||
|
// computation of angle depending on diff time, sampling rates,
|
||||||
|
// and geometry
|
||||||
|
float angle = -(float) asin((minDiffTime * _Vson) / (_TauxEchantillonnageSon* _DistanceMic));
|
||||||
|
if (angle<2 && angle >-2){ //Empeche de renvoyer la valeur -nan lorsque le son est jugé trop faible.
|
||||||
|
printf("GetD");
|
||||||
|
float angleGD = M_PI+angle;
|
||||||
|
cout << angleGD << ";" << NivRelatif << endl;
|
||||||
|
th = angleGD;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (minDiffTime2<minDiffTime && minDiffTime2<minDiffTime3) {
|
||||||
|
// Si le son est assez fort et pas extrême (= ce qui entraine généralement de fausses
|
||||||
|
// mesures), alors on le dessine:
|
||||||
|
if ((NivRelatif > _NiveauSonMin) && (minDiffTime2 > -_nbEchantillonsDiffMax) && (minDiffTime2 < _nbEchantillonsDiffMax)) {
|
||||||
|
// computation of angle depending on diff time, sampling rates,
|
||||||
|
// and geometry
|
||||||
|
float angle = -(float) asin((minDiffTime2 * _Vson) / (_TauxEchantillonnageSon* _DistanceMic));
|
||||||
|
if (angle<2 && angle >-2){ //Empeche de renvoyer la valeur -nan lorsque le son est jugé trop faible.
|
||||||
|
float angleGA = M_PI/4+angle;
|
||||||
|
printf("GetA");
|
||||||
|
cout << angleGA << ";" << NivRelatif << endl;
|
||||||
|
th = angleGA;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (minDiffTime3<minDiffTime && minDiffTime3<minDiffTime2) {
|
||||||
|
// Si le son est assez fort et pas extrême (= ce qui entraine généralement de fausses
|
||||||
|
// mesures), alors on le dessine:
|
||||||
|
if ((NivRelatif > _NiveauSonMin) && (minDiffTime3 > -_nbEchantillonsDiffMax) && (minDiffTime3 < _nbEchantillonsDiffMax)) {
|
||||||
|
// computation of angle depending on diff time, sampling rates,
|
||||||
|
// and geometry
|
||||||
|
float angle = -(float) asin((minDiffTime3 * _Vson) / (_TauxEchantillonnageSon* _DistanceMic));
|
||||||
|
if (angle<2 && angle >-2){ //Empeche de renvoyer la valeur -nan lorsque le son est jugé trop faible.
|
||||||
|
float angleAD = M_PI/4+angle;
|
||||||
|
printf("AetD");
|
||||||
|
cout << angleAD << ";" << NivRelatif << endl;
|
||||||
|
th = angleAD;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Calcule du niveau sonore moyen (la puissance) pour les canaux gauche et droit.
|
||||||
|
*/
|
||||||
|
SAMPLE_TYPE CalculNiv(SAMPLE_TYPE Droit[], SAMPLE_TYPE Gauche[], SAMPLE_TYPE Avant[]) {
|
||||||
|
float Niveau = 0;
|
||||||
|
for (int i = 0; i < _TailleTampon; i++) {
|
||||||
|
float s = (Gauche[i] + Droit[i]+ Avant[i]) / 2;
|
||||||
|
Niveau += (s * s);
|
||||||
|
}
|
||||||
|
Niveau /= _TailleTampon;
|
||||||
|
Niveau = sqrt(Niveau);
|
||||||
|
return (SAMPLE_TYPE) Niveau;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
int main(int argc, char *argv[]) {
|
||||||
|
ros::init(argc, argv, "localisation_v2");
|
||||||
|
ros::NodeHandle nh;
|
||||||
|
ros::Publisher cmd_velo = nh.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel", 1000);
|
||||||
|
geometry_msgs::Twist theta;
|
||||||
|
|
||||||
|
Localisation soundLoc;
|
||||||
|
|
||||||
|
while (ros::ok()){
|
||||||
|
soundLoc.run();
|
||||||
|
theta.angular.z = th;
|
||||||
|
//theta.linear.x = 0.1;
|
||||||
|
cmd_velo.publish(theta);
|
||||||
|
}
|
||||||
|
exit(0);
|
||||||
|
}
|
Loading…
Reference in a new issue