Skip to content

Commit e99939c

Browse files
authored
Mode report workaround (#67)
* Add option for OI mode reporting bug workaround AutonomyLab/create_robot#64 * Update README.md * Add note about 600 series OI mode reporting bug to Known Issues section and include details of API workaround option. * Add myself to contributors list
1 parent db575de commit e99939c

3 files changed

Lines changed: 36 additions & 2 deletions

File tree

README.md

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@ C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com
88
- [`V_2`](https://drive.google.com/file/d/0B9O4b91VYXMdMmFPMVNDUEZ6d0U) (Create 1, Roomba 500 series)
99
- [`V_3`](https://drive.google.com/file/d/0B9O4b91VYXMdSVk4amw1N09mQ3c) (Create 2, Roomba 600-800 series)
1010
* Author: [Jacob Perron](http://jacobperron.ca) ([Autonomy Lab](http://autonomylab.org), [Simon Fraser University](http://www.sfu.ca))
11-
* Contributors: [Mani Monajjemi](http:mani.im), [Ben Wolsieffer](https://github.com/lopsided98)
11+
* Contributors: [Mani Monajjemi](http:mani.im), [Ben Wolsieffer](https://github.com/lopsided98), [Josh Gadeken](https://github.com/process1183)
1212

1313
## Build Status ##
1414

@@ -72,3 +72,5 @@ To run unit tests, execute the following in the build directory:
7272

7373
* _Clock_ and _Schedule_ buttons are not functional. This is a known bug related to the firmware.
7474
* Inaccurate odometry angle for Create 1 ([#22](https://github.com/AutonomyLab/libcreate/issues/22))
75+
* Some 600 series models incorrectly report the OI Mode in their sensor stream ([create_robot #64](https://github.com/AutonomyLab/create_robot/issues/64))
76+
- To enable or disable the OI Mode reporting workaround, pass `true` or `false` to `setModeReportWorkaround()`

include/create/create.h

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -98,6 +98,10 @@ namespace create {
9898
void onData();
9999
bool updateLEDs();
100100

101+
// Flag to enable/disable the workaround for some 6xx incorrectly reporting OI mode
102+
// https://github.com/AutonomyLab/create_robot/issues/64
103+
bool modeReportWorkaround;
104+
101105
protected:
102106
std::shared_ptr<create::Data> data;
103107
std::shared_ptr<create::Serial> serial;
@@ -673,6 +677,20 @@ namespace create {
673677
* \return total number of serial packets.
674678
*/
675679
uint64_t getTotalPackets() const;
680+
681+
/**
682+
* \brief Enable or disable the mode reporting workaround.
683+
* Some Roomba 6xx robots incorrectly report the OI mode in their sensor streams. Enabling the workaround
684+
* will cause libcreate to decrement the reported OI mode in the sensor stream by 1.
685+
* See https://github.com/AutonomyLab/create_robot/issues/64
686+
*/
687+
void setModeReportWorkaround(const bool& enable);
688+
689+
/**
690+
* \return true if the mode reporting workaround is enabled, false otherwise.
691+
*/
692+
bool getModeReportWorkaround() const;
693+
676694
}; // end Create class
677695

678696
} // namespace create

src/create.cpp

Lines changed: 15 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@ namespace create {
4242
requestedLeftVel = 0;
4343
requestedRightVel = 0;
4444
dtHistoryLength = 100;
45+
modeReportWorkaround = false;
4546
data = std::shared_ptr<Data>(new Data(model.getVersion()));
4647
if (model.getVersion() == V_1) {
4748
serial = std::make_shared<SerialQuery>(data, install_signal_handler);
@@ -1117,10 +1118,23 @@ namespace create {
11171118
return requestedRightVel;
11181119
}
11191120

1121+
void Create::setModeReportWorkaround(const bool& enable) {
1122+
modeReportWorkaround = enable;
1123+
}
1124+
1125+
bool Create::getModeReportWorkaround() const {
1126+
return modeReportWorkaround;
1127+
}
1128+
11201129
create::CreateMode Create::getMode() {
11211130
if (data->isValidPacketID(ID_OI_MODE)) {
1122-
mode = (create::CreateMode) GET_DATA(ID_OI_MODE);
1131+
if (modeReportWorkaround) {
1132+
mode = (create::CreateMode) (GET_DATA(ID_OI_MODE) - 1);
1133+
} else {
1134+
mode = (create::CreateMode) GET_DATA(ID_OI_MODE);
1135+
}
11231136
}
1137+
11241138
return mode;
11251139
}
11261140

0 commit comments

Comments
 (0)