play_song.cpp
Go to the documentation of this file.
1 
31 #include "create/create.h"
32 
33 #include <iostream>
34 
35 int main(int argc, char** argv) {
36  // Select robot. Assume Create 2 unless argument says otherwise
38  std::string port = "/dev/ttyUSB0";
39  int baud = 115200;
40  if (argc > 1 && std::string(argv[1]) == "create1") {
42  baud = 57600;
43  std::cout << "Running driver for Create 1" << std::endl;
44  }
45  else {
46  std::cout << "Running driver for Create 2" << std::endl;
47  }
48 
49  // Construct robot object
50  create::Create* robot = new create::Create(model);
51 
52  // Connect to robot
53  if (robot->connect(port, baud))
54  std::cout << "Connected to robot" << std::endl;
55  else {
56  std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl;
57  return 1;
58  }
59 
60  // Switch to Full mode
61  robot->setMode(create::MODE_FULL);
62 
63  // Useful note defintions
64  const uint8_t G = 55;
65  const uint8_t AS = 58;
66  const uint8_t DS = 51;
67  const float half = 1.0f;
68  const float quarter = 0.5f;
69  const float dotted_eigth = 0.375f;
70  const float sixteenth = 0.125f;
71 
72  // Define a song
73  const uint8_t song_len = 9;
74  const uint8_t notes[song_len] = { G, G, G, DS, AS, G, DS, AS, G };
75  const float durations[song_len] = { quarter, quarter, quarter, dotted_eigth, sixteenth, quarter, dotted_eigth, sixteenth, half };
76  robot->defineSong(0, song_len, notes, durations);
77 
78  // Sleep to provide time for song to register
79  usleep(1000000);
80 
81  std::cout << "Playing a song!" << std::endl;
82 
83  // Request to play the song we just defined
84  robot->playSong(0);
85 
86  // Expect the song to take about four seconds
87  usleep(4500000);
88 
89  // Call disconnect to avoid leaving robot in Full mode
90  robot->disconnect();
91 
92  // Clean up
93  delete robot;
94 
95  std::cout << "Bye!" << std::endl;
96  return 0;
97 }
int main(int argc, char **argv)
Definition: play_song.cpp:35
static RobotModel CREATE_1
Compatible with Create 1 or Roomba 500 series.
Definition: types.h:68
bool playSong(const uint8_t &songNumber) const
Play a previously created song. This command will not work if a song was not already defined with the...
Definition: create.cpp:583
bool connect(const std::string &port, const int &baud)
Make a serial connection to Create.
Definition: create.cpp:272
static RobotModel CREATE_2
Compatible with Create 2 or Roomba 600 series and greater.
Definition: types.h:73
void disconnect()
Disconnect from serial.
Definition: create.cpp:293
bool setMode(const create::CreateMode &mode)
Change Create mode.
Definition: create.cpp:304
bool defineSong(const uint8_t &songNumber, const uint8_t &songLength, const uint8_t *notes, const float *durations) const
Defines a song from the provided notes and labels it with a song number.
Definition: create.cpp:560


libcreate
Author(s): Jacob Perron
autogenerated on Sat Jun 8 2019 17:58:17