AutonomyLab / create_robot

ROS driver for iRobot Create 1 and 2.
http://www.autonomylab.org/create_autonomy
BSD 3-Clause "New" or "Revised" License
198 stars 165 forks source link

Play a song on Create 1 #46

Closed hamburguesa66 closed 6 years ago

hamburguesa66 commented 6 years ago

Hi. First of all, amazing work guys.

I am working with an Create 1 robot (ROS Kinectic, Ubuntu 16.04), and i can't make it play a song. I want to play the Imperial March, as explained in this link. The example is written in Python, and i need it in C++.

Here is my code:

` ros::init(argc, argv, "musica"); ros::NodeHandle n;

mode_publisher = n.advertise<std_msgs::Empty>("/undock", 1000);
define_publisher = n.advertise<ca_msgs::DefineSong>("/define_song", 1000);
play_publisher = n.advertise<ca_msgs::PlaySong>("/play_song", 1000);
ros::Rate loop_rate(10);

std_msgs::Empty empty;
mode_publisher.publish(empty);

ROS_INFO("Escribiendo partitura.\n");

// define silence
int r = 30;

// map note names in the lilypad notation to irobot commands
int c4 = 60;
int cis4 = 61; 
int des4 = 61;
int d4 = 62;
int dis4 = 63;
int ees4 = 63;
int e4 = 64;
int f4 = 65;
int fis4 = 66;
int ges4 = 66;
int g4 = 67;
int gis4 = 68;
int aes4 = 68;
int a4 = 69;
int ais4 = 70;
int bes4 = 70;
int b4 = 71;
int c5 = 72;
int cis5 = 73;
int des5 = 73;
int d5 = 74;
int dis5 = 75;
int ees5 = 75;
int e5 = 76;
int f5 = 77;
int fis5 = 78;
int ges5 = 78;
int g5 = 79;
int gis5 = 80;
int aes5 = 80;
int a5 = 81;
int ais5 = 82;
int bes5 = 82;
int b5 = 83;
int c6 = 84;
int cis6 = 85;
int des6 = 85;
int d6 = 86;
int dis6 = 87;
int ees6 = 87;
int e6 = 88;
int f6 = 89;
int fis6 = 90;
int ges6 = 90;

// define some note lengths
// change the top MEASURE (4/4 time) to get faster/slower speeds
int MEASURE = 160;
int HALF = MEASURE/2;
int Q = MEASURE/4;
int E = MEASURE/8;
int Ed = MEASURE*3/16;
int S = MEASURE/16;

int MEASURE_TIME = MEASURE/64;

// Escribo la canción.
std::vector<uint8_t> notes(9);
std::vector<float> durations(9);

uint8_t kk[9] = { a4, a4, a4, f4, c5, a4, f4, c5, a4 };
notes.assign(&kk[0], &kk[0]+9);
float vv[9] = { Q, Q, Q, Ed, S, Q, Ed, S, HALF };
durations.assign(&vv[0], &vv[0]+9);

ca_msgs::DefineSong song_msg;
song_msg.song = 0;
song_msg.length = 9;
song_msg.notes = notes;
song_msg.durations = durations;

define_publisher.publish(song_msg);

ros::spinOnce();

// Especifico la canción a reproducir.
ca_msgs::PlaySong play_msg;
play_msg.song = 0;

play_publisher.publish(play_msg);

ROS_INFO("Reproduciendo musica.\n");

return 0;`

No compilation errors. But when i run the node, the create_1.launcher console puts "Bad Song Definition" (or something like that).

¿Am i doing something wrong? ¿Can you give me an example on how to define and play a simple song (or a beep)? Even by console, like "rostopic pub -1 ...."

Thanks in advance. Greetings from Argentina.

jacobperron commented 6 years ago

I believe the error may be in your note durations. They should be floating point values in the range [0, 4). You are assigning much larger values than 4.

I've recently pushed some updated examples to libcreate. You can check out play_song.cpp, which works for me on Create 2.