int main(int argc, char** argv) { ros::init(argc, argv, "sounds"); ros::NodeHandle nh; sound_play::SoundClient sc; sleepok(1, nh); while(nh.ok()){ sc.startWave(sound_directory + getRandomSound()); sleepok(900, nh); //sleep for fifteen minutes 900 seconds } }
int main(int argc, char** argv) { ros::init(argc, argv, "jetsonbot_teleop"); ros::NodeHandle nh ; // For some reason, this sound client needs to be defined in main // for sound to work. // Need to investigate -- jlb 8-1-15 sound_play::SoundClient sc ; JetsonbotTeleop jetsonbot_teleop; // sc.say("Hello World!") ; // Hard coded for now sleepok(1,nh); sc.playWave("/home/ubuntu/jetsonbot/sounds/StartupSounds/BritMale/InitializeChecks.wav") ; sleepok(4,nh); sc.playWave("/home/ubuntu/jetsonbot/sounds/StartupSounds/BritMale/PowerNominal.wav") ; sleepok(4,nh); sc.playWave("/home/ubuntu/jetsonbot/sounds/StartupSounds/BritMale/WirelessNetwork.wav") ; sleepok(5,nh); sc.playWave("/home/ubuntu/jetsonbot/sounds/StartupSounds/BritMale/3DCamera.wav") ; sleepok(3,nh); sc.playWave("/home/ubuntu/jetsonbot/sounds/StartupSounds/BritMale/ControllerLink.wav") ; sleepok(3,nh); sc.playWave("/home/ubuntu/jetsonbot/sounds/StartupSounds/BritMale/JetsonBotActive.wav") ; sleepok(7,nh); // sc.say("Initialization Checks Commencing"); // sleepok(3,nh); ros::spin(); // Set the follower service off if it is available // Turn off the follower ros::NodeHandle nodeHandle ; ros::ServiceClient serviceClient = nodeHandle.serviceClient<turtlebot_msgs::SetFollowState>("/turtlebot_follower/change_state"); turtlebot_msgs::SetFollowState srv ; srv.request.state=1 ; if (serviceClient.call(srv)) { ROS_INFO("Follower state changed to: %d",srv.request.state); } else { ROS_ERROR("Failed call to service turtlebot_follower/change_state %d",srv.response.result); } }
void JetsonbotTeleop::publish() { boost::mutex::scoped_lock lock(publish_mutex_); if (deadman_pressed_) { vel_pub_.publish(last_published_); zero_twist_published_=false; } else if(!deadman_pressed_ && !zero_twist_published_) { vel_pub_.publish(*new geometry_msgs::Twist()); zero_twist_published_=true; } #if 0 ROS_ERROR("aPressed: (%d)", aPressed); ROS_ERROR("bPressed: (%d)", bPressed); ROS_ERROR("xPressed: (%d)", xPressed); ROS_ERROR("leftPressed: (%d)", leftPressed); ROS_ERROR("rightPressed: (%d)", rightPressed); #endif sound_play::SoundClient soundClient ; if (aPressed) { //ROS_ERROR("APRESSED: (%d)", aPressed); soundClient.playWave(buttonASound) ; sleepok(1,ph_) ; } if (bPressed) { //ROS_ERROR("BPRESSED: (%d)", bPressed); soundClient.playWave(buttonBSound) ; sleepok(1,ph_) ; } if (yPressed) { //ROS_ERROR("YPRESSED: (%d)", yPressed); soundClient.playWave(buttonYSound) ; sleepok(1,ph_) ; } if (xPressed) { //ROS_ERROR("XPRESSED: (%d)", xPressed); soundClient.playWave(buttonXSound) ; sleepok(1,ph_) ; } if (leftPressed) { //ROS_ERROR("LEFTPRESSED: (%d)", leftPressed); sound_play::SoundClient soundClient ; soundClient.stopAll() ; } if (rightPressed) { // ROS_ERROR("RIGHTPRESSED: (%d)", rightPressed); soundClient.playWave(buttonRightSound) ; sleepok(1,ph_) ; } if (appPressed) { if (followerOn) { soundClient.playWave(buttonAppSoundOff) ; sleepok(1,ph_) ; } else { soundClient.playWave(buttonAppSoundOn) ; sleepok(1,ph_) ; } followerOn = !followerOn ; // Set the follower service off if it is available ros::NodeHandle nodeHandle ; ros::ServiceClient serviceClient = nodeHandle.serviceClient<turtlebot_msgs::SetFollowState>("/turtlebot_follower/change_state"); turtlebot_msgs::SetFollowState srv ; // Turn off the follower srv.request.state=followerOn ; if (serviceClient.call(srv)) { ROS_INFO("Follower state changed to: %d",srv.request.state); } else { ROS_ERROR("Failed call to service turtlebot_follower/change_state %d",srv.response.result); } } if (rightTrigger) { #if 0 geometry_msgs::Twist vel; vel.angular.z = a_scale_*((rightTrigger+1)/2); vel.linear.x = 0 ; last_published_ = vel; deadman_pressed_ = false; vel_pub_.publish(last_published_); zero_twist_published_=false; #endif // ROS_ERROR("rightTrigger: (%f)", rightTrigger); rightTrigger=0; } if (leftTrigger) { #if 0 geometry_msgs::Twist vel; vel.angular.z = a_scale_*((leftTrigger-1)/2); vel.linear.x = 0 ; last_published_ = vel; deadman_pressed_ = false; vel_pub_.publish(last_published_); zero_twist_published_=false; #endif // ROS_ERROR("leftTrigger: (%f)", leftTrigger); leftTrigger=0; } if (crossHorizontal) { if (crossHorizontal < 0.0) { geometry_msgs::Twist twist; twist.angular.z=1.57/2 ; for (int i = 0 ; i < 10 ; i++) { vel_pub_.publish(twist) ; // sleepok(0,ph_) ; } } else { if (crossHorizontal > 0.0) { geometry_msgs::Twist twist; twist.angular.z=-1.57/2 ; for (int i = 0 ; i < 10 ; i++) { vel_pub_.publish(twist) ; //sleepok(0,ph_) ; } } } } }