carl_speed_speak.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <geometry_msgs/Twist.h>
00003 #include <cmath>
00004 #include <sstream>
00005 #include <espeak/speak_lib.h>
00006 
00007 int buff_len = 500;
00008 int options = 0;
00009 unsigned int *unique_identifier;
00010 void* user_data;
00011 bool beep = false;
00012 
00013 void speak()
00014 {
00015   if (!beep) {
00016     espeak_Synth("carl", 4, 0, POS_CHARACTER, 0, espeakCHARS_AUTO, unique_identifier, user_data);
00017   } else {
00018     espeak_Synth("beep", 4, 0, POS_CHARACTER, 0, espeakCHARS_AUTO, unique_identifier, user_data);
00019   }
00020   espeak_Synchronize();
00021 }
00022 
00023 void cmd_vel_cback(const geometry_msgs::Twist::ConstPtr& msg)
00024 {
00025   float linear = msg->linear.x;
00026   int speed, pitch;
00027 
00028   if (linear < 0)
00029   {
00030     beep = true;
00031     speed = 1;
00032     pitch = 100;
00033   } else {
00034     beep = false;
00035     speed = (int) ((linear * 5000) + 500);
00036     pitch = (int) ((linear * 100) + 1);
00037   }
00038   espeak_SetParameter(espeakRATE, speed, 0);
00039   espeak_SetParameter(espeakPITCH, pitch, 0);
00040 }
00041 
00042 int main(int argc, char **argv)
00043 {
00044   // initialize ROS and the node
00045   ros::init(argc, argv, "carl_speed_espeak");
00046 
00047   // subscribe to cmd_vel
00048   ros::NodeHandle n;
00049   ros::Subscriber sub = n.subscribe("/cmd_vel", 1, cmd_vel_cback);
00050 
00051   if (espeak_Initialize(AUDIO_OUTPUT_PLAYBACK, buff_len, NULL, options) == -1)
00052   {
00053     ROS_ERROR("espeak could not initialize!");
00054     return EXIT_FAILURE;
00055   }
00056 
00057   espeak_SetParameter(espeakRATE, 500, 0);
00058   espeak_SetParameter(espeakPITCH, 1, 0);
00059 
00060   ros::AsyncSpinner spinner(4);
00061   spinner.start();
00062   while (ros::ok())
00063   {
00064     speak();
00065   }
00066 
00067   return EXIT_SUCCESS;
00068 }


carl_demos
Author(s): David Kent , Russell Toris
autogenerated on Thu Jun 6 2019 21:59:32