ros_madplay_player.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /*
18  * ros_madplay_player.cpp
19  *
20  * Created on: 2017. 02. 03.
21  * Author: Jay Song
22  */
23 
25 
26 pid_t g_play_pid = -1;
27 std::string g_sound_file_path = "";
29 
30 void play_sound_callback(const std_msgs::String::ConstPtr& msg)
31 {
32  std_msgs::String done_msg;
33 
34  if(msg->data == "")
35  {
36  if(g_play_pid != -1)
37  kill(g_play_pid, SIGKILL);
38 
39  g_play_pid = -1;
40  done_msg.data = "play_sound_fail";
41  g_done_msg_pub.publish(done_msg);
42  return;
43  }
44 
45  if(g_play_pid != -1)
46  kill(g_play_pid, SIGKILL);
47 
48  g_play_pid = fork();
49 
50  switch(g_play_pid)
51  {
52  case -1:
53  fprintf(stderr, "Fork Failed!! \n");
54  done_msg.data = "play_sound_fail";
55  g_done_msg_pub.publish(done_msg);
56  break;
57  case 0:
58  execl("/usr/bin/madplay", "madplay", (g_sound_file_path + msg->data).c_str(), "-Q", (char*)0);
59  break;
60  default:
61  done_msg.data = "play_sound";
62  g_done_msg_pub.publish(done_msg);
63  break;
64  }
65 
66 }
67 
68 int main(int argc, char** argv)
69 {
70  ros::init(argc, argv, "ros_madplay_player");
71  ros::NodeHandle nh;
72 
73  g_sound_file_path = nh.param<std::string>("sound_file_path", "");
74  if(g_sound_file_path != "" && g_sound_file_path.compare(g_sound_file_path.size()-1, 1, "/") != 0)
75  g_sound_file_path += "/";
76 
77  ros::Subscriber play_mp3_sub = nh.subscribe("/play_sound_file", 10, &play_sound_callback);
78  g_done_msg_pub = nh.advertise<std_msgs::String>("/robotis/movement_done", 5);
79 
80  ros::spin();
81  return 0;
82 }
83 
84 
85 
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string g_sound_file_path
pid_t g_play_pid
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ros::Publisher g_done_msg_pub
void play_sound_callback(const std_msgs::String::ConstPtr &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spin()


ros_madplay_player
Author(s): Zerom , Jay Song
autogenerated on Mon Jun 10 2019 14:38:22