Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
irobot::OpenInterface Class Reference

C++ class implementation of the iRobot OI. More...

#include <inc/OpenInterface.h>

List of all members.

Public Member Functions

int brushes (unsigned char side_brush, unsigned char vacuum, unsigned char main_brush, unsigned char side_brush_clockwise, unsigned char main_brush_dir)
 Set brushes.
int brushesPWM (char main_brush, char side_brush, char vacuum)
 Set brushes motors pwms.
void calculateOdometry ()
 Calculate Roomba odometry. Call after reading encoder pulses.
int clean ()
 Set the Roomba in cleaning mode. Returns the OImode to safe.
int closeSerialPort ()
 Close the serial port.
int drive (double linear_speed, double angular_speed)
 Drive.
int driveDirect (int left_speed, int right_speed)
 Drive direct.
int drivePWM (int left_pwm, int right_pwm)
 Drive PWM.
int getSensorPackets (int timeout)
 Read sensor packets.
int goDock ()
 Sends the Roomba to the dock. Returns the OImode to safe.
int max ()
 Set the Roomba in max cleaning mode. Returns the OImode to safe.
 OpenInterface (const char *new_serial_port)
 Constructor.
int openSerialPort (bool full_control)
 Open the serial port.
int playSong (unsigned char song_number)
 Play song.
int powerDown ()
 Power down the Roomba.
void resetOdometry ()
 Sends the Roomba to the dock. Returns the OImode to safe.
int setDigitLeds (unsigned char digit3, unsigned char digit2, unsigned char digit1, unsigned char digit0)
 Set digit leds.
int setLeds (unsigned char check_robot, unsigned char dock, unsigned char spot, unsigned char debris, unsigned char power_color, unsigned char power_intensity)
 Set leds.
void setOdometry (double new_x, double new_y, double new_yaw)
int setSchedulingLeds (unsigned char sun, unsigned char mon, unsigned char tue, unsigned char wed, unsigned char thu, unsigned char fri, unsigned char sat, unsigned char colon, unsigned char pm, unsigned char am, unsigned char clock, unsigned char schedule)
 Set scheduling leds.
int setSensorPackets (OI_Packet_ID *new_sensor_packets, int new_num_of_packets, size_t new_buffer_size)
 Set sensor packets.
int setSong (unsigned char song_number, unsigned char song_length, unsigned char *notes, unsigned char *note_lengths)
 Set song.
int spot ()
 Set the Roomba in spot cleaning mode. Returns the OImode to safe.
int startStream ()
 Start stream. NOT TESTED.
int stopStream ()
 Stom stream. NOT TESTED.
int streamSensorPackets ()
 Stream sensor packets. NOT TESTED.
 ~OpenInterface ()
 Destructor.

Public Attributes

bool bumper_ [2]
 Cliff sensors. Indexes: LEFT FRONT_LEFT FRONT_RIGHT RIGHT.
bool buttons_ [8]
 IR characters received. Indexes: OMNI LEFT RIGHT.
float capacity_
 Battery charge in Ah.
float charge_
 Battery temperature in C degrees.
unsigned char charging_state_
 Motor overcurrent. Indexes: LEFT RIGHT MAIN_BRUSH SIDE_BRUSH.
bool cliff_ [4]
 Virtual wall detected.
int cliff_signal_ [4]
 Wall signal.
float current_
 Battery voltage in volts.
unsigned char dirt_detect_
 Buttons. Indexes: BUTTON_CLOCK BUTTON_SCHEDULE BUTTON_DAY BUTTON_HOUR BUTTON_MINUTE BUTTON_DOCK BUTTON_SPOT BUTTON_CLEAN.
bool dock_
 Whether the Roomba is connected to the power cord or not.
bool ir_bumper_ [6]
 Bumper sensors. Indexes: LEFT RIGHT.
int ir_bumper_signal_ [6]
 CLiff sensors signal. Indexes: LEFT FRONT_LEFT FRONT_RIGHT RIGHT.
unsigned char ir_char_ [3]
 IR bumper sensors signal. Indexes: LEFT FRONT_LEFT CENTER_LEFT CENTER_RIGHT FRONT_RIGHT RIGHT.
int motor_current_ [4]
 Dirt detected.
double odometry_x_
 Roomba odometry x.
double odometry_y_
 Roomba odometry y.
double odometry_yaw_
 Roomba odometry yaw.
unsigned char OImode_
 Current operation mode, one of ROOMBA_MODE_'s.
bool overcurrent_ [4]
 Motor current. Indexes: LEFT RIGHT MAIN_BRUSH SIDE_BRUSH.
bool power_cord_
 One of OI_CHARGING_'s.
int stasis_
 Battery capacity in Ah.
char temperature_
 Battery current in amps.
bool virtual_wall_
 Wall detected.
float voltage_
 Whether the Roomba is docked or not.
bool wall_
int wall_signal_
 Wheel drop sensors: Indexes: LEFT RIGHT.
bool wheel_drop_ [2]
 IR bumper sensors. Indexes: LEFT FRONT_LEFT CENTER_LEFT CENTER_RIGHT FRONT_RIGHT RIGHT.

Private Member Functions

int buffer2signed_int (unsigned char *buffer, int index)
 Buffer to signed int.
int buffer2unsigned_int (unsigned char *buffer, int index)
 Buffer to unsigned int.
int parseAngle (unsigned char *buffer, int index)
int parseBatteryCapacity (unsigned char *buffer, int index)
int parseBatteryCharge (unsigned char *buffer, int index)
int parseBumpersAndWheeldrops (unsigned char *buffer, int index)
int parseButtons (unsigned char *buffer, int index)
int parseChargingSource (unsigned char *buffer, int index)
int parseChargingState (unsigned char *buffer, int index)
int parseCurrent (unsigned char *buffer, int index)
int parseDirtDetector (unsigned char *buffer, int index)
int parseDistance (unsigned char *buffer, int index)
int parseFontRightCliffSignal (unsigned char *buffer, int index)
int parseFrontLeftCliff (unsigned char *buffer, int index)
int parseFrontLeftCliffSignal (unsigned char *buffer, int index)
int parseFrontRightCliff (unsigned char *buffer, int index)
int parseIrCharLeft (unsigned char *buffer, int index)
int parseIrCharRight (unsigned char *buffer, int index)
int parseIrOmniChar (unsigned char *buffer, int index)
int parseLeftCliff (unsigned char *buffer, int index)
int parseLeftCliffSignal (unsigned char *buffer, int index)
int parseLeftEncoderCounts (unsigned char *buffer, int index)
int parseLeftMotorCurrent (unsigned char *buffer, int index)
int parseLightBumper (unsigned char *buffer, int index)
int parseLightBumperCenterLeftSignal (unsigned char *buffer, int index)
int parseLightBumperCenterRightSignal (unsigned char *buffer, int index)
int parseLightBumperFrontLeftSignal (unsigned char *buffer, int index)
int parseLightBumperFrontRightSignal (unsigned char *buffer, int index)
int parseLightBumperLeftSignal (unsigned char *buffer, int index)
int parseLightBumperRightSignal (unsigned char *buffer, int index)
int parseMainBrushMotorCurrent (unsigned char *buffer, int index)
int parseNumberOfStreamPackets (unsigned char *buffer, int index)
int parseOiMode (unsigned char *buffer, int index)
int parseOvercurrents (unsigned char *buffer, int index)
int parseRequestedLeftVelocity (unsigned char *buffer, int index)
int parseRequestedRadius (unsigned char *buffer, int index)
int parseRequestedRightVelocity (unsigned char *buffer, int index)
int parseRequestedVelocity (unsigned char *buffer, int index)
int parseRightCliff (unsigned char *buffer, int index)
int parseRightCliffSignal (unsigned char *buffer, int index)
int parseRightEncoderCounts (unsigned char *buffer, int index)
int parseRightMotorCurrent (unsigned char *buffer, int index)
int parseSensorPackets (unsigned char *buffer, size_t buffer_length)
 1 when the robot is going forward, 0 otherwise
int parseSideBrushMotorCurrent (unsigned char *buffer, int index)
int parseSongNumber (unsigned char *buffer, int index)
int parseSongPlaying (unsigned char *buffer, int index)
int parseStasis (unsigned char *buffer, int index)
int parseTemperature (unsigned char *buffer, int index)
int parseVirtualWall (unsigned char *buffer, int index)
int parseVoltage (unsigned char *buffer, int index)
int parseWall (unsigned char *buffer, int index)
int parseWallSignal (unsigned char *buffer, int index)
int sendOpcode (OI_Opcode code)
 Send OP code.
int startOI (bool full_control)
 Start OI.

Private Attributes

int angle_
 Amount of angle turned since last reading. Not being used, poor resolution.
int distance_
 Amount of distance travelled since last reading. Not being used, poor resolution.
int encoder_counts_ [2]
 Delta encoder counts.
uint16_t last_encoder_counts_ [2]
 Last encoder counts reading. For odometry calculation.
int num_of_packets_
 Number of packets.
size_t packets_size_
 Total size of packets.
std::string port_name_
 Serial port to which the robot is connected.
OI_Packet_IDsensor_packets_
 Array of packets.
cereal::CerealPortserial_port_
 Cereal port object.
bool stream_defined_
 Stream variable. NOT TESTED.

Detailed Description

C++ class implementation of the iRobot OI.

This class implements the iRobot Open Interface protocolor as described by iRobot. Based on the Player Roomba driver writen by Brian Gerkey.

Definition at line 293 of file OpenInterface.h.


Constructor & Destructor Documentation

irobot::OpenInterface::OpenInterface ( const char *  new_serial_port)

Constructor.

By default the constructor will set the Roomba to read only the encoder counts (for odometry).

Parameters:
new_serial_portName of the serial port to open.
See also:
setSensorPackets()

Definition at line 49 of file OpenInterface.cpp.

Destructor.

Definition at line 77 of file OpenInterface.cpp.


Member Function Documentation

int irobot::OpenInterface::brushes ( unsigned char  side_brush,
unsigned char  vacuum,
unsigned char  main_brush,
unsigned char  side_brush_clockwise,
unsigned char  main_brush_dir 
)

Set brushes.

Set the various brushes motors.

Parameters:
side_brushSide brush on (1) or off (0).
vacuumVacuum on (1) or off (0).
main_brushMain brush on (1) or off (0).
side_brush_clockwiseWether to rotate the side brush clockwise or not.
main_brush_dirMain brush direction.
Returns:
0 if ok, -1 otherwise.

Definition at line 207 of file OpenInterface.cpp.

int irobot::OpenInterface::brushesPWM ( char  main_brush,
char  side_brush,
char  vacuum 
)

Set brushes motors pwms.

Set the brushes motors pwms. This is very interesting. One could disconnect the motors and plug other actuators that could be controller over pwm on the Roomba.

Parameters:
main_brushMain brush motor pwm.
side_brushSide brush motor pwm.
vacuumVacuum motor pwm.
Returns:
0 if ok, -1 otherwise.

Definition at line 220 of file OpenInterface.cpp.

int irobot::OpenInterface::buffer2signed_int ( unsigned char *  buffer,
int  index 
) [private]

Buffer to signed int.

Parsing helper function. Converts 2 bytes of data into a signed int value.

Parameters:
bufferData buffer.
indexPosition in the buffer where the value is.
See also:
buffer2unsigned_int()
Returns:
A signed int value.

Definition at line 1233 of file OpenInterface.cpp.

int irobot::OpenInterface::buffer2unsigned_int ( unsigned char *  buffer,
int  index 
) [private]

Buffer to unsigned int.

Parsing helper function. Converts 2 bytes of data into an unsigned int value.

Parameters:
bufferData buffer.
indexPosition in the buffer where the value is.
See also:
buffer2signed_int()
Returns:
An unsigned int value.

Definition at line 1243 of file OpenInterface.cpp.

Calculate Roomba odometry. Call after reading encoder pulses.

Definition at line 1256 of file OpenInterface.cpp.

Set the Roomba in cleaning mode. Returns the OImode to safe.

Definition at line 1288 of file OpenInterface.cpp.

Close the serial port.

Definition at line 129 of file OpenInterface.cpp.

int irobot::OpenInterface::drive ( double  linear_speed,
double  angular_speed 
)

Drive.

Send velocity commands to Roomba.

Parameters:
linear_speedLinear speed.
angular_speedAngular speed.
Returns:
0 if ok, -1 otherwise.

Definition at line 162 of file OpenInterface.cpp.

int irobot::OpenInterface::driveDirect ( int  left_speed,
int  right_speed 
)

Drive direct.

Send velocity commands to Roomba.

Parameters:
left_speedLeft wheel speed.
right_speedRight wheel speed.
Returns:
0 if ok, -1 otherwise.

Definition at line 173 of file OpenInterface.cpp.

int irobot::OpenInterface::drivePWM ( int  left_pwm,
int  right_pwm 
)

Drive PWM.

Set the motors pwms. NOT IMPLEMENTED

Parameters:
left_pwmLeft wheel motor pwm.
right_pwmRight wheel motor pwm.
Returns:
0 if ok, -1 otherwise.

Definition at line 198 of file OpenInterface.cpp.

Read sensor packets.

Requested the defined sensor packets from the Roomba. If you need odometry and you requested encoder data you need to call calculateOdometry() afterwords.

Parameters:
timeoutTimeout in milliseconds.
See also:
calculateOdometry()
Returns:
0 if ok, -1 otherwise.

Definition at line 259 of file OpenInterface.cpp.

Sends the Roomba to the dock. Returns the OImode to safe.

Definition at line 1312 of file OpenInterface.cpp.

Set the Roomba in max cleaning mode. Returns the OImode to safe.

Definition at line 1296 of file OpenInterface.cpp.

int irobot::OpenInterface::openSerialPort ( bool  full_control)

Open the serial port.

Parameters:
full_controlWhether to set the Roomba on OImode full or not.

Definition at line 86 of file OpenInterface.cpp.

int irobot::OpenInterface::parseAngle ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 913 of file OpenInterface.cpp.

int irobot::OpenInterface::parseBatteryCapacity ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 964 of file OpenInterface.cpp.

int irobot::OpenInterface::parseBatteryCharge ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 956 of file OpenInterface.cpp.

int irobot::OpenInterface::parseBumpersAndWheeldrops ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 809 of file OpenInterface.cpp.

int irobot::OpenInterface::parseButtons ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 897 of file OpenInterface.cpp.

int irobot::OpenInterface::parseChargingSource ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1012 of file OpenInterface.cpp.

int irobot::OpenInterface::parseChargingState ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 921 of file OpenInterface.cpp.

int irobot::OpenInterface::parseCurrent ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 940 of file OpenInterface.cpp.

int irobot::OpenInterface::parseDirtDetector ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 881 of file OpenInterface.cpp.

int irobot::OpenInterface::parseDistance ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 905 of file OpenInterface.cpp.

int irobot::OpenInterface::parseFontRightCliffSignal ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 996 of file OpenInterface.cpp.

int irobot::OpenInterface::parseFrontLeftCliff ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 836 of file OpenInterface.cpp.

int irobot::OpenInterface::parseFrontLeftCliffSignal ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 988 of file OpenInterface.cpp.

int irobot::OpenInterface::parseFrontRightCliff ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 844 of file OpenInterface.cpp.

int irobot::OpenInterface::parseIrCharLeft ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1177 of file OpenInterface.cpp.

int irobot::OpenInterface::parseIrCharRight ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1185 of file OpenInterface.cpp.

int irobot::OpenInterface::parseIrOmniChar ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 889 of file OpenInterface.cpp.

int irobot::OpenInterface::parseLeftCliff ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 828 of file OpenInterface.cpp.

int irobot::OpenInterface::parseLeftCliffSignal ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 980 of file OpenInterface.cpp.

int irobot::OpenInterface::parseLeftEncoderCounts ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1093 of file OpenInterface.cpp.

int irobot::OpenInterface::parseLeftMotorCurrent ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1193 of file OpenInterface.cpp.

int irobot::OpenInterface::parseLightBumper ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1116 of file OpenInterface.cpp.

int irobot::OpenInterface::parseLightBumperCenterLeftSignal ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1145 of file OpenInterface.cpp.

int irobot::OpenInterface::parseLightBumperCenterRightSignal ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1153 of file OpenInterface.cpp.

int irobot::OpenInterface::parseLightBumperFrontLeftSignal ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1137 of file OpenInterface.cpp.

int irobot::OpenInterface::parseLightBumperFrontRightSignal ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1161 of file OpenInterface.cpp.

int irobot::OpenInterface::parseLightBumperLeftSignal ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1129 of file OpenInterface.cpp.

int irobot::OpenInterface::parseLightBumperRightSignal ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1169 of file OpenInterface.cpp.

int irobot::OpenInterface::parseMainBrushMotorCurrent ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1209 of file OpenInterface.cpp.

int irobot::OpenInterface::parseNumberOfStreamPackets ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1040 of file OpenInterface.cpp.

int irobot::OpenInterface::parseOiMode ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1021 of file OpenInterface.cpp.

int irobot::OpenInterface::parseOvercurrents ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 868 of file OpenInterface.cpp.

int irobot::OpenInterface::parseRequestedLeftVelocity ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1064 of file OpenInterface.cpp.

int irobot::OpenInterface::parseRequestedRadius ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1052 of file OpenInterface.cpp.

int irobot::OpenInterface::parseRequestedRightVelocity ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1058 of file OpenInterface.cpp.

int irobot::OpenInterface::parseRequestedVelocity ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1046 of file OpenInterface.cpp.

int irobot::OpenInterface::parseRightCliff ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 852 of file OpenInterface.cpp.

int irobot::OpenInterface::parseRightCliffSignal ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1004 of file OpenInterface.cpp.

int irobot::OpenInterface::parseRightEncoderCounts ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1070 of file OpenInterface.cpp.

int irobot::OpenInterface::parseRightMotorCurrent ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1201 of file OpenInterface.cpp.

int irobot::OpenInterface::parseSensorPackets ( unsigned char *  buffer,
size_t  buffer_length 
) [private]

1 when the robot is going forward, 0 otherwise

Parse data

Data parsing function. Parses data comming from the Roomba.

Parameters:
bufferData to be parsed.
buffer_lengthSize of the data buffer.
Returns:
0 if ok, -1 otherwise.

Definition at line 336 of file OpenInterface.cpp.

int irobot::OpenInterface::parseSideBrushMotorCurrent ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1217 of file OpenInterface.cpp.

int irobot::OpenInterface::parseSongNumber ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1028 of file OpenInterface.cpp.

int irobot::OpenInterface::parseSongPlaying ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1034 of file OpenInterface.cpp.

int irobot::OpenInterface::parseStasis ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 1225 of file OpenInterface.cpp.

int irobot::OpenInterface::parseTemperature ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 948 of file OpenInterface.cpp.

int irobot::OpenInterface::parseVirtualWall ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 860 of file OpenInterface.cpp.

int irobot::OpenInterface::parseVoltage ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 932 of file OpenInterface.cpp.

int irobot::OpenInterface::parseWall ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 820 of file OpenInterface.cpp.

int irobot::OpenInterface::parseWallSignal ( unsigned char *  buffer,
int  index 
) [private]

Definition at line 972 of file OpenInterface.cpp.

int irobot::OpenInterface::playSong ( unsigned char  song_number)

Play song.

Play a song previously recorded on Roombas memory. You can only play songs stored with setSong().

Parameters:
song_numberSong id (from 0 to 15) so you can play it later.
See also:
setSong()
Returns:
0 if ok, -1 otherwise.

Definition at line 1344 of file OpenInterface.cpp.

Power down the Roomba.

Definition at line 154 of file OpenInterface.cpp.

Sends the Roomba to the dock. Returns the OImode to safe.

Definition at line 1270 of file OpenInterface.cpp.

Send OP code.

Send an OP code to Roomba.

Parameters:
codeOP code to send.
Returns:
0 if ok, -1 otherwise.

Definition at line 143 of file OpenInterface.cpp.

int irobot::OpenInterface::setDigitLeds ( unsigned char  digit3,
unsigned char  digit2,
unsigned char  digit1,
unsigned char  digit0 
)

Set digit leds.

Set the digit leds on the Roomba, the ones on the clock. Digits are ordered from left to right on the robot, 3, 2, 1, 0.

Parameters:
digit3Digit 3
digit2Digit 2
digit1Digit 1
digit0Digit 0
Returns:
0 if ok, -1 otherwise.

Definition at line 1390 of file OpenInterface.cpp.

int irobot::OpenInterface::setLeds ( unsigned char  check_robot,
unsigned char  dock,
unsigned char  spot,
unsigned char  debris,
unsigned char  power_color,
unsigned char  power_intensity 
)

Set leds.

Set the leds state on the Roomba.

Parameters:
check_robotCheck robot led.
dockDock led.
spotSpot led.
debrisDebris led.
power_colorPower led color, varies from green (yellow, orange) to red.
power_intensityPower led intensity.
Returns:
0 if ok, -1 otherwise.

Definition at line 1359 of file OpenInterface.cpp.

void irobot::OpenInterface::setOdometry ( double  new_x,
double  new_y,
double  new_yaw 
)

Definition at line 1278 of file OpenInterface.cpp.

int irobot::OpenInterface::setSchedulingLeds ( unsigned char  sun,
unsigned char  mon,
unsigned char  tue,
unsigned char  wed,
unsigned char  thu,
unsigned char  fri,
unsigned char  sat,
unsigned char  colon,
unsigned char  pm,
unsigned char  am,
unsigned char  clock,
unsigned char  schedule 
)

Set scheduling leds.

Set the leds state on the Roomba.

Parameters:
sunSunday, 1 on, 0 off.
monMonday, 1 on, 0 off.
tueTuesday, 1 on, 0 off.
wedYou get the idea...
thu...
friBoooooring!
satSaturday, pfew!
colonColon on the clock.
pmPM.
amAM.
clockClock.
scheduleSchedule.
Returns:
0 if ok, -1 otherwise.

Definition at line 1375 of file OpenInterface.cpp.

int irobot::OpenInterface::setSensorPackets ( OI_Packet_ID new_sensor_packets,
int  new_num_of_packets,
size_t  new_buffer_size 
)

Set sensor packets.

Set the sensor packets one wishes to read from the roomba. By default the constructor will set the Roomba to read only the encoder counts (for odometry).

Parameters:
new_sensor_packetsArray of sensor packets to read.
new_num_of_packetsNumber of sensor packets in the array.
new_buffer_sizeSize of the resulting sensor data reply.
Returns:
0 if ok, -1 otherwise.

Definition at line 236 of file OpenInterface.cpp.

int irobot::OpenInterface::setSong ( unsigned char  song_number,
unsigned char  song_length,
unsigned char *  notes,
unsigned char *  note_lengths 
)

Set song.

Record a song on Roombas memory. Songs can be played with playSong().

Parameters:
song_numberSong id (from 0 to 15) so you can play it later.
song_lengthNumber of notes in the song.
notesArray of notes.
note_lengthsArray of notes length.
See also:
playSong()
Returns:
0 if ok, -1 otherwise.

Definition at line 1320 of file OpenInterface.cpp.

Set the Roomba in spot cleaning mode. Returns the OImode to safe.

Definition at line 1304 of file OpenInterface.cpp.

int irobot::OpenInterface::startOI ( bool  full_control) [private]

Start OI.

Start the OI, change to roomba to a OImode that allows control.

Parameters:
full_controlWhether to set the Roomba on OImode full or not.
Returns:
0 if ok, -1 otherwise.

Definition at line 99 of file OpenInterface.cpp.

Start stream. NOT TESTED.

Definition at line 309 of file OpenInterface.cpp.

Stom stream. NOT TESTED.

Definition at line 321 of file OpenInterface.cpp.

Stream sensor packets. NOT TESTED.

Definition at line 284 of file OpenInterface.cpp.


Member Data Documentation

Amount of angle turned since last reading. Not being used, poor resolution.

Definition at line 660 of file OpenInterface.h.

Cliff sensors. Indexes: LEFT FRONT_LEFT FRONT_RIGHT RIGHT.

Definition at line 509 of file OpenInterface.h.

IR characters received. Indexes: OMNI LEFT RIGHT.

Definition at line 517 of file OpenInterface.h.

Battery charge in Ah.

Definition at line 531 of file OpenInterface.h.

Battery temperature in C degrees.

Definition at line 530 of file OpenInterface.h.

Motor overcurrent. Indexes: LEFT RIGHT MAIN_BRUSH SIDE_BRUSH.

Definition at line 524 of file OpenInterface.h.

Virtual wall detected.

Definition at line 508 of file OpenInterface.h.

Wall signal.

Definition at line 513 of file OpenInterface.h.

Battery voltage in volts.

Definition at line 528 of file OpenInterface.h.

Buttons. Indexes: BUTTON_CLOCK BUTTON_SCHEDULE BUTTON_DAY BUTTON_HOUR BUTTON_MINUTE BUTTON_DOCK BUTTON_SPOT BUTTON_CLEAN.

Definition at line 519 of file OpenInterface.h.

Amount of distance travelled since last reading. Not being used, poor resolution.

Definition at line 658 of file OpenInterface.h.

Whether the Roomba is connected to the power cord or not.

Definition at line 526 of file OpenInterface.h.

Delta encoder counts.

Definition at line 662 of file OpenInterface.h.

Bumper sensors. Indexes: LEFT RIGHT.

Definition at line 510 of file OpenInterface.h.

CLiff sensors signal. Indexes: LEFT FRONT_LEFT FRONT_RIGHT RIGHT.

Definition at line 514 of file OpenInterface.h.

IR bumper sensors signal. Indexes: LEFT FRONT_LEFT CENTER_LEFT CENTER_RIGHT FRONT_RIGHT RIGHT.

Definition at line 515 of file OpenInterface.h.

Last encoder counts reading. For odometry calculation.

Definition at line 664 of file OpenInterface.h.

Dirt detected.

Definition at line 521 of file OpenInterface.h.

Number of packets.

Definition at line 651 of file OpenInterface.h.

Roomba odometry x.

Definition at line 500 of file OpenInterface.h.

Roomba odometry y.

Definition at line 502 of file OpenInterface.h.

Roomba odometry yaw.

Definition at line 504 of file OpenInterface.h.

Current operation mode, one of ROOMBA_MODE_'s.

Definition at line 493 of file OpenInterface.h.

Motor current. Indexes: LEFT RIGHT MAIN_BRUSH SIDE_BRUSH.

Definition at line 522 of file OpenInterface.h.

Total size of packets.

Definition at line 655 of file OpenInterface.h.

std::string irobot::OpenInterface::port_name_ [private]

Serial port to which the robot is connected.

Definition at line 643 of file OpenInterface.h.

One of OI_CHARGING_'s.

Definition at line 525 of file OpenInterface.h.

Array of packets.

Definition at line 653 of file OpenInterface.h.

Cereal port object.

Definition at line 645 of file OpenInterface.h.

Battery capacity in Ah.

Definition at line 533 of file OpenInterface.h.

Stream variable. NOT TESTED.

Definition at line 648 of file OpenInterface.h.

Battery current in amps.

Definition at line 529 of file OpenInterface.h.

Wall detected.

Definition at line 507 of file OpenInterface.h.

Whether the Roomba is docked or not.

Definition at line 527 of file OpenInterface.h.

Definition at line 506 of file OpenInterface.h.

Wheel drop sensors: Indexes: LEFT RIGHT.

Definition at line 512 of file OpenInterface.h.

IR bumper sensors. Indexes: LEFT FRONT_LEFT CENTER_LEFT CENTER_RIGHT FRONT_RIGHT RIGHT.

Definition at line 511 of file OpenInterface.h.


The documentation for this class was generated from the following files:


roomba_500_series
Author(s): Gonçalo Cabrita
autogenerated on Mon Jan 6 2014 11:26:40