35 int main(
int argc,
char** argv) {
38 std::string port =
"/dev/ttyUSB0";
40 if (argc > 1 && std::string(argv[1]) ==
"create1") {
43 std::cout <<
"Running driver for Create 1" << std::endl;
46 std::cout <<
"Running driver for Create 2" << std::endl;
54 std::cout <<
"Connected to robot" << std::endl;
56 std::cout <<
"Failed to connect to robot on port " << port.c_str() << std::endl;
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;
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);
81 std::cout <<
"Playing a song!" << std::endl;
int main(int argc, char **argv)
static RobotModel CREATE_1
Compatible with Create 1 or Roomba 500 series.
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...
bool connect(const std::string &port, const int &baud)
Make a serial connection to Create.
static RobotModel CREATE_2
Compatible with Create 2 or Roomba 600 series and greater.
void disconnect()
Disconnect from serial.
bool setMode(const create::CreateMode &mode)
Change Create mode.
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.