Add support for early model Roomba 400s and other robots using the original SCI protocol.

This commit is contained in:
Ben Wolsieffer 2016-07-13 21:50:32 -04:00
parent c68a308c71
commit 618956e14c
18 changed files with 675 additions and 307 deletions

View file

@ -37,7 +37,8 @@ POSSIBILITY OF SUCH DAMAGE.
#include <string>
#include <unistd.h>
#include "create/serial.h"
#include "create/serial_stream.h"
#include "create/serial_query.h"
#include "create/data.h"
#include "create/types.h"
#include "create/util.h"
@ -68,6 +69,8 @@ namespace create {
uint8_t powerLED;
uint8_t powerLEDIntensity;
CreateMode mode;
create::Pose pose;
create::Vel vel;
@ -80,6 +83,9 @@ namespace create {
Matrix poseCovar;
float requestedLeftVel;
float requestedRightVel;
void init();
// Add two matrices and handle overflow case
Matrix addMatrices(const Matrix &A, const Matrix &B) const;
@ -94,7 +100,7 @@ namespace create {
/* Default constructor.
* Does not attempt to establish serial connection to Create.
*/
Create(RobotModel = CREATE_2);
Create(RobotModel = RobotModel::CREATE_2);
/* Attempts to establish serial connection to Create.
* \param port of your computer that is connected to Create.
@ -102,7 +108,7 @@ namespace create {
* 115200 for Create 2 and 57600 for Create 1.
* \param model type of robot.
*/
Create(const std::string& port, const int& baud, RobotModel model = CREATE_2);
Create(const std::string& port, const int& baud, RobotModel model = RobotModel::CREATE_2);
~Create();
@ -152,21 +158,21 @@ namespace create {
* turn in place clockwise = -CREATE_2_IN_PLACE_RADIUS
* \return true if successful, false otherwise
*/
bool driveRadius(const float& velocity, const float& radius) const;
bool driveRadius(const float& velocity, const float& radius);
/* Set the velocities for the left and right wheels.
* \param leftWheel velocity in m/s.
* \param rightWheel veloctiy in m/s.
* \return true if successful, false otherwise
*/
bool driveWheels(const float& leftWheel, const float& rightWheel) const;
bool driveWheels(const float& leftWheel, const float& rightWheel);
/* Set the forward and angular velocity of Create.
* \param xVel in m/s
* \param angularVel in rads/s
* \return true if successful, false otherwise
*/
bool drive(const float& xVel, const float& angularVel) const;
bool drive(const float& xVel, const float& angularVel);
/* Set the power to the side brush motor.
* \param power is in the range [-1, 1]
@ -453,10 +459,12 @@ namespace create {
float getRightWheelDistance() const;
/* Get the requested velocity (in meters/sec) of the left wheel.
* This value is bounded at the maximum velocity of the robot model.
*/
float getRequestedLeftWheelVel() const;
/* Get the requested velocity (in meters/sec) of the right wheel.
* This value is bounded at the maximum velocity of the robot model.
*/
float getRequestedRightWheelVel() const;
@ -466,7 +474,7 @@ namespace create {
/* Get the current mode reported by Create.
*/
create::CreateMode getMode() const;
create::CreateMode getMode();
/* Get the estimated position of Create based on wheel encoders.
*/

View file

@ -48,7 +48,7 @@ namespace create {
std::vector<uint8_t> ids;
public:
Data(RobotModel = CREATE_2);
Data(ProtocolVersion version = V_3);
~Data();
bool isValidPacketID(const uint8_t id) const;

View file

@ -47,39 +47,20 @@ POSSIBILITY OF SUCH DAMAGE.
namespace create {
class Serial {
private:
enum ReadState {
READ_HEADER,
READ_NBYTES,
READ_PACKET_ID,
READ_PACKET_BYTES,
READ_CHECKSUM
};
boost::shared_ptr<Data> data;
protected:
boost::asio::io_service io;
boost::asio::serial_port port;
private:
boost::thread ioThread;
boost::condition_variable dataReadyCond;
boost::mutex dataReadyMut;
ReadState readState;
bool dataReady;
bool isReading;
bool firstRead;
// These are for possible diagnostics
uint64_t corruptPackets;
uint64_t totalPackets;
// State machine variables
uint8_t headerByte;
uint8_t packetID;
uint8_t expectedNumBytes;
uint8_t byteRead;
uint16_t packetBytes;
uint8_t numBytesRead;
uint32_t byteSum;
uint8_t numDataBytesRead;
uint8_t expectedNumDataBytes;
// Callback executed when data arrives from Create
void onData(const boost::system::error_code& e, const std::size_t& size);
@ -88,11 +69,21 @@ namespace create {
// Start and stop reading data from Create
bool startReading();
void stopReading();
protected:
boost::shared_ptr<Data> data;
// These are for possible diagnostics
uint64_t corruptPackets;
uint64_t totalPackets;
virtual bool startSensorStream() = 0;
virtual void processByte(uint8_t byteRead) = 0;
// Notifies main thread that data is fresh and makes the user callback
void notifyDataReady();
public:
Serial(boost::shared_ptr<Data> data, const uint8_t& header = create::util::CREATE_2_HEADER);
Serial(boost::shared_ptr<Data> data);
~Serial();
bool connect(const std::string& port, const int& baud = 115200, boost::function<void()> cb = 0);
void disconnect();

View file

@ -0,0 +1,76 @@
/**
Software License Agreement (BSD)
\file serial_query.h
\authors Jacob Perron <jperron@sfu.ca>
\authors Ben Wolsieffer <benwolsieffer@gmail.com>
\copyright Copyright (c) 2015, Autonomy Lab (Simon Fraser University), All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice,
this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
* Neither the name of Autonomy Lab nor the names of its contributors may
be used to endorse or promote products derived from this software without
specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
*/
// Based on example from:
// https://github.com/labust/labust-ros-pkg/wiki/Create-a-Serial-Port-application
#ifndef CREATE_SERIAL_QUERY_H
#define CREATE_SERIAL_QUERY_H
#include <boost/asio.hpp>
#include <boost/thread.hpp>
#include <boost/thread/condition_variable.hpp>
#include <boost/function.hpp>
#include <boost/shared_ptr.hpp>
#include "create/data.h"
#include "create/types.h"
#include "create/util.h"
#include "create/serial.h"
namespace create {
class SerialQuery : public Serial {
private:
boost::asio::deadline_timer streamRecoveryTimer;
uint8_t packetID;
int8_t packetByte;
uint16_t packetData;
const uint8_t maxPacketID;
bool started;
void requestSensorData();
void restartSensorStream(const boost::system::error_code& err);
void flushInput();
protected:
bool startSensorStream();
void processByte(uint8_t byteRead);
public:
SerialQuery(boost::shared_ptr<Data> data);
};
} // namespace create
#endif // CREATE_SERIAL_H

View file

@ -0,0 +1,81 @@
/**
Software License Agreement (BSD)
\file serial_stream.h
\authors Jacob Perron <jperron@sfu.ca>
\copyright Copyright (c) 2015, Autonomy Lab (Simon Fraser University), All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice,
this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
* Neither the name of Autonomy Lab nor the names of its contributors may
be used to endorse or promote products derived from this software without
specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
*/
// Based on example from:
// https://github.com/labust/labust-ros-pkg/wiki/Create-a-Serial-Port-application
#ifndef CREATE_SERIAL_STREAM_H
#define CREATE_SERIAL_STREAM_H
#include <boost/asio.hpp>
#include <boost/thread.hpp>
#include <boost/thread/condition_variable.hpp>
#include <boost/function.hpp>
#include <boost/shared_ptr.hpp>
#include "create/data.h"
#include "create/types.h"
#include "create/util.h"
#include "create/serial.h"
namespace create {
class SerialStream : public Serial {
private:
enum ReadState {
READ_HEADER,
READ_NBYTES,
READ_PACKET_ID,
READ_PACKET_BYTES,
READ_CHECKSUM
};
// State machine variables
ReadState readState;
uint8_t headerByte;
uint8_t packetID;
uint8_t expectedNumBytes;
uint16_t packetBytes;
uint8_t numBytesRead;
uint32_t byteSum;
uint8_t numDataBytesRead;
uint8_t expectedNumDataBytes;
protected:
bool startSensorStream();
void processByte(uint8_t byteRead);
public:
SerialStream(boost::shared_ptr<Data> data, const uint8_t& header = create::util::STREAM_HEADER);
};
} // namespace create
#endif // CREATE_SERIAL_H

View file

@ -33,11 +33,46 @@ POSSIBILITY OF SUCH DAMAGE.
#define CREATE_TYPES_H
#include <vector>
#include <stdint.h>
#include <string>
#include <stdexcept>
namespace create {
enum RobotModel {
CREATE_1 = 0, // Roomba 400 series
CREATE_2 // Roomba 600 series
enum ProtocolVersion {
V_1 = 1,
V_2 = 2,
V_3 = 4,
V_ALL = 0xFFFFFFFF
};
class RobotModel {
public:
bool operator==(RobotModel& other) const;
operator uint32_t() const;
uint32_t getId() const;
ProtocolVersion getVersion() const;
float getAxleLength() const;
unsigned int getBaud() const;
float getMaxVelocity() const;
float getWheelDiameter() const;
static RobotModel ROOMBA_400; // Roomba 400 series
static RobotModel CREATE_1; // Roomba 500 series
static RobotModel CREATE_2; // Roomba 600 series
private:
uint32_t id;
ProtocolVersion version;
float axleLength;
unsigned int baud;
float maxVelocity;
float wheelDiameter;
RobotModel(const ProtocolVersion version, const float axleLength, const unsigned int baud, const float maxVelocity = 0.5, const float wheelDiameter = 0.078);
static uint32_t nextId;
};
enum SensorPacketID {
@ -60,8 +95,8 @@ namespace create {
ID_CLIFF_RIGHT = 12,
ID_VIRTUAL_WALL = 13,
ID_OVERCURRENTS = 14,
ID_DIRT_DETECT = 15,
ID_UNUSED_1 = 16,
ID_DIRT_DETECT_LEFT = 15,
ID_DIRT_DETECT_RIGHT = 16,
ID_IR_OMNI = 17,
ID_IR_LEFT = 52,
ID_IR_RIGHT = 53,
@ -79,8 +114,8 @@ namespace create {
ID_CLIFF_FRONT_LEFT_SIGNAL = 29,
ID_CLIFF_FRONT_RIGHT_SIGNAL = 30,
ID_CLIFF_RIGHT_SIGNAL = 31,
ID_UNUSED_2 = 32,
ID_UNUSED_3 = 33,
ID_CARGO_BAY_DIGITAL_INPUTS = 32,
ID_CARGO_BAY_ANALOG_SIGNAL = 33,
ID_CHARGE_SOURCE = 34,
ID_OI_MODE = 35,
ID_SONG_NUM = 36,
@ -112,6 +147,7 @@ namespace create {
OC_RESET = 7,
OC_STOP = 173,
OC_BAUD = 129,
OC_CONTROL = 130,
OC_SAFE = 131,
OC_FULL = 132,
OC_CLEAN = 135,

View file

@ -40,17 +40,12 @@ POSSIBILITY OF SUCH DAMAGE.
namespace create {
namespace util {
static const float CREATE_1_AXLE_LENGTH = 0.26;
static const uint8_t CREATE_2_HEADER = 19;
static const float CREATE_2_AXLE_LENGTH = 0.235;
static const float CREATE_2_TICKS_PER_REV = 508.8;
static const uint32_t CREATE_2_MAX_ENCODER_TICKS = 65535;
static const float CREATE_2_WHEEL_DIAMETER = 0.078;
static const float CREATE_2_MAX_VEL = 0.5;
static const float CREATE_2_MAX_RADIUS = 2.0;
static const float CREATE_2_STRAIGHT_RADIUS = 32.768;
static const float CREATE_2_IN_PLACE_RADUIS = 0.001;
static const uint8_t STREAM_HEADER = 19;
static const float V_3_TICKS_PER_REV = 508.8;
static const uint32_t V_3_MAX_ENCODER_TICKS = 65535;
static const float MAX_RADIUS = 2.0;
static const float STRAIGHT_RADIUS = 32.768;
static const float IN_PLACE_RADIUS = 0.001;
static const float PI = 3.14159;
static const float TWO_PI = 6.28318;
static const float EPS = 0.0001;