From b0e8259510d5fa24149395a3341377650547899c Mon Sep 17 00:00:00 2001 From: Ben Wolsieffer Date: Fri, 24 Jun 2016 17:46:20 -0400 Subject: [PATCH 001/108] Fix odometry inversion for Create 1. --- src/create.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/create.cpp b/src/create.cpp index f2c7468..b3d7f0e 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -103,7 +103,7 @@ namespace create { deltaDist = ((int16_t) GET_DATA(ID_DISTANCE)) / 1000.0; //mm -> m deltaYaw = ((int16_t) GET_DATA(ID_ANGLE)) * (util::PI / 180.0); // D2R deltaX = deltaDist * cos( util::normalizeAngle(pose.yaw + deltaYaw) ); - deltaY = -deltaDist * sin( util::normalizeAngle(pose.yaw + deltaYaw) ); + deltaY = deltaDist * sin( util::normalizeAngle(pose.yaw + deltaYaw) ); leftWheelDist = deltaDist / 2.0; rightWheelDist = leftWheelDist; From b8002c04566731f8dab34cf9d8e883de51c4f7c3 Mon Sep 17 00:00:00 2001 From: Ben Wolsieffer Date: Fri, 24 Jun 2016 22:20:24 -0400 Subject: [PATCH 002/108] Manually link to thread library. This allows libcreate to build on ARM. --- CMakeLists.txt | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index f029641..727852b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,6 +2,7 @@ cmake_minimum_required(VERSION 2.8.3) project(libcreate) find_package(Boost REQUIRED system thread) +find_package(Threads REQUIRED) ## Specify additional locations of header files include_directories( @@ -16,6 +17,15 @@ add_library(create src/packet.cpp ) +if(THREADS_HAVE_PTHREAD_ARG) + set_property(TARGET create PROPERTY COMPILE_OPTIONS "-pthread") + set_property(TARGET create PROPERTY INTERFACE_COMPILE_OPTIONS "-pthread") +endif() + +if(CMAKE_THREAD_LIBS_INIT) + target_link_libraries(create "${CMAKE_THREAD_LIBS_INIT}") +endif() + target_link_libraries(create ${Boost_LIBRARIES} ) From d6f759d6831f848602bd1849075cc3b873f1e838 Mon Sep 17 00:00:00 2001 From: Ben Wolsieffer Date: Thu, 23 Jun 2016 16:27:05 -0400 Subject: [PATCH 003/108] Expose individual wheel distances and requested velocities. Fix wheel distance calculation for the Create 1. --- include/create/create.h | 20 ++++++++++++++++-- include/create/util.h | 2 ++ src/create.cpp | 45 ++++++++++++++++++++++++++++++++++++++--- src/data.cpp | 4 ++-- 4 files changed, 64 insertions(+), 7 deletions(-) diff --git a/include/create/create.h b/include/create/create.h index 640bb88..3d37e97 100644 --- a/include/create/create.h +++ b/include/create/create.h @@ -73,8 +73,8 @@ namespace create { uint32_t prevTicksLeft; uint32_t prevTicksRight; - float prevLeftVel; - float prevRightVel; + float totalLeftDist; + float totalRightDist; bool firstOnData; util::timestamp_t prevOnDataTime; @@ -444,6 +444,22 @@ namespace create { */ bool isMovingForward() const; + /* Get the total distance (in meters) the left wheel has moved. + */ + float getLeftWheelDistance() const; + + /* Get the total distance (in meters) the right wheel has moved. + */ + float getRightWheelDistance() const; + + /* Get the requested velocity (in meters/sec) of the left wheel. + */ + float getRequestedLeftWheelVel() const; + + /* Get the requested velocity (in meters/sec) of the right wheel. + */ + float getRequestedRightWheelVel() const; + /* Get the current charging state. */ create::ChargingState getChargingState() const; diff --git a/include/create/util.h b/include/create/util.h index 62e2bbb..7304209 100644 --- a/include/create/util.h +++ b/include/create/util.h @@ -40,6 +40,8 @@ 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; diff --git a/src/create.cpp b/src/create.cpp index f2c7468..3d21fe8 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -28,6 +28,8 @@ namespace create { powerLEDIntensity = 0; prevTicksLeft = 0; prevTicksRight = 0; + totalLeftDist = 0.0; + totalRightDist = 0.0; firstOnData = true; pose.x = 0; pose.y = 0; @@ -104,9 +106,9 @@ namespace create { deltaYaw = ((int16_t) GET_DATA(ID_ANGLE)) * (util::PI / 180.0); // D2R deltaX = deltaDist * cos( util::normalizeAngle(pose.yaw + deltaYaw) ); deltaY = -deltaDist * sin( util::normalizeAngle(pose.yaw + deltaYaw) ); - leftWheelDist = deltaDist / 2.0; - rightWheelDist = leftWheelDist; - + const float deltaYawWheelDist = (util::CREATE_1_AXLE_LENGTH / 2.0) * deltaYaw; + leftWheelDist = deltaDist - deltaYawWheelDist; + rightWheelDist = deltaDist + deltaYawWheelDist; } else if (model == CREATE_2) { // Get cumulative ticks (wraps around at 65535) @@ -149,6 +151,9 @@ namespace create { } } // if CREATE_2 + totalLeftDist += leftWheelDist; + totalRightDist += rightWheelDist; + if (fabs(dt) > util::EPS) { vel.x = deltaDist / dt; vel.y = 0.0; @@ -863,6 +868,40 @@ namespace create { } } + float Create::getLeftWheelDistance() const { + return totalLeftDist; + } + + float Create::getRightWheelDistance() const { + return totalRightDist; + } + + float Create::getRequestedLeftWheelVel() const { + if (data->isValidPacketID(ID_LEFT_VEL)) { + uint16_t uvel = GET_DATA(ID_LEFT_VEL); + int16_t vel; + std::memcpy(&vel, &uvel, sizeof(vel)); + return (vel / 1000.0); + } + else { + CERR("[create::Create] ", "Left wheel velocity not supported!"); + return 0; + } + } + + float Create::getRequestedRightWheelVel() const { + if (data->isValidPacketID(ID_RIGHT_VEL)) { + uint16_t uvel = GET_DATA(ID_RIGHT_VEL); + int16_t vel; + std::memcpy(&vel, &uvel, sizeof(vel)); + return (vel / 1000.0); + } + else { + CERR("[create::Create] ", "Right wheel velocity not supported!"); + return 0; + } + } + create::CreateMode Create::getMode() const { if (data->isValidPacketID(ID_OI_MODE)) { return (create::CreateMode) GET_DATA(ID_OI_MODE); diff --git a/src/data.cpp b/src/data.cpp index 4960fed..198bcca 100644 --- a/src/data.cpp +++ b/src/data.cpp @@ -26,6 +26,8 @@ namespace create { ADD_PACKET(ID_CAPACITY, 2, "battery_capacity"); ADD_PACKET(ID_VIRTUAL_WALL, 1, "virtual_wall"); ADD_PACKET(ID_OI_MODE, 1, "oi_mode"); + ADD_PACKET(ID_RIGHT_VEL, 2, "velocity_right"); + ADD_PACKET(ID_LEFT_VEL, 2, "velocity_left"); if (model == CREATE_1) { ADD_PACKET(ID_DISTANCE, 2, "distance"); @@ -48,8 +50,6 @@ namespace create { //ADD_PACKET(ID_NUM_STREAM_PACKETS, 1, "oi_stream_num_packets"); //ADD_PACKET(ID_VEL, 2, "velocity"); //ADD_PACKET(ID_RADIUS, 2, "radius"); - //ADD_PACKET(ID_RIGHT_VEL, 2, "velocity_right"); - //ADD_PACKET(ID_LEFT_VEL, 2, "velocity_left"); ADD_PACKET(ID_LEFT_ENC, 2, "enc_counts_left"); ADD_PACKET(ID_RIGHT_ENC, 2, "enc_counts_right"); ADD_PACKET(ID_LIGHT, 1, "light_bumper"); From 000dc9cf29482edbf90d1669084cc503bab72099 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Tue, 28 Jun 2016 15:50:40 -0700 Subject: [PATCH 004/108] Update README.md --- README.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index bbe6737..6f31b4c 100644 --- a/README.md +++ b/README.md @@ -5,7 +5,7 @@ C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com * Documentation: TODO * Code API: TODO * Author: [Jacob Perron](http://jacobperron.ca) ([Autonomy Lab](http://autonomylab.org), [Simon Fraser University](http://www.sfu.ca)) -* Contributors: [Mani Monajjemi](http:mani.im) +* Contributors: [Mani Monajjemi](http:mani.im), [Ben Wolsieffer](https://github.com/lopsided98) ## Dependencies @@ -27,6 +27,7 @@ Example compile line: `g++ create_demo.cpp -lcreate -lboost_system -lboost_threa ## Bugs * _Clock_ and _Schedule_ button presses are not detected. This is a known problem to the developers at iRobot. +* Inaccurate odometry angle for Create 1 ([#22](https://github.com/AutonomyLab/libcreate/issues/22)) ## Build Status From 618956e14cfe2899f15b5cce8e70df4c9a5db3e2 Mon Sep 17 00:00:00 2001 From: Ben Wolsieffer Date: Wed, 13 Jul 2016 21:50:32 -0400 Subject: [PATCH 005/108] Add support for early model Roomba 400s and other robots using the original SCI protocol. --- CMakeLists.txt | 3 + README.md | 6 +- examples/bumper_example.cpp | 2 +- examples/create_demo.cpp | 4 +- examples/odom_example.cpp | 4 +- include/create/create.h | 22 ++- include/create/data.h | 2 +- include/create/serial.h | 39 ++--- include/create/serial_query.h | 76 ++++++++++ include/create/serial_stream.h | 81 ++++++++++ include/create/types.h | 50 ++++++- include/create/util.h | 17 +-- src/create.cpp | 261 ++++++++++++++++++++------------- src/data.cpp | 96 +++++------- src/serial.cpp | 94 +----------- src/serial_query.cpp | 70 +++++++++ src/serial_stream.cpp | 103 +++++++++++++ src/types.cpp | 52 +++++++ 18 files changed, 675 insertions(+), 307 deletions(-) create mode 100644 include/create/serial_query.h create mode 100644 include/create/serial_stream.h create mode 100644 src/serial_query.cpp create mode 100644 src/serial_stream.cpp create mode 100644 src/types.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 727852b..ea5e467 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -13,8 +13,11 @@ include_directories( add_library(create src/create.cpp src/serial.cpp + src/serial_stream.cpp + src/serial_query.cpp src/data.cpp src/packet.cpp + src/types.cpp ) if(THREADS_HAVE_PTHREAD_ARG) diff --git a/README.md b/README.md index 6f31b4c..22cc852 100644 --- a/README.md +++ b/README.md @@ -1,9 +1,13 @@ # libcreate -C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com/About-iRobot/STEM/Create-2.aspx). This library forms the basis of the ROS driver in [create_autonomy](https://github.com/autonomylab/create_autonomy). +C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com/About-iRobot/STEM/Create-2.aspx) as well as most models of Roombas. This library forms the basis of the ROS driver in [create_autonomy](https://github.com/autonomylab/create_autonomy). * Documentation: TODO * Code API: TODO +* Protocol documentation: + - [`V_1`](http://www.ecsl.cs.sunysb.edu/mint/Roomba_SCI_Spec_Manual.pdf) (Roomba 400 series ) + - [`V_2`](http://www.irobot.com/filelibrary/pdfs/hrd/create/Create%20Open%20Interface_v2.pdf) (Create 1, Roomba 500 series) + - [`V_3`](https://cdn-shop.adafruit.com/datasheets/create_2_Open_Interface_Spec.pdf) (Create 2, Roomba 600-800 series) * Author: [Jacob Perron](http://jacobperron.ca) ([Autonomy Lab](http://autonomylab.org), [Simon Fraser University](http://www.sfu.ca)) * Contributors: [Mani Monajjemi](http:mani.im), [Ben Wolsieffer](https://github.com/lopsided98) diff --git a/examples/bumper_example.cpp b/examples/bumper_example.cpp index e6543ee..11e0ab8 100644 --- a/examples/bumper_example.cpp +++ b/examples/bumper_example.cpp @@ -3,7 +3,7 @@ int main(int argc, char** argv) { std::string port = "/dev/ttyUSB0"; int baud = 115200; - create::RobotModel model = create::CREATE_2; + create::RobotModel model = create::RobotModel::CREATE_2; create::Create* robot = new create::Create(model); diff --git a/examples/create_demo.cpp b/examples/create_demo.cpp index 668014b..243eaa6 100644 --- a/examples/create_demo.cpp +++ b/examples/create_demo.cpp @@ -5,10 +5,10 @@ create::Create* robot; int main(int argc, char** argv) { std::string port = "/dev/ttyUSB0"; int baud = 115200; - create::RobotModel model = create::CREATE_2; + create::RobotModel model = create::RobotModel::CREATE_2; if (argc > 1 && std::string(argv[1]) == "create1") { - model = create::CREATE_1; + model = create::RobotModel::CREATE_1; baud = 57600; std::cout << "1st generation Create selected" << std::endl; } diff --git a/examples/odom_example.cpp b/examples/odom_example.cpp index c45c5c7..4499f9f 100644 --- a/examples/odom_example.cpp +++ b/examples/odom_example.cpp @@ -5,10 +5,10 @@ create::Create* robot; int main(int argc, char** argv) { std::string port = "/dev/ttyUSB0"; int baud = 115200; - create::RobotModel model = create::CREATE_2; + create::RobotModel model = create::RobotModel::CREATE_2; if (argc > 1 && std::string(argv[1]) == "create1") { - model = create::CREATE_1; + model = create::RobotModel::CREATE_1; baud = 57600; std::cout << "1st generation Create selected" << std::endl; } diff --git a/include/create/create.h b/include/create/create.h index 3d37e97..bc2f39b 100644 --- a/include/create/create.h +++ b/include/create/create.h @@ -37,7 +37,8 @@ POSSIBILITY OF SUCH DAMAGE. #include #include -#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. */ diff --git a/include/create/data.h b/include/create/data.h index 02728f8..345bd1a 100644 --- a/include/create/data.h +++ b/include/create/data.h @@ -48,7 +48,7 @@ namespace create { std::vector ids; public: - Data(RobotModel = CREATE_2); + Data(ProtocolVersion version = V_3); ~Data(); bool isValidPacketID(const uint8_t id) const; diff --git a/include/create/serial.h b/include/create/serial.h index 2f641e7..9dd9bc3 100644 --- a/include/create/serial.h +++ b/include/create/serial.h @@ -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; + 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; + // 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, const uint8_t& header = create::util::CREATE_2_HEADER); + Serial(boost::shared_ptr data); ~Serial(); bool connect(const std::string& port, const int& baud = 115200, boost::function cb = 0); void disconnect(); diff --git a/include/create/serial_query.h b/include/create/serial_query.h new file mode 100644 index 0000000..033785a --- /dev/null +++ b/include/create/serial_query.h @@ -0,0 +1,76 @@ +/** +Software License Agreement (BSD) + +\file serial_query.h +\authors Jacob Perron +\authors Ben Wolsieffer +\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 +#include +#include +#include +#include + +#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); + }; +} // namespace create + +#endif // CREATE_SERIAL_H diff --git a/include/create/serial_stream.h b/include/create/serial_stream.h new file mode 100644 index 0000000..d59d126 --- /dev/null +++ b/include/create/serial_stream.h @@ -0,0 +1,81 @@ +/** +Software License Agreement (BSD) + +\file serial_stream.h +\authors Jacob Perron +\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 +#include +#include +#include +#include + +#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, const uint8_t& header = create::util::STREAM_HEADER); + + }; +} // namespace create + +#endif // CREATE_SERIAL_H diff --git a/include/create/types.h b/include/create/types.h index 1495094..ffbce6c 100644 --- a/include/create/types.h +++ b/include/create/types.h @@ -33,11 +33,46 @@ POSSIBILITY OF SUCH DAMAGE. #define CREATE_TYPES_H #include +#include +#include +#include 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, diff --git a/include/create/util.h b/include/create/util.h index 7304209..bbeaacd 100644 --- a/include/create/util.h +++ b/include/create/util.h @@ -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; diff --git a/src/create.cpp b/src/create.cpp index c34764a..1c6048f 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -8,7 +8,8 @@ #include "create/create.h" #define GET_DATA(id) (data->getPacket(id)->getData()) -#define BOUND(val,min,max) (valmax?val=max:val=val)) +#define BOUND_CONST(val,min,max) (valmax?max:val)) +#define BOUND(val,min,max) (val = BOUND_CONST(val,min,max)) namespace create { @@ -31,6 +32,7 @@ namespace create { totalLeftDist = 0.0; totalRightDist = 0.0; firstOnData = true; + mode = MODE_OFF; pose.x = 0; pose.y = 0; pose.yaw = 0; @@ -40,8 +42,14 @@ namespace create { vel.yaw = 0; vel.covariance = std::vector(9, 0.0); poseCovar = Matrix(3, 3, 0.0); - data = boost::shared_ptr(new Data(model)); - serial = boost::make_shared(data); + requestedLeftVel = 0; + requestedRightVel = 0; + data = boost::shared_ptr(new Data(model.getVersion())); + if (model.getVersion() == V_1) { + serial = boost::make_shared(data); + } else { + serial = boost::make_shared(data); + } } Create::Create(RobotModel m) : model(m) { @@ -83,7 +91,7 @@ namespace create { void Create::onData() { if (firstOnData) { - if (model == CREATE_2) { + if (model.getVersion() >= V_3) { // Initialize tick counts prevTicksLeft = GET_DATA(ID_LEFT_ENC); prevTicksRight = GET_DATA(ID_RIGHT_ENC); @@ -95,22 +103,45 @@ namespace create { // Get current time util::timestamp_t curTime = util::getTimestamp(); float dt = (curTime - prevOnDataTime) / 1000000.0; - float deltaDist, deltaX, deltaY, deltaYaw, leftWheelDist, rightWheelDist; - if (model == CREATE_1) { - /* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * - * Angle returned is NOT correct if your robot is using older firmware: * - * http://answers.ros.org/question/31935/createroomba-odometry/ * - * TODO: Consider using velocity command as substitute for pose estimation. * - * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ - deltaDist = ((int16_t) GET_DATA(ID_DISTANCE)) / 1000.0; //mm -> m - deltaYaw = ((int16_t) GET_DATA(ID_ANGLE)) * (util::PI / 180.0); // D2R - deltaX = deltaDist * cos( util::normalizeAngle(pose.yaw + deltaYaw) ); - deltaY = deltaDist * sin( util::normalizeAngle(pose.yaw + deltaYaw) ); - const float deltaYawWheelDist = (util::CREATE_1_AXLE_LENGTH / 2.0) * deltaYaw; - leftWheelDist = deltaDist - deltaYawWheelDist; - rightWheelDist = deltaDist + deltaYawWheelDist; + float deltaDist, deltaX, deltaY, deltaYaw, leftWheelDist, rightWheelDist, wheelDistDiff; + + // Protocol versions 1 and 2 use distance and angle fields for odometry + int16_t angleField; + if (model.getVersion() <= V_2) { + // This is a standards compliant way of doing unsigned to signed conversion + uint16_t distanceRaw = GET_DATA(ID_DISTANCE); + int16_t distance; + std::memcpy(&distance, &distanceRaw, sizeof(distance)); + deltaDist = distance / 1000.0; // mm -> m + + // Angle is processed differently in versions 1 and 2 + uint16_t angleRaw = GET_DATA(ID_ANGLE); + std::memcpy(&angleField, &angleRaw, sizeof(angleField)); } - else if (model == CREATE_2) { + + if (model.getVersion() == V_1) { + wheelDistDiff = 2.0 * angleField / 1000.0; + leftWheelDist = deltaDist - (wheelDistDiff / 2.0); + rightWheelDist = deltaDist + (wheelDistDiff / 2.0); + deltaYaw = wheelDistDiff / model.getAxleLength(); + } else if (model.getVersion() == V_2) { + /* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + * Certain older Creates have major problems with odometry * + * http://answers.ros.org/question/31935/createroomba-odometry/ * + * * + * All Creates have an issue with rounding of the angle field, which causes * + * major errors to accumulate in the odometry yaw. * + * http://wiki.tekkotsu.org/index.php/Create_Odometry_Bug * + * https://github.com/AutonomyLab/create_autonomy/issues/28 * + * * + * TODO: Consider using velocity command as substitute for pose estimation * + * to mitigate both of these problems. * + * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ + deltaYaw = angleField * (util::PI / 180.0); // D2R + wheelDistDiff = model.getAxleLength() * deltaYaw; + leftWheelDist = deltaDist - (wheelDistDiff / 2.0); + rightWheelDist = deltaDist + (wheelDistDiff / 2.0); + } else if (model.getVersion() >= V_3) { // Get cumulative ticks (wraps around at 65535) uint16_t totalTicksLeft = GET_DATA(ID_LEFT_ENC); uint16_t totalTicksRight = GET_DATA(ID_RIGHT_ENC); @@ -121,35 +152,33 @@ namespace create { prevTicksRight = totalTicksRight; // Handle wrap around - if (fabs(ticksLeft) > 0.9 * util::CREATE_2_MAX_ENCODER_TICKS) { - ticksLeft = (ticksLeft % util::CREATE_2_MAX_ENCODER_TICKS) + 1; + if (fabs(ticksLeft) > 0.9 * util::V_3_MAX_ENCODER_TICKS) { + ticksLeft = (ticksLeft % util::V_3_MAX_ENCODER_TICKS) + 1; } - if (fabs(ticksRight) > 0.9 * util::CREATE_2_MAX_ENCODER_TICKS) { - ticksRight = (ticksRight % util::CREATE_2_MAX_ENCODER_TICKS) + 1; + if (fabs(ticksRight) > 0.9 * util::V_3_MAX_ENCODER_TICKS) { + ticksRight = (ticksRight % util::V_3_MAX_ENCODER_TICKS) + 1; } // Compute distance travelled by each wheel - leftWheelDist = (ticksLeft / util::CREATE_2_TICKS_PER_REV) - * util::CREATE_2_WHEEL_DIAMETER * util::PI; - rightWheelDist = (ticksRight / util::CREATE_2_TICKS_PER_REV) - * util::CREATE_2_WHEEL_DIAMETER * util::PI; - - float wheelDistDiff = rightWheelDist - leftWheelDist; + leftWheelDist = (ticksLeft / util::V_3_TICKS_PER_REV) + * model.getWheelDiameter() * util::PI; + rightWheelDist = (ticksRight / util::V_3_TICKS_PER_REV) + * model.getWheelDiameter() * util::PI; deltaDist = (rightWheelDist + leftWheelDist) / 2.0; - // Moving straight - if (fabs(wheelDistDiff) < util::EPS) { - deltaX = deltaDist * cos(pose.yaw); - deltaY = deltaDist * sin(pose.yaw); - deltaYaw = 0.0; - } - else { - float turnRadius = (util::CREATE_2_AXLE_LENGTH / 2.0) * (leftWheelDist + rightWheelDist) / wheelDistDiff; - deltaYaw = wheelDistDiff / util::CREATE_2_AXLE_LENGTH; - deltaX = turnRadius * (sin(pose.yaw + deltaYaw) - sin(pose.yaw)); - deltaY = -turnRadius * (cos(pose.yaw + deltaYaw) - cos(pose.yaw)); - } - } // if CREATE_2 + wheelDistDiff = rightWheelDist - leftWheelDist; + deltaYaw = wheelDistDiff / model.getAxleLength(); + } + + // Moving straight + if (fabs(wheelDistDiff) < util::EPS) { + deltaX = deltaDist * cos(pose.yaw); + deltaY = deltaDist * sin(pose.yaw); + } else { + float turnRadius = (model.getAxleLength() / 2.0) * (leftWheelDist + rightWheelDist) / wheelDistDiff; + deltaX = turnRadius * (sin(pose.yaw + deltaYaw) - sin(pose.yaw)); + deltaY = -turnRadius * (cos(pose.yaw + deltaYaw) - cos(pose.yaw)); + } totalLeftDist += leftWheelDist; totalRightDist += rightWheelDist; @@ -158,8 +187,7 @@ namespace create { vel.x = deltaDist / dt; vel.y = 0.0; vel.yaw = deltaYaw / dt; - } - else { + } else { vel.x = 0.0; vel.y = 0.0; vel.yaw = 0.0; @@ -171,7 +199,7 @@ namespace create { float kl = 1.0; float cosYawAndHalfDelta = cos(pose.yaw + (deltaYaw / 2.0)); // deltaX? float sinYawAndHalfDelta = sin(pose.yaw + (deltaYaw / 2.0)); // deltaY? - float distOverTwoWB = deltaDist / (util::CREATE_2_AXLE_LENGTH * 2.0); + float distOverTwoWB = deltaDist / (model.getAxleLength() * 2.0); Matrix invCovar(2, 2); invCovar(0, 0) = kr * fabs(rightWheelDist); @@ -184,8 +212,8 @@ namespace create { Finc(0, 1) = (cosYawAndHalfDelta / 2.0) + (distOverTwoWB * sinYawAndHalfDelta); Finc(1, 0) = (sinYawAndHalfDelta / 2.0) + (distOverTwoWB * cosYawAndHalfDelta); Finc(1, 1) = (sinYawAndHalfDelta / 2.0) - (distOverTwoWB * cosYawAndHalfDelta); - Finc(2, 0) = (1.0 / util::CREATE_2_AXLE_LENGTH); - Finc(2, 1) = (-1.0 / util::CREATE_2_AXLE_LENGTH); + Finc(2, 0) = (1.0 / model.getAxleLength()); + Finc(2, 1) = (-1.0 / model.getAxleLength()); Matrix FincT = boost::numeric::ublas::trans(Finc); Matrix Fp(3, 3); @@ -271,24 +299,39 @@ namespace create { //} bool Create::setMode(const CreateMode& mode) { + if (model.getVersion() == V_1){ + // Switch to safe mode (required for compatibility with V_1) + if (!(serial->sendOpcode(OC_START) && serial->sendOpcode(OC_CONTROL))) return false; + } + bool ret; switch (mode) { case MODE_OFF: - return serial->sendOpcode(OC_POWER); + if (model.getVersion() == V_2) { + CERR("[create::Create] ", "protocol version 2 does not support turning robot off"); + ret = false; + } else { + ret = serial->sendOpcode(OC_POWER); + } break; case MODE_PASSIVE: - return serial->sendOpcode(OC_START); + ret = serial->sendOpcode(OC_START); break; case MODE_SAFE: - return serial->sendOpcode(OC_SAFE); + if (model.getVersion() > V_1) { + ret = serial->sendOpcode(OC_SAFE); + } break; case MODE_FULL: - return serial->sendOpcode(OC_FULL); + ret = serial->sendOpcode(OC_FULL); break; default: CERR("[create::Create] ", "cannot set robot to mode '" << mode << "'"); - break; + ret = false; } - return false; + if (ret) { + this->mode = mode; + } + return ret; } bool Create::clean(const CleanMode& mode) { @@ -309,16 +352,18 @@ namespace create { return serial->send(cmd, 4); } - bool Create::driveRadius(const float& vel, const float& radius) const { + bool Create::driveRadius(const float& vel, const float& radius) { + // Bound velocity + float boundedVel = BOUND_CONST(vel, -model.getMaxVelocity(), model.getMaxVelocity()); + // Expects each parameter as two bytes each and in millimeters - int16_t vel_mm = roundf(vel * 1000); + int16_t vel_mm = roundf(boundedVel * 1000); int16_t radius_mm = roundf(radius * 1000); - BOUND(vel_mm, -util::CREATE_2_MAX_VEL * 1000, util::CREATE_2_MAX_VEL * 1000); // Bound radius if not a special case if (radius_mm != 32768 && radius_mm != 32767 && radius_mm != -1 && radius_mm != 1) { - BOUND(radius_mm, -util::CREATE_2_MAX_RADIUS, util::CREATE_2_MAX_RADIUS); + BOUND(radius_mm, -util::MAX_RADIUS * 1000, util::MAX_RADIUS * 1000); } uint8_t cmd[5] = { OC_DRIVE, @@ -331,25 +376,58 @@ namespace create { return serial->send(cmd, 5); } - bool Create::driveWheels(const float& leftVel, const float& rightVel) const { - int16_t leftCmd = roundf(leftVel * 1000); - int16_t rightCmd = roundf(rightVel * 1000); - BOUND(leftCmd, -util::CREATE_2_MAX_VEL * 1000, util::CREATE_2_MAX_VEL * 1000); - BOUND(rightCmd, -util::CREATE_2_MAX_VEL * 1000, util::CREATE_2_MAX_VEL * 1000); + bool Create::driveWheels(const float& leftVel, const float& rightVel) { + const float boundedLeftVel = BOUND_CONST(leftVel, -model.getMaxVelocity(), model.getMaxVelocity()); + const float boundedRightVel = BOUND_CONST(rightVel, -model.getMaxVelocity(), model.getMaxVelocity()); + requestedLeftVel = boundedLeftVel; + requestedRightVel = boundedRightVel; + if (model.getVersion() > V_1) { + int16_t leftCmd = roundf(boundedLeftVel * 1000); + int16_t rightCmd = roundf(boundedRightVel * 1000); - uint8_t cmd[5] = { OC_DRIVE_DIRECT, - rightCmd >> 8, - rightCmd & 0xff, - leftCmd >> 8, - leftCmd & 0xff - }; - return serial->send(cmd, 5); + uint8_t cmd[5] = { OC_DRIVE_DIRECT, + rightCmd >> 8, + rightCmd & 0xff, + leftCmd >> 8, + leftCmd & 0xff + }; + return serial->send(cmd, 5); + } else { + float radius; + // Prevent divide by zero when driving straight + if (boundedLeftVel != boundedRightVel) { + radius = -((model.getAxleLength() / 2.0) * (boundedLeftVel + boundedRightVel)) / + (boundedLeftVel - boundedRightVel); + } else { + radius = util::STRAIGHT_RADIUS; + } + + float vel; + // Fix signs for spin in place + if (boundedLeftVel == -boundedRightVel || std::abs(roundf(radius * 1000)) <= 1) { + radius = util::IN_PLACE_RADIUS; + vel = boundedRightVel; + } else { + vel = (std::abs(boundedLeftVel) + std::abs(boundedRightVel)) / 2.0 * ((boundedLeftVel + boundedRightVel) > 0 ? 1.0 : -1.0); + } + + // Radius turns have a maximum radius of 2.0 meters + // When the radius is > 2 but <= 10, use a 2 meter radius + // When it is > 10, drive straight + // TODO: alternate between these 2 meter radius and straight to + // fake a larger radius + if (radius > 10.0) { + radius = util::STRAIGHT_RADIUS; + } + + return driveRadius(vel, radius); + } } - bool Create::drive(const float& xVel, const float& angularVel) const { + bool Create::drive(const float& xVel, const float& angularVel) { // Compute left and right wheel velocities - float leftVel = xVel - ((util::CREATE_2_AXLE_LENGTH / 2.0) * angularVel); - float rightVel = xVel + ((util::CREATE_2_AXLE_LENGTH / 2.0) * angularVel); + float leftVel = xVel - ((model.getAxleLength() / 2.0) * angularVel); + float rightVel = xVel + ((model.getAxleLength() / 2.0) * angularVel); return driveWheels(leftVel, rightVel); } @@ -552,8 +630,8 @@ namespace create { } uint8_t Create::getDirtDetect() const { - if (data->isValidPacketID(ID_DIRT_DETECT)) { - return GET_DATA(ID_DIRT_DETECT); + if (data->isValidPacketID(ID_DIRT_DETECT_LEFT)) { + return GET_DATA(ID_DIRT_DETECT_LEFT); } else { CERR("[create::Create] ", "Dirt detector not supported!"); @@ -869,47 +947,26 @@ namespace create { } float Create::getLeftWheelDistance() const { - return totalLeftDist; + return totalLeftDist; } float Create::getRightWheelDistance() const { - return totalRightDist; + return totalRightDist; } float Create::getRequestedLeftWheelVel() const { - if (data->isValidPacketID(ID_LEFT_VEL)) { - uint16_t uvel = GET_DATA(ID_LEFT_VEL); - int16_t vel; - std::memcpy(&vel, &uvel, sizeof(vel)); - return (vel / 1000.0); - } - else { - CERR("[create::Create] ", "Left wheel velocity not supported!"); - return 0; - } + return requestedLeftVel; } float Create::getRequestedRightWheelVel() const { - if (data->isValidPacketID(ID_RIGHT_VEL)) { - uint16_t uvel = GET_DATA(ID_RIGHT_VEL); - int16_t vel; - std::memcpy(&vel, &uvel, sizeof(vel)); - return (vel / 1000.0); - } - else { - CERR("[create::Create] ", "Right wheel velocity not supported!"); - return 0; - } + return requestedRightVel; } - create::CreateMode Create::getMode() const { + create::CreateMode Create::getMode() { if (data->isValidPacketID(ID_OI_MODE)) { - return (create::CreateMode) GET_DATA(ID_OI_MODE); - } - else { - CERR("[create::Create] ", "Querying Mode not supported!"); - return create::MODE_UNAVAILABLE; + mode = (create::CreateMode) GET_DATA(ID_OI_MODE); } + return mode; } Pose Create::getPose() const { diff --git a/src/data.cpp b/src/data.cpp index 198bcca..ef226e8 100644 --- a/src/data.cpp +++ b/src/data.cpp @@ -1,72 +1,50 @@ #include "create/data.h" -#define ADD_PACKET(id,nbytes,info) (packets[id]=boost::make_shared(nbytes,info)) +#define ADD_PACKET(id,nbytes,info,enabledVersion) if ((enabledVersion) & version) packets[id]=boost::make_shared(nbytes,info) namespace create { - Data::Data(RobotModel model) { + Data::Data(ProtocolVersion version) { // Populate data map /* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * WARNING: Adding too many packets will flood the serial * * buffer and corrupt the stream. * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ - ADD_PACKET(ID_BUMP_WHEELDROP, 1, "bumps_wheeldrops"); - ADD_PACKET(ID_WALL, 1, "wall"); - ADD_PACKET(ID_CLIFF_LEFT, 1, "cliff_left"); - ADD_PACKET(ID_CLIFF_FRONT_LEFT, 1, "cliff_front_left"); - ADD_PACKET(ID_CLIFF_FRONT_RIGHT, 1, "cliff_front_right"); - ADD_PACKET(ID_CLIFF_RIGHT, 1, "cliff_right"); - ADD_PACKET(ID_IR_OMNI, 1, "ir_opcode"); - ADD_PACKET(ID_BUTTONS, 1, "buttons"); - ADD_PACKET(ID_CHARGE_STATE, 1, "charging_state"); - ADD_PACKET(ID_VOLTAGE, 2, "voltage"); - ADD_PACKET(ID_CURRENT, 2, "current"); - ADD_PACKET(ID_TEMP, 1, "temperature"); - ADD_PACKET(ID_CHARGE , 2, "battery_charge"); - ADD_PACKET(ID_CAPACITY, 2, "battery_capacity"); - ADD_PACKET(ID_VIRTUAL_WALL, 1, "virtual_wall"); - ADD_PACKET(ID_OI_MODE, 1, "oi_mode"); - ADD_PACKET(ID_RIGHT_VEL, 2, "velocity_right"); - ADD_PACKET(ID_LEFT_VEL, 2, "velocity_left"); - - if (model == CREATE_1) { - ADD_PACKET(ID_DISTANCE, 2, "distance"); - ADD_PACKET(ID_ANGLE, 2, "angle"); - } - else if (model == CREATE_2) { - //ADD_PACKET(ID_OVERCURRENTS, 1, "overcurrents"); - ADD_PACKET(ID_DIRT_DETECT, 1, "dirt_detect"); - //ADD_PACKET(ID_UNUSED_1, 1, "unused 1"); - //ADD_PACKET(ID_WALL_SIGNAL, 2, "wall_signal"); - //ADD_PACKET(ID_CLIFF_LEFT_SIGNAL, 2, "cliff_left_signal"); - //ADD_PACKET(ID_CLIFF_FRONT_LEFT_SIGNAL, 2, "cliff_front_left_signal"); - //ADD_PACKET(ID_CLIFF_FRONT_RIGHT_SIGNAL, 2, "cliff_front_right_signal"); - //ADD_PACKET(ID_CLIFF_RIGHT_SIGNAL, 2, "cliff_right_signal"); - //ADD_PACKET(ID_UNUSED_2, 1, "unused 2"); - //ADD_PACKET(ID_UNUSED_3, 2, "unused 3"); - //ADD_PACKET(ID_CHARGE_SOURCE, 1, "charger_available"); - //ADD_PACKET(ID_SONG_NUM, 1, "song_number"); - //ADD_PACKET(ID_PLAYING, 1, "song_playing"); - //ADD_PACKET(ID_NUM_STREAM_PACKETS, 1, "oi_stream_num_packets"); - //ADD_PACKET(ID_VEL, 2, "velocity"); - //ADD_PACKET(ID_RADIUS, 2, "radius"); - ADD_PACKET(ID_LEFT_ENC, 2, "enc_counts_left"); - ADD_PACKET(ID_RIGHT_ENC, 2, "enc_counts_right"); - ADD_PACKET(ID_LIGHT, 1, "light_bumper"); - ADD_PACKET(ID_LIGHT_LEFT, 2, "light_bumper_left"); - ADD_PACKET(ID_LIGHT_FRONT_LEFT, 2, "light_bumper_front_left"); - ADD_PACKET(ID_LIGHT_CENTER_LEFT, 2, "light_bumper_center_left"); - ADD_PACKET(ID_LIGHT_CENTER_RIGHT, 2, "light_bumper_center_right"); - ADD_PACKET(ID_LIGHT_FRONT_RIGHT, 2, "light_bumper_front_right"); - ADD_PACKET(ID_LIGHT_RIGHT, 2, "light_bumper_right"); - ADD_PACKET(ID_IR_LEFT, 1, "ir_opcode_left"); - ADD_PACKET(ID_IR_RIGHT, 1, "ir_opcode_right"); - //ADD_PACKET(ID_LEFT_MOTOR_CURRENT, 2, "left_motor_current"); - //ADD_PACKET(ID_RIGHT_MOTOR_CURRENT, 2, "right_motor_current"); - //ADD_PACKET(ID_MAIN_BRUSH_CURRENT, 2, "main_brush_current"); - //ADD_PACKET(ID_SIDE_BRUSH_CURRENT, 2, "side_brush_current"); - ADD_PACKET(ID_STASIS, 1, "stasis"); - } // if CREATE_2 + ADD_PACKET(ID_BUMP_WHEELDROP, 1, "bumps_wheeldrops", V_ALL); + ADD_PACKET(ID_WALL, 1, "wall", V_ALL); + ADD_PACKET(ID_CLIFF_LEFT, 1, "cliff_left", V_ALL); + ADD_PACKET(ID_CLIFF_FRONT_LEFT, 1, "cliff_front_left", V_ALL); + ADD_PACKET(ID_CLIFF_FRONT_RIGHT, 1, "cliff_front_right", V_ALL); + ADD_PACKET(ID_CLIFF_RIGHT, 1, "cliff_right", V_ALL); + ADD_PACKET(ID_VIRTUAL_WALL, 1, "virtual_wall", V_ALL); + ADD_PACKET(ID_OVERCURRENTS, 1, "overcurrents", V_1); + ADD_PACKET(ID_DIRT_DETECT_LEFT, 1, "dirt_detect_left", V_ALL); + ADD_PACKET(ID_DIRT_DETECT_RIGHT, 1, "dirt_detect_right", V_1); + ADD_PACKET(ID_IR_OMNI, 1, "ir_opcode", V_ALL); + ADD_PACKET(ID_BUTTONS, 1, "buttons", V_ALL); + ADD_PACKET(ID_DISTANCE, 2, "distance", V_1 | V_2); + ADD_PACKET(ID_ANGLE, 2, "angle", V_1 | V_2); + ADD_PACKET(ID_CHARGE_STATE, 1, "charging_state", V_ALL); + ADD_PACKET(ID_VOLTAGE, 2, "voltage", V_ALL); + ADD_PACKET(ID_CURRENT, 2, "current", V_ALL); + ADD_PACKET(ID_TEMP, 1, "temperature", V_ALL); + ADD_PACKET(ID_CHARGE , 2, "battery_charge", V_ALL); + ADD_PACKET(ID_CAPACITY, 2, "battery_capacity", V_ALL); + ADD_PACKET(ID_OI_MODE, 1, "oi_mode", V_2 | V_3); + ADD_PACKET(ID_LEFT_ENC, 2, "enc_counts_left", V_3); + ADD_PACKET(ID_RIGHT_ENC, 2, "enc_counts_right", V_3); + ADD_PACKET(ID_LEFT_ENC, 2, "enc_counts_left", V_3); + ADD_PACKET(ID_RIGHT_ENC, 2, "enc_counts_right", V_3); + ADD_PACKET(ID_LIGHT, 1, "light_bumper", V_3); + ADD_PACKET(ID_LIGHT_LEFT, 2, "light_bumper_left", V_3); + ADD_PACKET(ID_LIGHT_FRONT_LEFT, 2, "light_bumper_front_left", V_3); + ADD_PACKET(ID_LIGHT_CENTER_LEFT, 2, "light_bumper_center_left", V_3); + ADD_PACKET(ID_LIGHT_CENTER_RIGHT, 2, "light_bumper_center_right", V_3); + ADD_PACKET(ID_LIGHT_FRONT_RIGHT, 2, "light_bumper_front_right", V_3); + ADD_PACKET(ID_LIGHT_RIGHT, 2, "light_bumper_right", V_3); + ADD_PACKET(ID_IR_LEFT, 1, "ir_opcode_left", V_3); + ADD_PACKET(ID_IR_RIGHT, 1, "ir_opcode_right", V_3); + ADD_PACKET(ID_STASIS, 1, "stasis", V_3); totalDataBytes = 0; for (std::map >::iterator it = packets.begin(); diff --git a/src/serial.cpp b/src/serial.cpp index 62206f5..3894b9e 100644 --- a/src/serial.cpp +++ b/src/serial.cpp @@ -5,11 +5,9 @@ namespace create { - Serial::Serial(boost::shared_ptr d, const uint8_t& header) : + Serial::Serial(boost::shared_ptr d) : data(d), - headerByte(header), port(io), - readState(READ_HEADER), isReading(false), dataReady(false), corruptPackets(0), @@ -64,27 +62,10 @@ namespace create { // Only allow once if (isReading) return true; - // Request from Create that we want a stream containing all packets - uint8_t numPackets = data->getNumPackets(); - std::vector packetIDs = data->getPacketIDs(); - uint8_t streamReq[2 + numPackets]; - streamReq[0] = OC_STREAM; - streamReq[1] = numPackets; - int i = 2; - for (std::vector::iterator it = packetIDs.begin(); it != packetIDs.end(); ++it) { - streamReq[i] = *it; - i++; - } - // Start OI sendOpcode(OC_START); - // Start streaming data - send(streamReq, 2 + numPackets); - - expectedNumBytes = data->getTotalDataBytes() + numPackets; - - //TODO: handle boost exceptions + if (!startSensorStream()) return false; io.reset(); @@ -112,7 +93,7 @@ namespace create { // Request data again sendOpcode(OC_START); - send(streamReq, 2 + numPackets); + startSensorStream(); } } @@ -158,74 +139,7 @@ namespace create { // Should have read exactly one byte if (size == 1) { - numBytesRead++; - byteSum += byteRead; - switch (readState) { - case READ_HEADER: - if (byteRead == headerByte) { - readState = READ_NBYTES; - byteSum = byteRead; - } - break; - - case READ_NBYTES: - if (byteRead == expectedNumBytes) { - readState = READ_PACKET_ID; - numBytesRead = 0; - } - else { - //notifyDataReady(); - readState = READ_HEADER; - } - break; - - case READ_PACKET_ID: - packetID = byteRead; - if (data->isValidPacketID(packetID)) { - expectedNumDataBytes = data->getPacket(packetID)->nbytes; - assert(expectedNumDataBytes == 1 || expectedNumDataBytes == 2); - numDataBytesRead = 0; - packetBytes = 0; - readState = READ_PACKET_BYTES; - } - else { - //notifyDataReady(); - readState = READ_HEADER; - } - break; - - case READ_PACKET_BYTES: - numDataBytesRead++; - if (expectedNumDataBytes == 2 && numDataBytesRead == 1) { - // High byte first - packetBytes = (byteRead << 8) & 0xff00; - } - else { - // Low byte - packetBytes += byteRead; - } - if (numDataBytesRead >= expectedNumDataBytes) { - data->getPacket(packetID)->setTempData(packetBytes); - if (numBytesRead >= expectedNumBytes) - readState = READ_CHECKSUM; - else - readState = READ_PACKET_ID; - } - break; - - case READ_CHECKSUM: - if ((byteSum & 0xFF) == 0) { - notifyDataReady(); - } - else { - // Corrupt data - corruptPackets++; - } - totalPackets++; - // Start again - readState = READ_HEADER; - break; - } // end switch (readState) + processByte(byteRead); } // end if (size == 1) // Read the next byte diff --git a/src/serial_query.cpp b/src/serial_query.cpp new file mode 100644 index 0000000..1cc23d2 --- /dev/null +++ b/src/serial_query.cpp @@ -0,0 +1,70 @@ +#include + +#include "create/serial_query.h" +#include "create/types.h" + +#define SENSORS_RESPONSE_LENGTH 20 + +namespace create { + + SerialQuery::SerialQuery(boost::shared_ptr d) : Serial(d), + streamRecoveryTimer(io), + packetID(ID_BUMP_WHEELDROP), + packetByte(0), + packetData(0), + maxPacketID(ID_CAPACITY) { + } + + bool SerialQuery::startSensorStream() { + if (!started) { + requestSensorData(); + started = true; + } + return true; + } + + void SerialQuery::requestSensorData() { + static const uint8_t requestPacket[2] = { OC_SENSORS, ID_GROUP_0 }; + // Prevents previous packet from corrupting next one + flushInput(); + send(requestPacket, 2); + // Automatically resend request if no response is received + streamRecoveryTimer.expires_from_now(boost::posix_time::milliseconds(50)); + streamRecoveryTimer.async_wait(boost::bind(&SerialQuery::restartSensorStream, this, _1)); + } + + void SerialQuery::restartSensorStream(const boost::system::error_code& err) { + if (err != boost::asio::error::operation_aborted) { + if (packetID != ID_BUMP_WHEELDROP) { + ++corruptPackets; + } + requestSensorData(); + } + } + + void SerialQuery::flushInput() { + // Only works with POSIX support + tcflush(port.lowest_layer().native(), TCIFLUSH); + } + + void SerialQuery::processByte(uint8_t byteRead) { + packetData |= (static_cast(byteRead) << (8 * packetByte)); + + if (packetByte > 0) { + --packetByte; + } else if (packetID < maxPacketID) { + // New packet + data->getPacket(packetID)->setTempData(packetData); + packetData = 0; + ++packetID; + packetByte = data->getPacket(packetID)->nbytes - 1; + } else { + // Response finished + packetID = ID_BUMP_WHEELDROP; + packetByte = 0; + packetData = 0; + notifyDataReady(); + requestSensorData(); + } + } +} // namespace create diff --git a/src/serial_stream.cpp b/src/serial_stream.cpp new file mode 100644 index 0000000..8674718 --- /dev/null +++ b/src/serial_stream.cpp @@ -0,0 +1,103 @@ +#include + +#include "create/serial_stream.h" +#include "create/types.h" + +namespace create { + + SerialStream::SerialStream(boost::shared_ptr d, const uint8_t& header) : Serial(d), headerByte(header){ + } + + bool SerialStream::startSensorStream() { + // Request from Create that we want a stream containing all packets + uint8_t numPackets = data->getNumPackets(); + std::vector packetIDs = data->getPacketIDs(); + uint8_t streamReq[2 + numPackets]; + streamReq[0] = OC_STREAM; + streamReq[1] = numPackets; + int i = 2; + for (std::vector::iterator it = packetIDs.begin(); it != packetIDs.end(); ++it) { + streamReq[i] = *it; + i++; + } + + // Start streaming data + send(streamReq, 2 + numPackets); + + expectedNumBytes = data->getTotalDataBytes() + numPackets; + + return true; + } + + void SerialStream::processByte(uint8_t byteRead) { + numBytesRead++; + byteSum += byteRead; + switch (readState) { + case READ_HEADER: + if (byteRead == headerByte) { + readState = READ_NBYTES; + byteSum = byteRead; + } + break; + + case READ_NBYTES: + if (byteRead == expectedNumBytes) { + readState = READ_PACKET_ID; + numBytesRead = 0; + } + else { + //notifyDataReady(); + readState = READ_HEADER; + } + break; + + case READ_PACKET_ID: + packetID = byteRead; + if (data->isValidPacketID(packetID)) { + expectedNumDataBytes = data->getPacket(packetID)->nbytes; + assert(expectedNumDataBytes == 1 || expectedNumDataBytes == 2); + numDataBytesRead = 0; + packetBytes = 0; + readState = READ_PACKET_BYTES; + } + else { + //notifyDataReady(); + readState = READ_HEADER; + } + break; + + case READ_PACKET_BYTES: + numDataBytesRead++; + if (expectedNumDataBytes == 2 && numDataBytesRead == 1) { + // High byte first + packetBytes = (byteRead << 8) & 0xff00; + } + else { + // Low byte + packetBytes += byteRead; + } + if (numDataBytesRead >= expectedNumDataBytes) { + data->getPacket(packetID)->setTempData(packetBytes); + if (numBytesRead >= expectedNumBytes) + readState = READ_CHECKSUM; + else + readState = READ_PACKET_ID; + } + break; + + case READ_CHECKSUM: + if ((byteSum & 0xFF) == 0) { + notifyDataReady(); + } + else { + // Corrupt data + corruptPackets++; + } + totalPackets++; + // Start again + readState = READ_HEADER; + break; + } // end switch (readState) + } + +} // namespace create diff --git a/src/types.cpp b/src/types.cpp new file mode 100644 index 0000000..3e237a7 --- /dev/null +++ b/src/types.cpp @@ -0,0 +1,52 @@ +#include "create/types.h" + +namespace create { + + RobotModel::RobotModel(const ProtocolVersion version, const float axleLength, const unsigned int baud, const float maxVelocity, const float wheelDiameter): + id(nextId), + version(version), + axleLength(axleLength), + baud(baud), + maxVelocity(maxVelocity), + wheelDiameter(wheelDiameter) { + nextId <<= 1; + } + + bool RobotModel::operator ==(RobotModel& other) const { + return id == other.id; + } + + RobotModel::operator uint32_t() const { + return id; + } + + uint32_t RobotModel::getId() const { + return id; + } + + ProtocolVersion RobotModel::getVersion() const { + return version; + } + + float RobotModel::getAxleLength() const { + return axleLength; + } + + unsigned int RobotModel::getBaud() const { + return baud; + } + + float RobotModel::getMaxVelocity() const { + return maxVelocity; + } + + float RobotModel::getWheelDiameter() const { + return wheelDiameter; + } + + uint32_t RobotModel::nextId = 1; + + RobotModel RobotModel::ROOMBA_400(V_1, 0.258, 57600); + RobotModel RobotModel::CREATE_1(V_2, 0.258, 57600); + RobotModel RobotModel::CREATE_2(V_3, 0.235, 115200); +} From 6b90694a846dfb1bd89013e7ea7bc5992af73a73 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 13 Oct 2016 13:51:55 -0700 Subject: [PATCH 006/108] Catkinize Update CMakeLists.txt configuration and install rules Add package.xml Add config.cmake.in --- CMakeLists.txt | 121 +++++++++++++++++++++++++++++++++++++++++------- README.md | 18 +++---- config.cmake.in | 4 ++ package.xml | 25 ++++++++++ 4 files changed, 142 insertions(+), 26 deletions(-) create mode 100644 config.cmake.in create mode 100644 package.xml diff --git a/CMakeLists.txt b/CMakeLists.txt index ea5e467..3ec72e1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,16 +1,28 @@ -cmake_minimum_required(VERSION 2.8.3) -project(libcreate) +# After installation this project can be found by 'find_package(... CONFIG)' command: +# +# find_package(libcreate CONFIG REQUIRED) +# target_link_libraries(... libcreate::create) +# +# Reference for this file: +# https://github.com/forexample/package-example/blob/cf2ea1d6a209fb9eca2ab83fdd0ac15fe4d3e807/Foo/CMakeLists.txt + +cmake_minimum_required(VERSION 3.0) +project(libcreate VERSION 1.2.0) find_package(Boost REQUIRED system thread) find_package(Threads REQUIRED) -## Specify additional locations of header files +######### +# Build # +######### + +# Specify locations of header files include_directories( include ) -## Declare cpp library -add_library(create +# Declare cpp library +add_library(create SHARED src/create.cpp src/serial.cpp src/serial_stream.cpp @@ -20,6 +32,15 @@ add_library(create src/types.cpp ) +# Global includes. Used by all targets +# * header can be included by C++ code `#include ` +target_include_directories( + create PUBLIC + "$" + "$" +) + +# Manually link to thread library for build on ARM if(THREADS_HAVE_PTHREAD_ARG) set_property(TARGET create PROPERTY COMPILE_OPTIONS "-pthread") set_property(TARGET create PROPERTY INTERFACE_COMPILE_OPTIONS "-pthread") @@ -29,16 +50,17 @@ if(CMAKE_THREAD_LIBS_INIT) target_link_libraries(create "${CMAKE_THREAD_LIBS_INIT}") endif() +# Link to Boost target_link_libraries(create ${Boost_LIBRARIES} ) -## Declare example executables +# Declare example executables add_executable(create_demo examples/create_demo.cpp) add_executable(bumper_example examples/bumper_example.cpp) add_executable(odom_example examples/odom_example.cpp) -## Specify libraries to link a library or executable target against +# Specify libraries to link executable targets against target_link_libraries(create_demo ${Boost_LIBRARIES} create @@ -52,13 +74,78 @@ target_link_libraries(odom_example create ) -## Install -install(TARGETS create DESTINATION lib) -install(FILES - include/create/create.h - include/create/serial.h - include/create/types.h - include/create/data.h - include/create/packet.h - include/create/util.h - DESTINATION include/create) +########### +# Install # +########### + +# Layout. This works for all platforms: +# * /lib/cmake/ +# * /lib/ +# * /include/ +set(config_install_dir "lib/cmake/${PROJECT_NAME}") +set(include_install_dir "include") + +set(generated_dir "${CMAKE_CURRENT_BINARY_DIR}/generated") + +# Configuration +set(version_config "${generated_dir}/${PROJECT_NAME}-config-version.cmake") +set(project_config "${generated_dir}/${PROJECT_NAME}-config.cmake") +set(targets_export_name "${PROJECT_NAME}-targets") +set(namespace "${PROJECT_NAME}::") + +# Include module with function 'write_basic_package_version_file' +include(CMakePackageConfigHelpers) + +# Configure '-config-version.cmake' +write_basic_package_version_file( + "${version_config}" + COMPATIBILITY SameMajorVersion +) + +# Configure '-config.cmake' +# Use variables: +# * targets_export_name +# * PROJECT_NAME +configure_package_config_file( + "config.cmake.in" + "${project_config}" + INSTALL_DESTINATION "${config_install_dir}" +) + +# Install targets +install( + TARGETS create + EXPORT "${targets_export_name}" + ARCHIVE DESTINATION "lib" + LIBRARY DESTINATION "lib" + RUNTIME DESTINATION "bin" + INCLUDES DESTINATION "${include_install_dir}" +) + +# Install headers +install(DIRECTORY include/create + DESTINATION include + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE +) + +# Install config +# * /lib/cmake/libcreate/libcreate-config.cmake +# * /lib/cmake/libcreate/libcreate-config-version.cmake +install( + FILES "${project_config}" "${version_config}" + DESTINATION "${config_install_dir}" +) + +# Install config +# * /lib/cmake/libcreate/libcreate-targets.cmake +install( + EXPORT "${targets_export_name}" + NAMESPACE "${namespace}" + DESTINATION "${config_install_dir}" +) + +# Install package.xml (for catkin) +install(FILES package.xml + DESTINATION share/${PROJECT_NAME} +) diff --git a/README.md b/README.md index 22cc852..eea48b5 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ -# libcreate +# libcreate # -C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com/About-iRobot/STEM/Create-2.aspx) as well as most models of Roombas. This library forms the basis of the ROS driver in [create_autonomy](https://github.com/autonomylab/create_autonomy). +C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com/About-iRobot/STEM/Create-2.aspx) as well as most models of Roomba. [create_autonomy](http://wiki.ros.org/create_autonomy) is a [ROS](http://www.ros.org/) wrapper for this library. * Documentation: TODO * Code API: TODO @@ -11,28 +11,28 @@ C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com * Author: [Jacob Perron](http://jacobperron.ca) ([Autonomy Lab](http://autonomylab.org), [Simon Fraser University](http://www.sfu.ca)) * Contributors: [Mani Monajjemi](http:mani.im), [Ben Wolsieffer](https://github.com/lopsided98) -## Dependencies +## Dependencies ## * [Boost System Library](http://www.boost.org/doc/libs/1_59_0/libs/system/doc/index.html) * [Boost Thread Library](http://www.boost.org/doc/libs/1_59_0/doc/html/thread.html) -## Install +## Install ## * `cmake CMakeLists.txt` * `make` * `sudo make install` -## Example +## Example ## See source for examples. - + Example compile line: `g++ create_demo.cpp -lcreate -lboost_system -lboost_thread` -## Bugs +## Known issues ## -* _Clock_ and _Schedule_ button presses are not detected. This is a known problem to the developers at iRobot. +* _Clock_ and _Schedule_ buttons are not functional. This is a known bug related to the firmware. * Inaccurate odometry angle for Create 1 ([#22](https://github.com/AutonomyLab/libcreate/issues/22)) -## Build Status +## Build Status ## ![Build Status](https://api.travis-ci.org/AutonomyLab/libcreate.svg?branch=master) diff --git a/config.cmake.in b/config.cmake.in new file mode 100644 index 0000000..9b4c9ee --- /dev/null +++ b/config.cmake.in @@ -0,0 +1,4 @@ +@PACKAGE_INIT@ + +include("${CMAKE_CURRENT_LIST_DIR}/@targets_export_name@.cmake") +check_required_components("@PROJECT_NAME@") diff --git a/package.xml b/package.xml new file mode 100644 index 0000000..9a31e9c --- /dev/null +++ b/package.xml @@ -0,0 +1,25 @@ + + + libcreate + 1.2.0 + C++ library for interfacing with iRobot's Create 1 and Create 2 + + Jacob Perron + + BSD + + http://wiki.ros.org/libcreate + + Jacob Perron + + cmake + + boost + + boost + catkin + + + cmake + + From a18184753db37d1bd51683d3a38d1691a0f094a5 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 13 Oct 2016 19:21:02 -0700 Subject: [PATCH 007/108] Reduce mimumum cmake version to 2.8 --- CMakeLists.txt | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 3ec72e1..9a9611a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,8 +6,10 @@ # Reference for this file: # https://github.com/forexample/package-example/blob/cf2ea1d6a209fb9eca2ab83fdd0ac15fe4d3e807/Foo/CMakeLists.txt -cmake_minimum_required(VERSION 3.0) -project(libcreate VERSION 1.2.0) +cmake_minimum_required(VERSION 2.8) +project(libcreate) + +set(package_version 1.2.0) find_package(Boost REQUIRED system thread) find_package(Threads REQUIRED) @@ -99,6 +101,7 @@ include(CMakePackageConfigHelpers) # Configure '-config-version.cmake' write_basic_package_version_file( "${version_config}" + VERSION "${package_version}" COMPATIBILITY SameMajorVersion ) From 2081818e73033aad3025ea2795199798a4c4ae69 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 13 Oct 2016 21:19:54 -0700 Subject: [PATCH 008/108] Switch to trusty for CI --- .travis.yml | 4 ++++ CMakeLists.txt | 2 +- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index d5c9e58..99d6a03 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,3 +1,6 @@ +sudo: required +dist: trusty + language: cpp compiler: @@ -8,5 +11,6 @@ before_install: - sudo apt-get install libboost-system-dev libboost-thread-dev script: + - cmake --version - cmake . - make diff --git a/CMakeLists.txt b/CMakeLists.txt index 9a9611a..be7fe66 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ # Reference for this file: # https://github.com/forexample/package-example/blob/cf2ea1d6a209fb9eca2ab83fdd0ac15fe4d3e807/Foo/CMakeLists.txt -cmake_minimum_required(VERSION 2.8) +cmake_minimum_required(VERSION 2.8.12) project(libcreate) set(package_version 1.2.0) From 57574086cdaaf8510d28c971d7810418a73d934b Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sun, 16 Oct 2016 12:12:45 -0700 Subject: [PATCH 009/108] Add Changelog --- CHANGELOG.rst | 75 ++++++++++++++++++++++++++++++++++++++++++++++++++ CMakeLists.txt | 2 +- package.xml | 2 +- 3 files changed, 77 insertions(+), 2 deletions(-) create mode 100644 CHANGELOG.rst diff --git a/CHANGELOG.rst b/CHANGELOG.rst new file mode 100644 index 0000000..20d70ba --- /dev/null +++ b/CHANGELOG.rst @@ -0,0 +1,75 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package libcreate +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Forthcoming +----------- +* Switch to trusty for CI +* Set mimumum cmake version to 2.8.12 +* Update CMakeLists.txt configuration and install rules +* Add package.xml +* Add config.cmake.in +* Contributors: Jacob Perron + +1.3.0 (2016-08-23) +------------------ +* Add support for early model Roomba 400s and other robots using the original SCI protocol. +* Expose individual wheel distances and requested velocities. Fix wheel distance calculation for the Create 1. +* Manually link to thread library. This allows libcreate to build on ARM. +* Fix odometry inversion for Create 1. +* Contributors: Ben Wolsieffer, Jacob Perron + +1.2.1 (2016-04-30) +------------------ +* Make velocity relative to base frame, not odometry frame +* Contributors: Jacob Perron + +1.2.0 (2016-04-15) +------------------ +* Add covariance info to Pose and Vel +* Fix getMode bug +* Contributors: Jacob Perron + +1.1.1 (2016-04-07) +------------------ +* Fix odometry sign error +* Add warning in code regarding Create 1 odometry issue +* Add odom_example.cpp +* Contributors: Jacob Perron + +1.1.0 (2016-04-02) +------------------ +* Add API to get light sensor signals +* Contributors: Jacob Perron + +1.0.0 (2016-04-01) +------------------ +* Fix odometry for Create 1 +* Fix odom angle sign error +* Convert units to base units +* Implement 'getMode' +* Rename 'isIRDetect*' functions to 'isLightBumper*' +* Documentation / code cleanup +* Add function 'driveRadius' +* Add function 'isVirtualWall' +* Fix sign error on returned 'current' and 'temperature' +* Contributors: Jacob Perron + +0.1.1 (2016-03-25) +------------------ +* Fix odometry bug +* Contributors: Jacob Perron + +0.1.0 (2016-03-24) +------------------ +* Add enum of special IR characters +* Fix bug: convert distance measurement to meters +* Add support for first generation Create (Roomba 400 series) +* Fix bug: Too many packets requested corrupting serial buffer +* Expose functions for getting number of corrupt packets and total packets in Create class +* Add getters for number of corrupt and total packets received over serial +* Update README.md +* Added build badge +* Added CI (travis) +* Instantaneous velocity now available +* Contributors: Jacob Perron diff --git a/CMakeLists.txt b/CMakeLists.txt index be7fe66..cb37422 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -9,7 +9,7 @@ cmake_minimum_required(VERSION 2.8.12) project(libcreate) -set(package_version 1.2.0) +set(package_version 1.4.0) find_package(Boost REQUIRED system thread) find_package(Threads REQUIRED) diff --git a/package.xml b/package.xml index 9a31e9c..017e60f 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ libcreate - 1.2.0 + 1.3.0 C++ library for interfacing with iRobot's Create 1 and Create 2 Jacob Perron From 811b115b0c27a05be1a8273b21faaf1a63f372bb Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sun, 16 Oct 2016 12:19:06 -0700 Subject: [PATCH 010/108] 1.4.0 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 20d70ba..3cb8907 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package libcreate ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +1.4.0 (2016-10-16) +------------------ * Switch to trusty for CI * Set mimumum cmake version to 2.8.12 * Update CMakeLists.txt configuration and install rules diff --git a/package.xml b/package.xml index 017e60f..974633d 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ libcreate - 1.3.0 + 1.4.0 C++ library for interfacing with iRobot's Create 1 and Create 2 Jacob Perron From 00bc9fb5dd9437497c128579b7cbe0f57abfbe33 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sun, 16 Oct 2016 16:30:29 -0700 Subject: [PATCH 011/108] Use package.xml format 2 Add doxygen as doc dependency --- package.xml | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/package.xml b/package.xml index 974633d..fb2af92 100644 --- a/package.xml +++ b/package.xml @@ -1,5 +1,5 @@ - + libcreate 1.4.0 C++ library for interfacing with iRobot's Create 1 and Create 2 @@ -9,15 +9,18 @@ BSD http://wiki.ros.org/libcreate + https://github.com/AutonomyLab/libcreate + https://github.com/AutonomyLab/libcreate/issues Jacob Perron cmake - boost + boost - boost - catkin + catkin + + doxygen cmake From 9c93971d7d67f489b0957fe924aeced130d39f89 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sun, 16 Oct 2016 16:30:44 -0700 Subject: [PATCH 012/108] Add mainpage.dox --- mainpage.dox | 7 +++++++ 1 file changed, 7 insertions(+) create mode 100644 mainpage.dox diff --git a/mainpage.dox b/mainpage.dox new file mode 100644 index 0000000..679c1be --- /dev/null +++ b/mainpage.dox @@ -0,0 +1,7 @@ +/** +\mainpage +\htmlinclude manifest.html + +\b libcreate is a C++ library for interfacing with iRobot's Create mobile robot platforms and various Roomba models. + +*/ From 78f0af78d1b95e215a9aecaa7229ccf178801261 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sun, 13 Nov 2016 01:15:07 -0800 Subject: [PATCH 013/108] Update documentation --- include/create/create.h | 279 ++++++++++++++++++++++++++++------------ include/create/types.h | 26 +++- 2 files changed, 216 insertions(+), 89 deletions(-) diff --git a/include/create/create.h b/include/create/create.h index bc2f39b..2143607 100644 --- a/include/create/create.h +++ b/include/create/create.h @@ -97,52 +97,74 @@ namespace create { boost::shared_ptr serial; public: - /* Default constructor. - * Does not attempt to establish serial connection to Create. - */ - Create(RobotModel = RobotModel::CREATE_2); + /** + * \brief Default constructor. + * + * Calling this constructor Does not attempt to establish a serial connection to the robot. + * + * \param model the type of the robot. See RobotModel to determine the value for your robot. + */ + Create(RobotModel model = RobotModel::CREATE_2); - /* Attempts to establish serial connection to Create. + /** + * \brief Attempts to establish serial connection to Create. + * * \param port of your computer that is connected to Create. * \param baud rate to communicate with Create. Typically, * 115200 for Create 2 and 57600 for Create 1. - * \param model type of robot. + * \param model type of robot. See RobotModel to determine the value for your robot. */ Create(const std::string& port, const int& baud, RobotModel model = RobotModel::CREATE_2); + /** + * \brief Attempts to disconnect from serial. + */ ~Create(); - /* Make a serial connection to Create. + /** + * \brief Make a serial connection to Create. + * * This is the first thing that should be done after instantiated this class. + * * \return true if a successful connection is established, false otherwise. */ bool connect(const std::string& port, const int& baud); + /** + * \brief Check if serial connection is active. + * + * \return true if successfully connected, false otherwise. + */ inline bool connected() const { return serial->connected(); }; - /* Disconnect from serial. + /** + * \brief Disconnect from serial. */ void disconnect(); - /* Change Create mode. - * \param mode to put Create in. + /** + * \brief Change Create mode. + * \param mode to change Create to. * \return true if successful, false otherwise */ bool setMode(const create::CreateMode& mode); - /* Starts a cleaning mode. + /** + * \brief Starts a cleaning mode. * Changes mode to MODE_PASSIVE. * \return true if successful, false otherwise */ bool clean(const create::CleanMode& mode = CLEAN_DEFAULT); - /* Starts the docking behaviour. + /** + * \brief Starts the docking behaviour. * Changes mode to MODE_PASSIVE. * \return true if successful, false otherwise */ bool dock() const; - /* Sets the internal clock of Create. + /** + * \brief Sets the internal clock of Create. * \param day in range [0, 6] * \param hour in range [0, 23] * \param min in range [0, 59] @@ -150,7 +172,8 @@ namespace create { */ bool setDate(const create::DayOfWeek& day, const uint8_t& hour, const uint8_t& min) const; - /* Set the average wheel velocity and turning radius of Create. + /** + * \brief Set the average wheel velocity and turning radius of Create. * \param velocity is in m/s bounded between [-0.5, 0.5] * \param radius in meters. * Special cases: drive straight = CREATE_2_STRAIGHT_RADIUS, @@ -160,39 +183,45 @@ namespace create { */ bool driveRadius(const float& velocity, const float& radius); - /* Set the velocities for the left and right wheels. + /** + * \brief 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); - /* Set the forward and angular velocity of Create. + /** + * \brief 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); - /* Set the power to the side brush motor. + /** + * \brief Set the power to the side brush motor. * \param power is in the range [-1, 1] * \return true if successful, false otherwise */ bool setSideMotor(const float& power); - /* Set the power to the main brush motor. + /** + * \brief Set the power to the main brush motor. * \param power is in the range [-1, 1] * \return true if successful, false otherwise */ bool setMainMotor(const float& power); - /* Set the power to the vacuum motor. + /** + * \brief Set the power to the vacuum motor. * \param power is in the range [0, 1] * \return true if successful, false otherwise */ bool setVacuumMotor(const float& power); - /* Set the power of all motors. + /** + * \brief Set the power of all motors. * \param mainPower in the range [-1, 1] * \param sidePower in the range [-1, 1] * \param vacuumPower in the range [0, 1] @@ -200,38 +229,46 @@ namespace create { */ bool setAllMotors(const float& mainPower, const float& sidePower, const float& vacuumPower); - /* Set the blue "debris" LED on/off. + /** + * \brief Set the blue "debris" LED on/off. * \param enable * \return true if successful, false otherwise */ bool enableDebrisLED(const bool& enable); - /* Set the green "spot" LED on/off. + /** + * \brief Set the green "spot" LED on/off. * \param enable * \return true if successful, false otherwise */ bool enableSpotLED(const bool& enable); - /* Set the green "dock" LED on/off. + /** + * \brief Set the green "dock" LED on/off. * \param enable * \return true if successful, false otherwise */ bool enableDockLED(const bool& enable); - /* Set the orange "check Create" LED on/off. + /** + * \brief Set the orange "check Create" LED on/off. * \param enable * \return true if successful, false otherwise */ bool enableCheckRobotLED(const bool& enable); - /* Set the center power LED. + /** + * \brief Set the center power LED. * \param power in range [0, 255] where 0 = green and 255 = red * \param intensity in range [0, 255] * \return true if successful, false otherwise */ bool setPowerLED(const uint8_t& power, const uint8_t& intensity = 255); - /* Set the four 7-segment display digits from left to right. + /** + * \brief Set the four 7-segment display digits from left to right. + * + * \todo This function is not yet implemented refer to https://github.com/AutonomyLab/libcreate/issues/7 * \param segments to enable (true) or disable (false). * The size of segments should be less than 29. * The ordering of segments is left to right, top to bottom for each digit: @@ -245,10 +282,10 @@ namespace create { * * \return true if successful, false otherwise */ - //TODO (https://github.com/AutonomyLab/libcreate/issues/7) - //bool setDigits(const std::vector& segments) const; + bool setDigits(const std::vector& segments) const; - /* Set the four 7-segment display digits from left to right with ASCII codes. + /** + * \brief Set the four 7-segment display digits from left to right with ASCII codes. * Any code out side the accepted ascii ranges results in blank display. * \param digit1 is left most digit with ascii range [32, 126] * \param digit2 is second to left digit with ascii range [32, 126] @@ -259,7 +296,8 @@ namespace create { bool setDigitsASCII(const uint8_t& digit1, const uint8_t& digit2, const uint8_t& digit3, const uint8_t& digit4) const; - /* Defines a song from the provided notes and labels it with a song number. + /** + * \brief Defines a song from the provided notes and labels it with a song number. * \param songNumber can be one of four possible song slots, [0, 4] * \param songLength is the number of notes, maximum 16. * length(notes) = length(durations) = songLength should be true. @@ -273,226 +311,299 @@ namespace create { const uint8_t* notes, const float* durations) const; - /* Play a previously created song. + /** + * \brief Play a previously created song. * This command will not work if a song was not already defined with the specified song number. * \param songNumber is one of four stored songs in the range [0, 4] * \return true if successful, false otherwise */ bool playSong(const uint8_t& songNumber) const; - /* True if a left or right wheeldrop is detected. + /** + * \return true if a left or right wheeldrop is detected, false otherwise. */ bool isWheeldrop() const; - /* Returns true if left bumper is pressed, false otherwise. + /** + * \return true if left bumper is pressed, false otherwise. */ bool isLeftBumper() const; - /* Returns true if right bumper is pressed, false otherwise. + /** + * \return true if right bumper is pressed, false otherwise. */ bool isRightBumper() const; - /* True if wall is seen to right of Create, false otherwise. + /** + * \return true if wall is seen to right of Create, false otherwise. */ bool isWall() const; - /* True if there are any cliff detections, false otherwise. + /** + * \return true if there are any cliff detections, false otherwise. */ bool isCliff() const; - /* True if there is a virtual wall signal is being received. + /** + * \return true if there is a virtual wall signal is being received. */ bool isVirtualWall() const; - //TODO (https://github.com/AutonomyLab/libcreate/issues/8) - //bool isWheelOvercurrent() const; + /** + * \todo Not implemented yet (https://github.com/AutonomyLab/libcreate/issues/8) + * \return true if drive motors are overcurrent. + */ + bool isWheelOvercurrent() const; - //TODO (https://github.com/AutonomyLab/libcreate/issues/8) - //bool isMainBrushOvercurrent() const; + /** + * \todo Not implemented yet (https://github.com/AutonomyLab/libcreate/issues/8) + * \return true if main brush motor is overcurrent. + */ + bool isMainBrushOvercurrent() const; - //TODO (https://github.com/AutonomyLab/libcreate/issues/8) - //bool isSideBrushOvercurrent() const; + /** + * \todo Not implemented yet (https://github.com/AutonomyLab/libcreate/issues/8) + * \return true if side brush motor is overcurrent. + */ + bool isSideBrushOvercurrent() const; - /* Get level of the dirt detect sensor. + /** + * \brief Get level of the dirt detect sensor. * \return value in range [0, 255] */ uint8_t getDirtDetect() const; - /* Get value of 8-bit IR character currently being received by omnidirectional sensor. + /** + * \brief Get value of 8-bit IR character currently being received by omnidirectional sensor. * \return value in range [0, 255] */ uint8_t getIROmni() const; - /* Get value of 8-bit IR character currently being received by left sensor. + /** + * \brief Get value of 8-bit IR character currently being received by left sensor. * \return value in range [0, 255] */ uint8_t getIRLeft() const; - /* Get value of 8-bit IR character currently being received by right sensor. + /** + * \brief Get value of 8-bit IR character currently being received by right sensor. * \return value in range [0, 255] */ uint8_t getIRRight() const; - /* Get state of 'clean' button ('play' button on Create 1). + /** + * \brief Get state of 'clean' button ('play' button on Create 1). + * \return true if button is pressed, false otherwise. */ bool isCleanButtonPressed() const; - /* Not supported by any firmware! + /** + * \brief Not supported by any firmware! */ bool isClockButtonPressed() const; - /* Not supported by any firmware! + /** + * \brief Not supported by any firmware! */ bool isScheduleButtonPressed() const; - /* Get state of 'day' button. + /** + * \brief Get state of 'day' button. + * \return true if button is pressed, false otherwise. */ bool isDayButtonPressed() const; - /* Get state of 'hour' button. + /** + * \brief Get state of 'hour' button. + * \return true if button is pressed, false otherwise. */ bool isHourButtonPressed() const; - /* Get state of 'min' button. + /** + * \brief Get state of 'min' button. + * \return true if button is pressed, false otherwise. */ bool isMinButtonPressed() const; - /* Get state of 'dock' button ('advance' button on Create 1). + /** + * \brief Get state of 'dock' button ('advance' button on Create 1). + * \return true if button is pressed, false otherwise. */ bool isDockButtonPressed() const; - /* Get state of 'spot' button. + /** + * \brief Get state of 'spot' button. + * \return true if button is pressed, false otherwise. */ bool isSpotButtonPressed() const; - /* Get battery voltage. + /** + * \brief Get battery voltage. * \return value in volts */ float getVoltage() const; - /* Get current flowing in/out of battery. + /** + * \brief Get current flowing in/out of battery. * A positive current implies Create is charging. * \return value in amps */ float getCurrent() const; - /* Get the temperature of battery. + /** + * \brief Get the temperature of battery. * \return value in Celsius */ int8_t getTemperature() const; - /* Get battery's remaining charge. + /** + * \brief Get battery's remaining charge. * \return value in amp-hours */ float getBatteryCharge() const; - /* Get estimated battery charge capacity. + /** + * \brief Get estimated battery charge capacity. * \return in amp-hours */ float getBatteryCapacity() const; - /* Return true if farthest left light sensor detects an obstacle, false otherwise. + /** + * \return true if farthest left light sensor detects an obstacle, false otherwise. */ bool isLightBumperLeft() const; - /* Return true if front left light sensor detects an obstacle, false otherwise. + /** + * \return true if front left light sensor detects an obstacle, false otherwise. */ bool isLightBumperFrontLeft() const; - /* Return true if center left light sensor detects an obstacle, false otherwise. + /** + * \return true if center left light sensor detects an obstacle, false otherwise. */ bool isLightBumperCenterLeft() const; - /* Return true if farthest right light sensor detects an obstacle, false otherwise. + /** + * \return true if farthest right light sensor detects an obstacle, false otherwise. */ bool isLightBumperRight() const; - /* Return true if front right light sensor detects an obstacle, false otherwise. + /** + * \return true if front right light sensor detects an obstacle, false otherwise. */ bool isLightBumperFrontRight() const; - /* Return true if center right light sensor detects an obstacle, false otherwise. + /** + * \return true if center right light sensor detects an obstacle, false otherwise. */ bool isLightBumperCenterRight() const; - /* Return the signal strength from the left light sensor. + /** + * \brief Get the signal strength from the left light sensor. * \return value in range [0, 4095] */ uint16_t getLightSignalLeft() const; - /* Return the signal strength from the front-left light sensor. + /** + * \brief Get the signal strength from the front-left light sensor. * \return value in range [0, 4095] */ uint16_t getLightSignalFrontLeft() const; - /* Return the signal strength from the center-left light sensor. + /** + * \brief Get the signal strength from the center-left light sensor. * \return value in range [0, 4095] */ uint16_t getLightSignalCenterLeft() const; - /* Return the signal strength from the right light sensor. + /** + * \brief Get the signal strength from the right light sensor. * \return value in range [0, 4095] */ uint16_t getLightSignalRight() const; - /* Return the signal strength from the front-right light sensor. + /** + * \brief Get the signal strength from the front-right light sensor. * \return value in range [0, 4095] */ uint16_t getLightSignalFrontRight() const; - /* Return the signal strength from the center-right light sensor. + /** + * \brief Get the signal strength from the center-right light sensor. * \return value in range [0, 4095] */ uint16_t getLightSignalCenterRight() const; - /* Return true if Create is moving forward, false otherwise. + /** + * \return true if Create is moving forward, false otherwise. */ bool isMovingForward() const; - /* Get the total distance (in meters) the left wheel has moved. + /** + * \brief Get the total distance the left wheel has moved. + * \return distance in meters. */ float getLeftWheelDistance() const; - /* Get the total distance (in meters) the right wheel has moved. + /** + * \brief Get the total distance the right wheel has moved. + * \return distance in meters. */ float getRightWheelDistance() const; - /* Get the requested velocity (in meters/sec) of the left wheel. + /** + * \brief Get the requested velocity of the left wheel. * This value is bounded at the maximum velocity of the robot model. + * \return requested velocity in m/s. */ float getRequestedLeftWheelVel() const; - /* Get the requested velocity (in meters/sec) of the right wheel. + /** + * \brief Get the requested velocity of the right wheel. * This value is bounded at the maximum velocity of the robot model. + * \return requested velocity in m/s. */ float getRequestedRightWheelVel() const; - /* Get the current charging state. + /** + * \brief Get the current charging state. + * \return charging state. */ create::ChargingState getChargingState() const; - /* Get the current mode reported by Create. + /** + * \brief Get the current mode reported by Create. + * \return mode. */ create::CreateMode getMode(); - /* Get the estimated position of Create based on wheel encoders. + /** + * \brief Get the estimated pose of Create based on wheel encoders. + * \return pose (x-y position in meters and yaw angle in Radians) */ create::Pose getPose() const; - /* Get the estimated velocity of Create based on wheel encoders. + /** + * \brief Get the estimated velocity of Create based on wheel encoders. + * \return velocity (x and y in m/s and angular velocity in Radians/s) */ create::Vel getVel() const; - /* Get the number of corrupt serial packets since first connecting to Create. + /** + * \brief Get the number of corrupt serial packets since first connecting to Create. + * This value is ideally zero. If the number is consistently increasing then + * chances are some sensor information is not being updated. + * \return number of corrupt packets. */ uint64_t getNumCorruptPackets() const; - /* Get the total number of serial packets (including corrupt packets) since first connecting to Create. + /** + * \brief Get the total number of serial packets received (including corrupt packets) since first connecting to Create. + * \return total number of serial packets. */ uint64_t getTotalPackets() const; }; // end Create class } // namespace create - #endif // CREATE_DRIVER_H diff --git a/include/create/types.h b/include/create/types.h index ffbce6c..f9d99b0 100644 --- a/include/create/types.h +++ b/include/create/types.h @@ -45,8 +45,6 @@ namespace create { V_ALL = 0xFFFFFFFF }; - - class RobotModel { public: bool operator==(RobotModel& other) const; @@ -59,9 +57,20 @@ namespace create { 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 + /** + * \brief Compatible with Roomba 400 series and earlier. + */ + static RobotModel ROOMBA_400; + + /** + * \brief Compatible with Create 1 or Roomba 500 series. + */ + static RobotModel CREATE_1; + + /** + * \brief Compatible with Create 2 or Roomba 600 series and greater. + */ + static RobotModel CREATE_2; private: uint32_t id; @@ -260,10 +269,17 @@ namespace create { IR_CHAR_VIRTUAL_WALL = 162 }; + /** + * \brief Represents a robot pose. + */ struct Pose { float x; float y; float yaw; + + /** + * \brief 3x3 covariance matrix in row-major order. + */ std::vector covariance; }; From 3906d7954d66578a65f94d922a8f058e6eb3cf62 Mon Sep 17 00:00:00 2001 From: Erik Schembor Date: Mon, 20 Nov 2017 22:26:38 -0500 Subject: [PATCH 014/108] Add ability to drive the wheels with direct pwm duty --- include/create/create.h | 8 ++++++++ src/create.cpp | 21 +++++++++++++++++++++ 2 files changed, 29 insertions(+) diff --git a/include/create/create.h b/include/create/create.h index 2143607..e4662f8 100644 --- a/include/create/create.h +++ b/include/create/create.h @@ -191,6 +191,14 @@ namespace create { */ bool driveWheels(const float& leftWheel, const float& rightWheel); + /** + * \brief Set the direct for the left and right wheels. + * \param leftWheel pwm in the range [-1, 1] + * \param rightWheel pwm in the range [-1, 1] + * \return true if successful, false otherwise + */ + bool driveWheelsPwm(const float& leftWheel, const float& rightWheel); + /** * \brief Set the forward and angular velocity of Create. * \param xVel in m/s diff --git a/src/create.cpp b/src/create.cpp index 1c6048f..950c33e 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -424,6 +424,27 @@ namespace create { } } + bool Create::driveWheelsPwm(const float& leftWheel, const float& rightWheel) + { + static const int16_t PWM_COUNTS = 255; + + if (leftWheel < -1.0 || leftWheel > 1.0 || + rightWheel < -1.0 || rightWheel > 1.0) + return false; + + int16_t leftPwm = roundf(leftWheel * PWM_COUNTS); + int16_t rightPwm = roundf(rightWheel * PWM_COUNTS); + + uint8_t cmd[5] = { OC_DRIVE_PWM, + rightPwm >> 8, + rightPwm & 0xff, + leftPwm >> 8, + leftPwm & 0xff + }; + + return serial->send(cmd, 5); + } + bool Create::drive(const float& xVel, const float& angularVel) { // Compute left and right wheel velocities float leftVel = xVel - ((model.getAxleLength() / 2.0) * angularVel); From 5bc4d85177bad4dbb8fe3cc3fcf7ce56b684d111 Mon Sep 17 00:00:00 2001 From: Erik Schembor Date: Wed, 13 Dec 2017 22:04:22 -0500 Subject: [PATCH 015/108] Add apis for getting the measured velocities of the wheels --- include/create/create.h | 14 ++++++++++++++ src/create.cpp | 11 +++++++++++ 2 files changed, 25 insertions(+) diff --git a/include/create/create.h b/include/create/create.h index e4662f8..cf51442 100644 --- a/include/create/create.h +++ b/include/create/create.h @@ -83,6 +83,8 @@ namespace create { Matrix poseCovar; + float measuredLeftVel; + float measuredRightVel; float requestedLeftVel; float requestedRightVel; @@ -560,6 +562,18 @@ namespace create { */ float getRightWheelDistance() const; + /** + * \brief Get the measured velocity of the left wheel. + * \return velocity in m/s + */ + float getMeasuredLeftWheelVel() const; + + /** + * \brief Get the measured velocity of the right wheel. + * \return velocity in m/s + */ + float getMeasuredRightWheelVel() const; + /** * \brief Get the requested velocity of the left wheel. * This value is bounded at the maximum velocity of the robot model. diff --git a/src/create.cpp b/src/create.cpp index 950c33e..2e00cf1 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -170,6 +170,9 @@ namespace create { deltaYaw = wheelDistDiff / model.getAxleLength(); } + measuredLeftVel = leftWheelDist / dt; + measuredRightVel = rightWheelDist / dt; + // Moving straight if (fabs(wheelDistDiff) < util::EPS) { deltaX = deltaDist * cos(pose.yaw); @@ -975,6 +978,14 @@ namespace create { return totalRightDist; } + float Create::getMeasuredLeftWheelVel() const { + return measuredLeftVel; + } + + float Create::getMeasuredRightWheelVel() const { + return measuredRightVel; + } + float Create::getRequestedLeftWheelVel() const { return requestedLeftVel; } From fc8b1f300a4d0882446674012fd204c52b2d8b0a Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sun, 17 Dec 2017 16:07:53 -0800 Subject: [PATCH 016/108] Update Changelog --- CHANGELOG.rst | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 3cb8907..4c48a36 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,16 @@ Changelog for package libcreate ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Add APIs for getting the measured velocities of the wheels +* Add ability to drive the wheels with direct pwm duty +* Update documentation +* Add mainpage.dox +* Use package.xml format 2 +* Add doxygen as doc dependency +* Contributors: Erik Schembor, Jacob Perron + 1.4.0 (2016-10-16) ------------------ * Switch to trusty for CI From 3a607544bff887147b0dac26867cd58d684dd81b Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sun, 17 Dec 2017 18:34:18 -0800 Subject: [PATCH 017/108] 1.5.0 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 4c48a36..e4037ee 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package libcreate ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +1.5.0 (2017-12-17) +------------------ * Add APIs for getting the measured velocities of the wheels * Add ability to drive the wheels with direct pwm duty * Update documentation diff --git a/package.xml b/package.xml index fb2af92..46682b2 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ libcreate - 1.4.0 + 1.5.0 C++ library for interfacing with iRobot's Create 1 and Create 2 Jacob Perron From ddd41c1b6e471bf358b115268402b94e93c86b7f Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sun, 17 Dec 2017 18:37:08 -0800 Subject: [PATCH 018/108] Refactor cmake files --- CMakeLists.txt | 150 +++++++++++++++++++++++------------------------- config.cmake.in | 8 ++- 2 files changed, 80 insertions(+), 78 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index cb37422..2eeb4a7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,30 +1,31 @@ -# After installation this project can be found by 'find_package(... CONFIG)' command: +# After installation this project can be found by 'find_package' command: # -# find_package(libcreate CONFIG REQUIRED) -# target_link_libraries(... libcreate::create) +# find_package(libcreate REQUIRED) +# include_directores(${libcreate_INCLUDE_DIRS}) +# target_link_libraries(... ${libcreate_LIBRARIES}) # -# Reference for this file: -# https://github.com/forexample/package-example/blob/cf2ea1d6a209fb9eca2ab83fdd0ac15fe4d3e807/Foo/CMakeLists.txt cmake_minimum_required(VERSION 2.8.12) project(libcreate) -set(package_version 1.4.0) +set(PACKAGE_VERSION 1.5.0) -find_package(Boost REQUIRED system thread) +find_package(Boost REQUIRED COMPONENTS system thread) find_package(Threads REQUIRED) ######### # Build # ######### +set(LIBRARY_NAME create) + # Specify locations of header files include_directories( include ) # Declare cpp library -add_library(create SHARED +add_library(${LIBRARY_NAME} SHARED src/create.cpp src/serial.cpp src/serial_stream.cpp @@ -34,26 +35,18 @@ add_library(create SHARED src/types.cpp ) -# Global includes. Used by all targets -# * header can be included by C++ code `#include ` -target_include_directories( - create PUBLIC - "$" - "$" -) - # Manually link to thread library for build on ARM if(THREADS_HAVE_PTHREAD_ARG) - set_property(TARGET create PROPERTY COMPILE_OPTIONS "-pthread") - set_property(TARGET create PROPERTY INTERFACE_COMPILE_OPTIONS "-pthread") + set_property(TARGET ${LIBRARY_NAME} PROPERTY COMPILE_OPTIONS "-pthread") + set_property(TARGET ${LIBRARY_NAME} PROPERTY INTERFACE_COMPILE_OPTIONS "-pthread") endif() if(CMAKE_THREAD_LIBS_INIT) - target_link_libraries(create "${CMAKE_THREAD_LIBS_INIT}") + target_link_libraries(${LIBRARY_NAME} "${CMAKE_THREAD_LIBS_INIT}") endif() # Link to Boost -target_link_libraries(create +target_link_libraries(${LIBRARY_NAME} ${Boost_LIBRARIES} ) @@ -65,90 +58,93 @@ add_executable(odom_example examples/odom_example.cpp) # Specify libraries to link executable targets against target_link_libraries(create_demo ${Boost_LIBRARIES} - create + ${LIBRARY_NAME} ) target_link_libraries(bumper_example ${Boost_LIBRARIES} - create + ${LIBRARY_NAME} ) target_link_libraries(odom_example ${Boost_LIBRARIES} - create + ${LIBRARY_NAME} +) + +################# +# Configuration # +################# + +# Install directories layout: +# * /lib/ +# * /bin/ +# * /include/ +# * /lib/cmake/ +# * /share/ +set(LIB_INSTALL_DIR "lib") +set(BIN_INSTALL_DIR "bin") +set(INCLUDE_INSTALL_DIR "include") +set(CONFIG_INSTALL_DIR "${LIB_INSTALL_DIR}/cmake/${PROJECT_NAME}") +set(SHARE_INSTALL_DIR "share/${PROJECT_NAME}") + +set(GENERATED_DIR "${CMAKE_CURRENT_BINARY_DIR}/generated") +set(VERSION_CONFIG "${GENERATED_DIR}/${PROJECT_NAME}-config-version.cmake") +set(PROJECT_CONFIG "${GENERATED_DIR}/${PROJECT_NAME}-config.cmake") +set(TARGETS_EXPORT_NAME "${PROJECT_NAME}-targets") + +include(CMakePackageConfigHelpers) + +# Configure '-config-version.cmake' +write_basic_package_version_file( + "${VERSION_CONFIG}" + VERSION "${PACKAGE_VERSION}" + COMPATIBILITY SameMajorVersion +) + +# Configure '-config.cmake' +configure_package_config_file( + "config.cmake.in" + "${PROJECT_CONFIG}" + INSTALL_DESTINATION "${CONFIG_INSTALL_DIR}" + PATH_VARS + INCLUDE_INSTALL_DIR + LIBRARY_NAME ) ########### # Install # ########### -# Layout. This works for all platforms: -# * /lib/cmake/ -# * /lib/ -# * /include/ -set(config_install_dir "lib/cmake/${PROJECT_NAME}") -set(include_install_dir "include") - -set(generated_dir "${CMAKE_CURRENT_BINARY_DIR}/generated") - -# Configuration -set(version_config "${generated_dir}/${PROJECT_NAME}-config-version.cmake") -set(project_config "${generated_dir}/${PROJECT_NAME}-config.cmake") -set(targets_export_name "${PROJECT_NAME}-targets") -set(namespace "${PROJECT_NAME}::") - -# Include module with function 'write_basic_package_version_file' -include(CMakePackageConfigHelpers) - -# Configure '-config-version.cmake' -write_basic_package_version_file( - "${version_config}" - VERSION "${package_version}" - COMPATIBILITY SameMajorVersion -) - -# Configure '-config.cmake' -# Use variables: -# * targets_export_name -# * PROJECT_NAME -configure_package_config_file( - "config.cmake.in" - "${project_config}" - INSTALL_DESTINATION "${config_install_dir}" -) - # Install targets install( - TARGETS create - EXPORT "${targets_export_name}" - ARCHIVE DESTINATION "lib" - LIBRARY DESTINATION "lib" - RUNTIME DESTINATION "bin" - INCLUDES DESTINATION "${include_install_dir}" + TARGETS ${LIBRARY_NAME} + EXPORT "${TARGETS_EXPORT_NAME}" + LIBRARY DESTINATION "${LIB_INSTALL_DIR}" + ARCHIVE DESTINATION "${LIB_INSTALL_DIR}" + RUNTIME DESTINATION "${BIN_INSTALL_DIR}" + INCLUDES DESTINATION "${INCLUDE_INSTALL_DIR}" ) # Install headers -install(DIRECTORY include/create - DESTINATION include +install( + DIRECTORY include/ + DESTINATION ${INCLUDE_INSTALL_DIR} FILES_MATCHING PATTERN "*.h" PATTERN ".svn" EXCLUDE ) # Install config -# * /lib/cmake/libcreate/libcreate-config.cmake -# * /lib/cmake/libcreate/libcreate-config-version.cmake install( - FILES "${project_config}" "${version_config}" - DESTINATION "${config_install_dir}" + FILES "${PROJECT_CONFIG}" "${VERSION_CONFIG}" + DESTINATION "${CONFIG_INSTALL_DIR}" ) -# Install config -# * /lib/cmake/libcreate/libcreate-targets.cmake +# Install targets install( - EXPORT "${targets_export_name}" - NAMESPACE "${namespace}" - DESTINATION "${config_install_dir}" + EXPORT "${TARGETS_EXPORT_NAME}" + DESTINATION "${CONFIG_INSTALL_DIR}" ) # Install package.xml (for catkin) -install(FILES package.xml - DESTINATION share/${PROJECT_NAME} +install( + FILES package.xml + DESTINATION ${SHARE_INSTALL_DIR} ) diff --git a/config.cmake.in b/config.cmake.in index 9b4c9ee..fbd7630 100644 --- a/config.cmake.in +++ b/config.cmake.in @@ -1,4 +1,10 @@ @PACKAGE_INIT@ +find_package(Boost REQUIRED COMPONENTS system thread) +find_package(Threads REQUIRED) -include("${CMAKE_CURRENT_LIST_DIR}/@targets_export_name@.cmake") +include("${CMAKE_CURRENT_LIST_DIR}/@TARGETS_EXPORT_NAME@.cmake") +set_and_check(libcreate_INCLUDE_DIRS "@PACKAGE_INCLUDE_INSTALL_DIR@") +list(APPEND libcreate_INCLUDE_DIRS "${Boost_INCLUDE_DIRS}") +set(libcreate_LIBRARIES "@LIBRARY_NAME@") +list(APPEND libcreate_LIBRARIES "${Boost_LIBRARIES}") check_required_components("@PROJECT_NAME@") From 771e350305cf070b2e4672b7ca412179392aad94 Mon Sep 17 00:00:00 2001 From: jacobperron Date: Sat, 24 Mar 2018 16:03:24 -0700 Subject: [PATCH 019/108] Update README --- README.md | 44 ++++++++++++++++++++++++++++++-------------- 1 file changed, 30 insertions(+), 14 deletions(-) diff --git a/README.md b/README.md index eea48b5..249e635 100644 --- a/README.md +++ b/README.md @@ -2,8 +2,7 @@ C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com/About-iRobot/STEM/Create-2.aspx) as well as most models of Roomba. [create_autonomy](http://wiki.ros.org/create_autonomy) is a [ROS](http://www.ros.org/) wrapper for this library. -* Documentation: TODO -* Code API: TODO +* [Code API](http://docs.ros.org/kinetic/api/libcreate/html/index.html) * Protocol documentation: - [`V_1`](http://www.ecsl.cs.sunysb.edu/mint/Roomba_SCI_Spec_Manual.pdf) (Roomba 400 series ) - [`V_2`](http://www.irobot.com/filelibrary/pdfs/hrd/create/Create%20Open%20Interface_v2.pdf) (Create 1, Roomba 500 series) @@ -11,28 +10,45 @@ C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com * Author: [Jacob Perron](http://jacobperron.ca) ([Autonomy Lab](http://autonomylab.org), [Simon Fraser University](http://www.sfu.ca)) * Contributors: [Mani Monajjemi](http:mani.im), [Ben Wolsieffer](https://github.com/lopsided98) +## Build Status ## + +![Build Status](https://api.travis-ci.org/AutonomyLab/libcreate.svg?branch=master) + ## Dependencies ## * [Boost System Library](http://www.boost.org/doc/libs/1_59_0/libs/system/doc/index.html) * [Boost Thread Library](http://www.boost.org/doc/libs/1_59_0/doc/html/thread.html) -## Install ## +#### Serial Permissions #### -* `cmake CMakeLists.txt` -* `make` -* `sudo make install` +User permission is requried to connect to Create over serial. You can add your user to the dialout group to get permission: -## Example ## + sudo usermod -a -G dialout $USER -See source for examples. +Logout and login again for this to take effect. -Example compile line: `g++ create_demo.cpp -lcreate -lboost_system -lboost_thread` +## Build ## -## Known issues ## +Note, the examples found in the "examples" directory are built with the library. + +#### cmake #### + + git clone https://github.com/AutonomyLab/libcreate.git + cd libcreate + mkdir build && cd build + cmake .. + make -j + +#### catkin #### + + mkdir -p create_ws/src + cd create_ws + catkin init + cd src + git clone https://github.com/AutonomyLab/libcreate.git + catkin build + +## Known Issues ## * _Clock_ and _Schedule_ buttons are not functional. This is a known bug related to the firmware. * Inaccurate odometry angle for Create 1 ([#22](https://github.com/AutonomyLab/libcreate/issues/22)) - -## Build Status ## - -![Build Status](https://api.travis-ci.org/AutonomyLab/libcreate.svg?branch=master) From 14da9aed9a575d5ff644ebedbe131516379f9b0a Mon Sep 17 00:00:00 2001 From: jacobperron Date: Sat, 24 Mar 2018 18:08:14 -0700 Subject: [PATCH 020/108] Update examples More concise and focusing on individual features: * Battery level * Bumpers * Drive circle * LEDs * Serial packets * Play song * Wheeldrop --- CMakeLists.txt | 33 ++++----- examples/battery_level.cpp | 89 ++++++++++++++++++++++++ examples/bumper_example.cpp | 73 -------------------- examples/bumpers.cpp | 126 ++++++++++++++++++++++++++++++++++ examples/create_demo.cpp | 133 ------------------------------------ examples/drive_circle.cpp | 93 +++++++++++++++++++++++++ examples/leds.cpp | 105 ++++++++++++++++++++++++++++ examples/odom_example.cpp | 64 ----------------- examples/packets.cpp | 86 +++++++++++++++++++++++ examples/play_song.cpp | 97 ++++++++++++++++++++++++++ examples/wheeldrop.cpp | 91 ++++++++++++++++++++++++ 11 files changed, 704 insertions(+), 286 deletions(-) create mode 100644 examples/battery_level.cpp delete mode 100644 examples/bumper_example.cpp create mode 100644 examples/bumpers.cpp delete mode 100644 examples/create_demo.cpp create mode 100644 examples/drive_circle.cpp create mode 100644 examples/leds.cpp delete mode 100644 examples/odom_example.cpp create mode 100644 examples/packets.cpp create mode 100644 examples/play_song.cpp create mode 100644 examples/wheeldrop.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 2eeb4a7..487e846 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -51,23 +51,24 @@ target_link_libraries(${LIBRARY_NAME} ) # Declare example executables -add_executable(create_demo examples/create_demo.cpp) -add_executable(bumper_example examples/bumper_example.cpp) -add_executable(odom_example examples/odom_example.cpp) +set(EXAMPLES + battery_level + bumpers + drive_circle + leds + packets + play_song + wheeldrop +) -# Specify libraries to link executable targets against -target_link_libraries(create_demo - ${Boost_LIBRARIES} - ${LIBRARY_NAME} -) -target_link_libraries(bumper_example - ${Boost_LIBRARIES} - ${LIBRARY_NAME} -) -target_link_libraries(odom_example - ${Boost_LIBRARIES} - ${LIBRARY_NAME} -) +foreach(EXAMPLE ${EXAMPLES}) + add_executable(${EXAMPLE} examples/${EXAMPLE}.cpp) + + target_link_libraries(${EXAMPLE} + ${Boost_LIBRARIES} + ${LIBRARY_NAME} + ) +endforeach() ################# # Configuration # diff --git a/examples/battery_level.cpp b/examples/battery_level.cpp new file mode 100644 index 0000000..49fd70d --- /dev/null +++ b/examples/battery_level.cpp @@ -0,0 +1,89 @@ +/** +Software License Agreement (BSD) + +\file battery_level.cpp +\authors Jacob Perron +\copyright Copyright (c) 2018, 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. +*/ +#include "create/create.h" + +#include + +int main(int argc, char** argv) { + // Select robot. Assume Create 2 unless argument says otherwise + create::RobotModel model = create::RobotModel::CREATE_2; + std::string port = "/dev/ttyUSB0"; + int baud = 115200; + if (argc > 1 && std::string(argv[1]) == "create1") { + model = create::RobotModel::CREATE_1; + baud = 57600; + std::cout << "Running driver for Create 1" << std::endl; + } + else { + std::cout << "Running driver for Create 2" << std::endl; + } + + // Construct robot object + create::Create* robot = new create::Create(model); + + // Connect to robot + if (robot->connect(port, baud)) + std::cout << "Connected to robot" << std::endl; + else { + std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; + return 1; + } + + // Switch to Full mode + robot->setMode(create::MODE_FULL); + + std::cout << std::endl << "Press center 'Clean' button to disconnect and end program" << std::endl; + + // Get battery capacity (max charge) + const float battery_capacity = robot->getBatteryCapacity(); + + float battery_charge = 0.0f; + while (!robot->isCleanButtonPressed()) { + // Get battery charge + battery_charge = robot->getBatteryCharge(); + + // Print battery percentage + std::cout << "\rBattery level: " << (battery_charge / battery_capacity) * 100.0 << "%"; + + usleep(100000); // 10 Hz + } + + std::cout << std::endl; + + // Call disconnect to avoid leaving robot in Full mode + robot->disconnect(); + + // Clean up + delete robot; + + std::cout << "Bye!" << std::endl; + return 0; +} diff --git a/examples/bumper_example.cpp b/examples/bumper_example.cpp deleted file mode 100644 index 11e0ab8..0000000 --- a/examples/bumper_example.cpp +++ /dev/null @@ -1,73 +0,0 @@ -#include "create/create.h" - -int main(int argc, char** argv) { - std::string port = "/dev/ttyUSB0"; - int baud = 115200; - create::RobotModel model = create::RobotModel::CREATE_2; - - create::Create* robot = new create::Create(model); - - // Attempt to connect to Create - if (robot->connect(port, baud)) - std::cout << "Successfully connected to Create" << std::endl; - else { - std::cout << "Failed to connect to Create on port " << port.c_str() << std::endl; - return 1; - } - - robot->setMode(create::MODE_FULL); - - uint16_t signals[6]; - bool contact_bumpers[2]; - bool light_bumpers[6]; - - // Stop program when clean button is pressed - while (!robot->isCleanButtonPressed()) { - signals[0] = robot->getLightSignalLeft(); - signals[1] = robot->getLightSignalFrontLeft(); - signals[2] = robot->getLightSignalCenterLeft(); - signals[3] = robot->getLightSignalCenterRight(); - signals[4] = robot->getLightSignalFrontRight(); - signals[5] = robot->getLightSignalRight(); - - contact_bumpers[0] = robot->isLeftBumper(); - contact_bumpers[1] = robot->isRightBumper(); - - light_bumpers[0] = robot->isLightBumperLeft(); - light_bumpers[1] = robot->isLightBumperFrontLeft(); - light_bumpers[2] = robot->isLightBumperCenterLeft(); - light_bumpers[3] = robot->isLightBumperCenterRight(); - light_bumpers[4] = robot->isLightBumperFrontRight(); - light_bumpers[5] = robot->isLightBumperRight(); - - // print signals from left to right - std::cout << "[ " << signals[0] << " , " - << signals[1] << " , " - << signals[2] << " , " - << signals[3] << " , " - << signals[4] << " , " - << signals[5] - << " ]" << std::endl; - std::cout << "[ " << light_bumpers[0] << " , " - << light_bumpers[1] << " , " - << light_bumpers[2] << " , " - << light_bumpers[3] << " , " - << light_bumpers[4] << " , " - << light_bumpers[5] - << " ]" << std::endl; - std::cout << "[ " << contact_bumpers[0] << " , " - << contact_bumpers[1] - << " ]" << std::endl; - std::cout << std::endl; - - usleep(1000 * 100); //10hz - } - - std::cout << "Stopping Create" << std::endl; - - // Disconnect from robot - robot->disconnect(); - delete robot; - - return 0; -} diff --git a/examples/bumpers.cpp b/examples/bumpers.cpp new file mode 100644 index 0000000..52c6877 --- /dev/null +++ b/examples/bumpers.cpp @@ -0,0 +1,126 @@ +/** +Software License Agreement (BSD) + +\file bumpers.cpp +\authors Jacob Perron +\copyright Copyright (c) 2018, 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. +*/ +#include "create/create.h" + +#include + +int main(int argc, char** argv) { + // Select robot. Assume Create 2 unless argument says otherwise + create::RobotModel model = create::RobotModel::CREATE_2; + std::string port = "/dev/ttyUSB0"; + int baud = 115200; + if (argc > 1 && std::string(argv[1]) == "create1") { + model = create::RobotModel::CREATE_1; + baud = 57600; + std::cout << "Running driver for Create 1" << std::endl; + } + else { + std::cout << "Running driver for Create 2" << std::endl; + } + + // Construct robot object + create::Create* robot = new create::Create(model); + + // Connect to robot + if (robot->connect(port, baud)) + std::cout << "Connected to robot" << std::endl; + else { + std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; + return 1; + } + + // Switch to Full mode + robot->setMode(create::MODE_FULL); + + std::cout << std::endl << "Press center 'Clean' button to disconnect and end program" << std::endl; + + uint16_t light_signals[6]; + bool light_bumpers[6]; + bool contact_bumpers[2]; + + while (!robot->isCleanButtonPressed()) { + // Get light sensor data (only available for Create 2 or later robots) + if (model == create::RobotModel::CREATE_2) { + // Get raw light signal values + light_signals[0] = robot->getLightSignalLeft(); + light_signals[1] = robot->getLightSignalFrontLeft(); + light_signals[2] = robot->getLightSignalCenterLeft(); + light_signals[3] = robot->getLightSignalCenterRight(); + light_signals[4] = robot->getLightSignalFrontRight(); + light_signals[5] = robot->getLightSignalRight(); + + // Get obstacle data from light sensors (true/false) + light_bumpers[0] = robot->isLightBumperLeft(); + light_bumpers[1] = robot->isLightBumperFrontLeft(); + light_bumpers[2] = robot->isLightBumperCenterLeft(); + light_bumpers[3] = robot->isLightBumperCenterRight(); + light_bumpers[4] = robot->isLightBumperFrontRight(); + light_bumpers[5] = robot->isLightBumperRight(); + } + + // Get state of bumpers + contact_bumpers[0] = robot->isLeftBumper(); + contact_bumpers[1] = robot->isRightBumper(); + + // Print signals from left to right + std::cout << "[ " << light_signals[0] << " , " + << light_signals[1] << " , " + << light_signals[2] << " , " + << light_signals[3] << " , " + << light_signals[4] << " , " + << light_signals[5] + << " ]" << std::endl; + std::cout << "[ " << light_bumpers[0] << " , " + << light_bumpers[1] << " , " + << light_bumpers[2] << " , " + << light_bumpers[3] << " , " + << light_bumpers[4] << " , " + << light_bumpers[5] + << " ]" << std::endl; + std::cout << "[ " << contact_bumpers[0] << " , " + << contact_bumpers[1] + << " ]" << std::endl; + std::cout << std::endl; + + usleep(100000); // 10 Hz + } + + std::cout << std::endl; + + // Call disconnect to avoid leaving robot in Full mode + robot->disconnect(); + + // Clean up + delete robot; + + std::cout << "Bye!" << std::endl; + return 0; +} diff --git a/examples/create_demo.cpp b/examples/create_demo.cpp deleted file mode 100644 index 243eaa6..0000000 --- a/examples/create_demo.cpp +++ /dev/null @@ -1,133 +0,0 @@ -#include "create/create.h" - -create::Create* robot; - -int main(int argc, char** argv) { - std::string port = "/dev/ttyUSB0"; - int baud = 115200; - create::RobotModel model = create::RobotModel::CREATE_2; - - if (argc > 1 && std::string(argv[1]) == "create1") { - model = create::RobotModel::CREATE_1; - baud = 57600; - std::cout << "1st generation Create selected" << std::endl; - } - - robot = new create::Create(model); - - // Attempt to connect to Create - if (robot->connect(port, baud)) - std::cout << "Successfully connected to Create" << std::endl; - else { - std::cout << "Failed to connect to Create on port " << port.c_str() << std::endl; - return 1; - } - - // Note: Some functionality does not work as expected in Safe mode - robot->setMode(create::MODE_FULL); - - std::cout << "battery level: " << - robot->getBatteryCharge() / (float) robot->getBatteryCapacity() * 100.0 << "%" << std::endl; - - bool drive = false; - - // Make a song - //uint8_t songLength = 16; - //uint8_t notes[16] = { 67, 67, 66, 66, 65, 65, 66, 66, - // 67, 67, 66, 66, 65, 65, 66, 66 }; - //float durations[songLength]; - //for (int i = 0; i < songLength; i++) { - // durations[i] = 0.25; - //} - //robot->defineSong(0, songLength, notes, durations); - //usleep(1000000); - //robot->playSong(0); - - // Quit when center "Clean" button pressed - while (!robot->isCleanButtonPressed()) { - // Check for button presses - if (robot->isDayButtonPressed()) - std::cout << "day button press" << std::endl; - if (robot->isMinButtonPressed()) - std::cout << "min button press" << std::endl; - if (robot->isDockButtonPressed()) { - std::cout << "dock button press" << std::endl; - robot->enableCheckRobotLED(false); - } - if (robot->isSpotButtonPressed()) { - std::cout << "spot button press" << std::endl; - robot->enableCheckRobotLED(true); - } - if (robot->isHourButtonPressed()) { - std::cout << "hour button press" << std::endl; - drive = !drive; - } - - // Check for wheeldrop or cliffs - if (robot->isWheeldrop() || robot->isCliff()) { - drive = false; - robot->setPowerLED(255); - } - - // If everything is ok, drive forward using IR's to avoid obstacles - if (drive) { - robot->setPowerLED(0); // green - if (robot->isLightBumperLeft() || - robot->isLightBumperFrontLeft() || - robot->isLightBumperCenterLeft()) { - // turn right - robot->drive(0.1, -1.0); - robot->setDigitsASCII('-','-','-',']'); - } - else if (robot->isLightBumperRight() || - robot->isLightBumperFrontRight() || - robot->isLightBumperCenterRight()) { - // turn left - robot->drive(0.1, 1.0); - robot->setDigitsASCII('[','-','-','-'); - } - else { - // drive straight - robot->drive(0.1, 0.0); - robot->setDigitsASCII(' ','^','^',' '); - } - } - else { // drive == false - // stop moving - robot->drive(0, 0); - robot->setDigitsASCII('S','T','O','P'); - } - - // Turn on blue 'debris' light if moving forward - if (robot->isMovingForward()) { - robot->enableDebrisLED(true); - } - else { - robot->enableDebrisLED(false); - } - - // Check bumpers - if (robot->isLeftBumper()) { - std::cout << "left bump detected!" << std::endl; - } - if (robot->isRightBumper()) { - std::cout << "right bump detected!" << std::endl; - } - - usleep(1000 * 100); //10hz - } - - std::cout << "Stopping Create." << std::endl; - - // Turn off lights - robot->setPowerLED(0, 0); - robot->enableDebrisLED(false); - robot->enableCheckRobotLED(false); - robot->setDigitsASCII(' ', ' ', ' ', ' '); - - // Make sure to disconnect to clean up - robot->disconnect(); - delete robot; - - return 0; -} diff --git a/examples/drive_circle.cpp b/examples/drive_circle.cpp new file mode 100644 index 0000000..f7e1fcf --- /dev/null +++ b/examples/drive_circle.cpp @@ -0,0 +1,93 @@ +/** +Software License Agreement (BSD) + +\file drive_circle.cpp +\authors Jacob Perron +\copyright Copyright (c) 2018, 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. +*/ +#include "create/create.h" + +#include +#include + +int main(int argc, char** argv) { + // Select robot. Assume Create 2 unless argument says otherwise + create::RobotModel model = create::RobotModel::CREATE_2; + std::string port = "/dev/ttyUSB0"; + int baud = 115200; + if (argc > 1 && std::string(argv[1]) == "create1") { + model = create::RobotModel::CREATE_1; + baud = 57600; + std::cout << "Running driver for Create 1" << std::endl; + } + else { + std::cout << "Running driver for Create 2" << std::endl; + } + + // Construct robot object + create::Create* robot = new create::Create(model); + + // Connect to robot + if (robot->connect(port, baud)) + std::cout << "Connected to robot" << std::endl; + else { + std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; + return 1; + } + + // Switch to Full mode + robot->setMode(create::MODE_FULL); + + std::cout << std::endl << "Press center 'Clean' button to disconnect and end program" << std::endl; + + // There's a delay between switching modes and when the robot will accept drive commands + usleep(100000); + + // Command robot to drive a radius of 0.15 metres at 0.2 m/s + robot->driveRadius(0.2, 0.15); + + while (!robot->isCleanButtonPressed()) { + // Get robot odometry and print + const create::Pose pose = robot->getPose(); + + std::cout << std::fixed << std::setprecision(2) << "\rOdometry (x, y, yaw): (" + << pose.x << ", " << pose.y << ", " << pose.yaw << ") "; + + usleep(10000); // 10 Hz + } + + std::cout << std::endl; + + // Call disconnect to avoid leaving robot in Full mode + // Also, this consequently stops the robot from moving + robot->disconnect(); + + // Clean up + delete robot; + + std::cout << "Bye!" << std::endl; + return 0; +} diff --git a/examples/leds.cpp b/examples/leds.cpp new file mode 100644 index 0000000..31a542d --- /dev/null +++ b/examples/leds.cpp @@ -0,0 +1,105 @@ +/** +Software License Agreement (BSD) + +\file leds.cpp +\authors Jacob Perron +\copyright Copyright (c) 2018, 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. +*/ +#include "create/create.h" + +#include + +int main(int argc, char** argv) { + // Select robot. Assume Create 2 unless argument says otherwise + create::RobotModel model = create::RobotModel::CREATE_2; + std::string port = "/dev/ttyUSB0"; + int baud = 115200; + if (argc > 1 && std::string(argv[1]) == "create1") { + model = create::RobotModel::CREATE_1; + baud = 57600; + std::cout << "Running driver for Create 1" << std::endl; + } + else { + std::cout << "Running driver for Create 2" << std::endl; + } + + // Construct robot object + create::Create* robot = new create::Create(model); + + // Connect to robot + if (robot->connect(port, baud)) + std::cout << "Connected to robot" << std::endl; + else { + std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; + return 1; + } + + // Switch to Full mode + robot->setMode(create::MODE_FULL); + + std::cout << std::endl << "Press center 'Clean' button to disconnect and end program" << std::endl; + + bool enable_check_robot_led = true; + bool enable_debris_led = false; + bool enable_dock_led = true; + bool enable_spot_led = false; + uint8_t power_led = 0; + char digit_buffer[5]; + + while (!robot->isCleanButtonPressed()) { + // Set LEDs + robot->enableCheckRobotLED(enable_check_robot_led); + robot->enableDebrisLED(enable_debris_led); + robot->enableDockLED(enable_dock_led); + robot->enableSpotLED(enable_spot_led); + robot->setPowerLED(power_led); + + // Set 7-segment displays + const int len = sprintf(digit_buffer, "%d", power_led); + for (int i = len; i < 4; i++) digit_buffer[i] = ' '; + robot->setDigitsASCII(digit_buffer[0], digit_buffer[1], digit_buffer[2], digit_buffer[3]); + + // Update LED values + enable_check_robot_led = !enable_check_robot_led; + enable_debris_led = !enable_debris_led; + enable_dock_led = !enable_dock_led; + enable_spot_led = !enable_spot_led; + power_led++; + + usleep(250000); // 5 Hz + } + + std::cout << std::endl; + + // Call disconnect to avoid leaving robot in Full mode + robot->disconnect(); + + // Clean up + delete robot; + + std::cout << "Bye!" << std::endl; + return 0; +} diff --git a/examples/odom_example.cpp b/examples/odom_example.cpp deleted file mode 100644 index 4499f9f..0000000 --- a/examples/odom_example.cpp +++ /dev/null @@ -1,64 +0,0 @@ -#include "create/create.h" - -create::Create* robot; - -int main(int argc, char** argv) { - std::string port = "/dev/ttyUSB0"; - int baud = 115200; - create::RobotModel model = create::RobotModel::CREATE_2; - - if (argc > 1 && std::string(argv[1]) == "create1") { - model = create::RobotModel::CREATE_1; - baud = 57600; - std::cout << "1st generation Create selected" << std::endl; - } - - robot = new create::Create(model); - - // Attempt to connect to Create - if (robot->connect(port, baud)) - std::cout << "Successfully connected to Create" << std::endl; - else { - std::cout << "Failed to connect to Create on port " << port.c_str() << std::endl; - return 1; - } - - robot->setMode(create::MODE_FULL); - - usleep(1000000); - - // Drive in a circle - robot->drive(0.1, 0.5); - - // Quit when center "Clean" button pressed - while (!robot->isCleanButtonPressed()) { - create::Pose pose = robot->getPose(); - create::Vel vel = robot->getVel(); - - // Print pose - std::cout << "x: " << pose.x - << "\ty: " << pose.y - << "\tyaw: " << pose.yaw * 180.0/create::util::PI << std::endl << std::endl; - - // Print velocity - std::cout << "vx: " << vel.x - << "\tvy: " << vel.y - << "\tvyaw: " << vel.yaw * 180.0/create::util::PI << std::endl << std::endl; - - // Print covariances - std::cout << "[ " << pose.covariance[0] << ", " << pose.covariance[1] << ", " << pose.covariance[2] << std::endl - << " " << pose.covariance[3] << ", " << pose.covariance[4] << ", " << pose.covariance[5] << std::endl - << " " << pose.covariance[6] << ", " << pose.covariance[7] << ", " << pose.covariance[8] << " ]" << std::endl << std::endl;; - std::cout << "[ " << vel.covariance[0] << ", " << vel.covariance[1] << ", " << vel.covariance[2] << std::endl - << " " << vel.covariance[3] << ", " << vel.covariance[4] << ", " << vel.covariance[5] << std::endl - << " " << vel.covariance[6] << ", " << vel.covariance[7] << ", " << vel.covariance[8] << " ]" << std::endl << std::endl;; - usleep(1000 * 100); //10hz - } - - std::cout << "Stopping Create." << std::endl; - - robot->disconnect(); - delete robot; - - return 0; -} diff --git a/examples/packets.cpp b/examples/packets.cpp new file mode 100644 index 0000000..4e109c2 --- /dev/null +++ b/examples/packets.cpp @@ -0,0 +1,86 @@ +/** +Software License Agreement (BSD) + +\file packets.cpp +\authors Jacob Perron +\copyright Copyright (c) 2018, 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. +*/ +#include "create/create.h" + +#include + +int main(int argc, char** argv) { + // Select robot. Assume Create 2 unless argument says otherwise + create::RobotModel model = create::RobotModel::CREATE_2; + std::string port = "/dev/ttyUSB0"; + int baud = 115200; + if (argc > 1 && std::string(argv[1]) == "create1") { + model = create::RobotModel::CREATE_1; + baud = 57600; + std::cout << "Running driver for Create 1" << std::endl; + } + else { + std::cout << "Running driver for Create 2" << std::endl; + } + + // Construct robot object + create::Create* robot = new create::Create(model); + + // Connect to robot + if (robot->connect(port, baud)) + std::cout << "Connected to robot" << std::endl; + else { + std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; + return 1; + } + + // Switch to Full mode + // robot->setMode(create::MODE_FULL); + + std::cout << std::endl << "Press center 'Clean' button to disconnect and end program" << std::endl; + + while (!robot->isCleanButtonPressed()) { + // Get serial packet statistics + const uint64_t total_packets = robot->getTotalPackets(); + const uint64_t num_corrupt_packets = robot->getNumCorruptPackets(); + + // Print packet stats + std::cout << "\rTotal packets: " << total_packets << " Corrupt packets: " << num_corrupt_packets; + + usleep(100000); // 10 Hz + } + + std::cout << std::endl; + + // Call disconnect to avoid leaving robot in Full mode + robot->disconnect(); + + // Clean up + delete robot; + + std::cout << "Bye!" << std::endl; + return 0; +} diff --git a/examples/play_song.cpp b/examples/play_song.cpp new file mode 100644 index 0000000..979ef84 --- /dev/null +++ b/examples/play_song.cpp @@ -0,0 +1,97 @@ +/** +Software License Agreement (BSD) + +\file play_song.cpp +\authors Jacob Perron +\copyright Copyright (c) 2018, 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. +*/ +#include "create/create.h" + +#include + +int main(int argc, char** argv) { + // Select robot. Assume Create 2 unless argument says otherwise + create::RobotModel model = create::RobotModel::CREATE_2; + std::string port = "/dev/ttyUSB0"; + int baud = 115200; + if (argc > 1 && std::string(argv[1]) == "create1") { + model = create::RobotModel::CREATE_1; + baud = 57600; + std::cout << "Running driver for Create 1" << std::endl; + } + else { + std::cout << "Running driver for Create 2" << std::endl; + } + + // Construct robot object + create::Create* robot = new create::Create(model); + + // Connect to robot + if (robot->connect(port, baud)) + std::cout << "Connected to robot" << std::endl; + else { + std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; + return 1; + } + + // Switch to Full mode + robot->setMode(create::MODE_FULL); + + // Useful note defintions + const uint8_t G = 55; + const uint8_t AS = 58; + const uint8_t DS = 51; + const float half = 1.0f; + const float quarter = 0.5f; + const float dotted_eigth = 0.375f; + const float sixteenth = 0.125f; + + // Define a song + const uint8_t song_len = 9; + const uint8_t notes[song_len] = { G, G, G, DS, AS, G, DS, AS, G }; + const float durations[song_len] = { quarter, quarter, quarter, dotted_eigth, sixteenth, quarter, dotted_eigth, sixteenth, half }; + robot->defineSong(0, song_len, notes, durations); + + // Sleep to provide time for song to register + usleep(1000000); + + std::cout << "Playing a song!" << std::endl; + + // Request to play the song we just defined + robot->playSong(0); + + // Expect the song to take about four seconds + usleep(4500000); + + // Call disconnect to avoid leaving robot in Full mode + robot->disconnect(); + + // Clean up + delete robot; + + std::cout << "Bye!" << std::endl; + return 0; +} diff --git a/examples/wheeldrop.cpp b/examples/wheeldrop.cpp new file mode 100644 index 0000000..5564539 --- /dev/null +++ b/examples/wheeldrop.cpp @@ -0,0 +1,91 @@ +/** +Software License Agreement (BSD) + +\file wheeldrop.cpp +\authors Jacob Perron +\copyright Copyright (c) 2018, 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. +*/ +#include "create/create.h" + +#include + +int main(int argc, char** argv) { + // Select robot. Assume Create 2 unless argument says otherwise + create::RobotModel model = create::RobotModel::CREATE_2; + std::string port = "/dev/ttyUSB0"; + int baud = 115200; + if (argc > 1 && std::string(argv[1]) == "create1") { + model = create::RobotModel::CREATE_1; + baud = 57600; + std::cout << "Running driver for Create 1" << std::endl; + } + else { + std::cout << "Running driver for Create 2" << std::endl; + } + + // Construct robot object + create::Create* robot = new create::Create(model); + + // Connect to robot + if (robot->connect(port, baud)) + std::cout << "Connected to robot" << std::endl; + else { + std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; + return 1; + } + + // Switch to Full mode + robot->setMode(create::MODE_FULL); + + std::cout << std::endl << "Press center 'Clean' button to disconnect and end program" << std::endl; + + while (!robot->isCleanButtonPressed()) { + // Get wheeldrop status + const bool wheeldrop = robot->isWheeldrop(); + + // Print status + std::cout << "\rWheeldrop status: " << wheeldrop; + + // If dropped, then make light red + if (wheeldrop) + robot->setPowerLED(255); // Red + else + robot->setPowerLED(0); // Green + + usleep(10000); // 10 Hz + } + + std::cout << std::endl; + + // Call disconnect to avoid leaving robot in Full mode + robot->disconnect(); + + // Clean up + delete robot; + + std::cout << "Bye!" << std::endl; + return 0; +} From 360b8c25998fbf8a1011b0a6c1a475ab7d6df37c Mon Sep 17 00:00:00 2001 From: "K.Moriarty" Date: Wed, 4 Apr 2018 21:29:30 -0700 Subject: [PATCH 021/108] updated setDigits function API comments -added HTML to adjust for spacing in diagram, showing the proper ordering of segments. -note that if this doesn't work, you may need to add asterisks back to each line, and try a more manual approach (using  ,
). For the API documentation parsing procedure used by ROS for C++ packages, refer to: http://www.stack.nl/~dimitri/doxygen/manual/htmlcmds.html --- include/create/create.h | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/include/create/create.h b/include/create/create.h index cf51442..1e4d262 100644 --- a/include/create/create.h +++ b/include/create/create.h @@ -278,17 +278,19 @@ namespace create { /** * \brief Set the four 7-segment display digits from left to right. * - * \todo This function is not yet implemented refer to https://github.com/AutonomyLab/libcreate/issues/7 + * \todo This function is not yet implemented refer to https://github.com/AutonomyLab/libcreate/issues/7 * \param segments to enable (true) or disable (false). * The size of segments should be less than 29. * The ordering of segments is left to right, top to bottom for each digit: * - * 0 7 14 21 - * |‾‾‾| |‾‾‾| |‾‾‾| |‾‾‾| - * 1 |___| 2 8 |___| 9 15 |___| 16 22 |___| 23 - * | 3 | | 10| | 17| | 24| - * 4 |___| 5 11|___| 12 18 |___| 19 25 |___| 26 - * 6 13 20 27 + *
+                 0           7             14            21 
+               |‾‾‾|       |‾‾‾|         |‾‾‾|         |‾‾‾|  
+             1 |___| 2   8 |___| 9    15 |___| 16   22 |___| 23 
+               | 3 |       | 10|         | 17|         | 24|
+             4 |___| 5   11|___| 12   18 |___| 19   25 |___| 26
+                 6           13            20            27
+            
* * \return true if successful, false otherwise */ From 6a8702f4e186b0f206d869e747d8ab1010733b5f Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sun, 1 Apr 2018 18:51:28 -0700 Subject: [PATCH 022/108] Remove redundant packets from Data constructor --- src/data.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/data.cpp b/src/data.cpp index ef226e8..340062c 100644 --- a/src/data.cpp +++ b/src/data.cpp @@ -33,8 +33,6 @@ namespace create { ADD_PACKET(ID_OI_MODE, 1, "oi_mode", V_2 | V_3); ADD_PACKET(ID_LEFT_ENC, 2, "enc_counts_left", V_3); ADD_PACKET(ID_RIGHT_ENC, 2, "enc_counts_right", V_3); - ADD_PACKET(ID_LEFT_ENC, 2, "enc_counts_left", V_3); - ADD_PACKET(ID_RIGHT_ENC, 2, "enc_counts_right", V_3); ADD_PACKET(ID_LIGHT, 1, "light_bumper", V_3); ADD_PACKET(ID_LIGHT_LEFT, 2, "light_bumper_left", V_3); ADD_PACKET(ID_LIGHT_FRONT_LEFT, 2, "light_bumper_front_left", V_3); From a70dee6605f28a30a253b8ea1cf22442621de68c Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sun, 1 Apr 2018 20:04:27 -0700 Subject: [PATCH 023/108] Refactor Packet API Declare setData member as protected Rename 'setTempData' to 'setDataToValidate' --- include/create/packet.h | 11 ++++++++--- src/packet.cpp | 2 +- src/serial_query.cpp | 2 +- src/serial_stream.cpp | 2 +- 4 files changed, 11 insertions(+), 6 deletions(-) diff --git a/include/create/packet.h b/include/create/packet.h index 8f2f426..da0a6e2 100644 --- a/include/create/packet.h +++ b/include/create/packet.h @@ -41,6 +41,10 @@ namespace create { mutable boost::mutex dataMutex; mutable boost::mutex tmpDataMutex; + protected: + // Thread safe + void setData(const uint16_t& d); + public: const uint8_t nbytes; const std::string info; @@ -48,10 +52,11 @@ namespace create { Packet(const uint8_t& nbytes, const std::string& info); ~Packet(); - // All of the following are thread safe - void setTempData(const uint16_t& td); + // Thread safe + void setDataToValidate(const uint16_t& td); + // Thread safe void validate(); - void setData(const uint16_t& d); + // Thread safe uint16_t getData() const; }; diff --git a/src/packet.cpp b/src/packet.cpp index 799d9f7..9b65305 100644 --- a/src/packet.cpp +++ b/src/packet.cpp @@ -10,7 +10,7 @@ namespace create { Packet::~Packet() { } - void Packet::setTempData(const uint16_t& tmp) { + void Packet::setDataToValidate(const uint16_t& tmp) { boost::mutex::scoped_lock lock(tmpDataMutex); tmpData = tmp; } diff --git a/src/serial_query.cpp b/src/serial_query.cpp index 1cc23d2..a0b7c00 100644 --- a/src/serial_query.cpp +++ b/src/serial_query.cpp @@ -54,7 +54,7 @@ namespace create { --packetByte; } else if (packetID < maxPacketID) { // New packet - data->getPacket(packetID)->setTempData(packetData); + data->getPacket(packetID)->setDataToValidate(packetData); packetData = 0; ++packetID; packetByte = data->getPacket(packetID)->nbytes - 1; diff --git a/src/serial_stream.cpp b/src/serial_stream.cpp index 8674718..aac3184 100644 --- a/src/serial_stream.cpp +++ b/src/serial_stream.cpp @@ -77,7 +77,7 @@ namespace create { packetBytes += byteRead; } if (numDataBytesRead >= expectedNumDataBytes) { - data->getPacket(packetID)->setTempData(packetBytes); + data->getPacket(packetID)->setDataToValidate(packetBytes); if (numBytesRead >= expectedNumBytes) readState = READ_CHECKSUM; else From 3fca0c57989a7d51f1c2a5476a4173c90706666b Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sun, 1 Apr 2018 20:47:14 -0700 Subject: [PATCH 024/108] Add unit tests (gtests) Testing as much as we can without hardware --- CMakeLists.txt | 69 +++++++++++++- CMakeLists.txt.in | 15 ++++ tests/test_create.cpp | 67 ++++++++++++++ tests/test_data.cpp | 169 +++++++++++++++++++++++++++++++++++ tests/test_packet.cpp | 73 +++++++++++++++ tests/test_robot_model.cpp | 43 +++++++++ tests/test_serial_query.cpp | 90 +++++++++++++++++++ tests/test_serial_stream.cpp | 90 +++++++++++++++++++ 8 files changed, 615 insertions(+), 1 deletion(-) create mode 100644 CMakeLists.txt.in create mode 100644 tests/test_create.cpp create mode 100644 tests/test_data.cpp create mode 100644 tests/test_packet.cpp create mode 100644 tests/test_robot_model.cpp create mode 100644 tests/test_serial_query.cpp create mode 100644 tests/test_serial_stream.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 487e846..325f554 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,4 +1,4 @@ -# After installation this project can be found by 'find_package' command: +# After installation this project can be found by 'find_package' command: # # find_package(libcreate REQUIRED) # include_directores(${libcreate_INCLUDE_DIRS}) @@ -10,6 +10,8 @@ project(libcreate) set(PACKAGE_VERSION 1.5.0) +option(LIBCREATE_BUILD_TESTS "Enable the build of tests." ON) + find_package(Boost REQUIRED COMPONENTS system thread) find_package(Threads REQUIRED) @@ -149,3 +151,68 @@ install( FILES package.xml DESTINATION ${SHARE_INSTALL_DIR} ) + +########### +# Testing # +########### + +if(LIBCREATE_BUILD_TESTS) + enable_testing() + + # Download and unpack googletest at configure time + configure_file(CMakeLists.txt.in googletest-download/CMakeLists.txt) + execute_process(COMMAND ${CMAKE_COMMAND} -G "${CMAKE_GENERATOR}" . + RESULT_VARIABLE GTEST_DOWNLOAD_RESULT + WORKING_DIRECTORY ${CMAKE_BINARY_DIR}/googletest-download + ) + + if(GTEST_DOWNLOAD_RESULT) + message(FATAL_ERROR "CMake step for googletest failed: ${GTEST_DOWNLOAD_RESULT}") + endif() + + # Build googletest + execute_process(COMMAND ${CMAKE_COMMAND} --build . + RESULT_VARIABLE GTEST_BUILD_RESULT + WORKING_DIRECTORY ${CMAKE_BINARY_DIR}/googletest-download + ) + + if(GTEST_BUILD_RESULT) + message(FATAL_ERROR "Build step for googletest failed: ${GTEST_BUILD_RESULT}") + endif() + + # Add googletest directly to our build. This defines the gtest and gtest_main targets. + add_subdirectory(${CMAKE_BINARY_DIR}/googletest-src + ${CMAKE_BINARY_DIR}/googletest-build) + + # The gtest/gtest_main targets carry header search path + # dependencies automatically when using CMake 2.8.11 or + # later. Otherwise we have to add them here ourselves. + if (CMAKE_VERSION VERSION_LESS 2.8.11) + include_directories("${gtest_SOURCE_DIR}/include") + endif() + + # Add tests + set(LIBCREATE_TESTS + test_create + test_data + test_packet + test_robot_model + test_serial_stream + test_serial_query + ) + + foreach(LIBCREATE_TEST ${LIBCREATE_TESTS}) + add_executable(${LIBCREATE_TEST} tests/${LIBCREATE_TEST}.cpp) + + target_link_libraries(${LIBCREATE_TEST} + # ${Boost_LIBRARIES} + ${LIBRARY_NAME} + gtest_main + ) + + add_test( + NAME ${LIBCREATE_TEST} + COMMAND ${LIBCREATE_TEST} + ) + endforeach() +endif() diff --git a/CMakeLists.txt.in b/CMakeLists.txt.in new file mode 100644 index 0000000..4c67ef5 --- /dev/null +++ b/CMakeLists.txt.in @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8.2) + +project(googletest-download NONE) + +include(ExternalProject) +ExternalProject_Add(googletest + GIT_REPOSITORY https://github.com/google/googletest.git + GIT_TAG master + SOURCE_DIR "${CMAKE_BINARY_DIR}/googletest-src" + BINARY_DIR "${CMAKE_BINARY_DIR}/googletest-build" + CONFIGURE_COMMAND "" + BUILD_COMMAND "" + INSTALL_COMMAND "" + TEST_COMMAND "" +) diff --git a/tests/test_create.cpp b/tests/test_create.cpp new file mode 100644 index 0000000..57e76e8 --- /dev/null +++ b/tests/test_create.cpp @@ -0,0 +1,67 @@ +/** +Software License Agreement (BSD) + +\file test_create.cpp +\authors Jacob Perron +\copyright Copyright (c) 2018, 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. +*/ +#include "create/create.h" +#include "create/types.h" + +#include "gtest/gtest.h" + +#include + +TEST(CreateTest, ConstructorSingleParam) +{ + create::Create create_default; + + create::Create create_1(create::RobotModel::CREATE_1); + + create::Create create_2(create::RobotModel::CREATE_2); + + create::Create create_roomba_400(create::RobotModel::ROOMBA_400); +} + +// TEST(CreateTest, ConstructorMultiParam) +// { +// TODO(jacobperron): Document exception thrown and consider defining custom exception +// create::Create create(std::string("/dev/ttyUSB0"), 11520); +// } + +TEST(CreateTest, Connected) +{ + create::Create create; + // Nothing to be connected to + EXPECT_FALSE(create.connected()); +} + +TEST(CreateTest, Disconnect) +{ + create::Create create; + // Even though not connected, this should not crash + create.disconnect(); +} diff --git a/tests/test_data.cpp b/tests/test_data.cpp new file mode 100644 index 0000000..8f893fe --- /dev/null +++ b/tests/test_data.cpp @@ -0,0 +1,169 @@ +/** +Software License Agreement (BSD) + +\file test_data.cpp +\authors Jacob Perron +\copyright Copyright (c) 2018, 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. +*/ +#include "create/data.h" +#include "create/packet.h" +#include "create/types.h" + +#include "gtest/gtest.h" + +#include + +TEST(DataTest, Constructor) +{ + create::Data data_default; + + create::Data data_v_1(create::V_1); + + create::Data data_v_2(create::V_2); + + create::Data data_v_3(create::V_3); + + create::Data data_v_all(create::V_ALL); +} + +// Number of packets for a given protocol are determined in the Data() constructor +TEST(DataTest, GetNumPackets) +{ + // Number of packets shared by all protocols is 16 + create::Data data_v_1(create::V_1); + // Number exclusive to V_1 = 4 + // 16 + 4 = 20 + EXPECT_EQ(static_cast(data_v_1.getNumPackets()), 20); + + create::Data data_v_2(create::V_2); + // Number exclusive to V_2 = 3 + // 16 + 3 = 19 + EXPECT_EQ(static_cast(data_v_2.getNumPackets()), 19); + + create::Data data_v_3(create::V_3); + // Number exclusive to V_3 = 13 + // 16 + 13 = 29 + EXPECT_EQ(static_cast(data_v_3.getNumPackets()), 29); + + create::Data data_v_all(create::V_ALL); + EXPECT_EQ(static_cast(data_v_all.getNumPackets()), 33); +} + +TEST(DataTest, GetPacket) +{ + // Get a packet exclusive to V_1 + create::Data data_v_1(create::V_1); + boost::shared_ptr v_1_packet_ptr = data_v_1.getPacket(create::ID_OVERCURRENTS); + EXPECT_NE(v_1_packet_ptr, boost::shared_ptr()) + << "ID_OVERCURRENTS packet not found for protocol V_1"; + EXPECT_EQ(static_cast(v_1_packet_ptr->nbytes), 1); + EXPECT_EQ(v_1_packet_ptr->info, std::string("overcurrents")); + + // Get a packet for V_2 + create::Data data_v_2(create::V_2); + boost::shared_ptr v_2_packet_ptr = data_v_2.getPacket(create::ID_DISTANCE); + EXPECT_NE(v_2_packet_ptr, boost::shared_ptr()) + << "ID_DISTANCE packet not found for protocol V_2"; + EXPECT_EQ(static_cast(v_2_packet_ptr->nbytes), 2); + EXPECT_EQ(v_2_packet_ptr->info, std::string("distance")); + + // Get a packet exclusive to V_3 + create::Data data_v_3(create::V_3); + boost::shared_ptr v_3_packet_ptr = data_v_3.getPacket(create::ID_LIGHT_FRONT_RIGHT); + EXPECT_NE(v_3_packet_ptr, boost::shared_ptr()) + << "ID_LIGHT_FRONT_RIGHT packet not found for protocol V_3"; + EXPECT_EQ(static_cast(v_3_packet_ptr->nbytes), 2); + EXPECT_EQ(v_3_packet_ptr->info, std::string("light_bumper_front_right")); + + // Get a non-existent packet + boost::shared_ptr not_a_packet_ptr = data_v_3.getPacket(60); + EXPECT_EQ(not_a_packet_ptr, boost::shared_ptr()); +} + +TEST(DataTest, GetPacketIDs) +{ + create::Data data_v_3(create::V_3); + const std::vector packet_ids = data_v_3.getPacketIDs(); + // Vector should have same length as reported by getNumPackets() + ASSERT_EQ(static_cast(packet_ids.size()), 29); + + // Vector should contain ID_LEFT_ENC + bool found = false; + for (std::size_t i = 0; (i < packet_ids.size()) && !found; i++) + { + if (packet_ids[i] == create::ID_LEFT_ENC) + { + found = true; + } + } + EXPECT_TRUE(found) << "ID_LEFT_ENC packet ID not returned for protocol V_3"; +} + +TEST(DataTest, GetTotalDataBytes) +{ + // All protocols have 20 mutual data bytes + // V_1 has an additional 6 bytes + create::Data data_v_1(create::V_1); + EXPECT_EQ(static_cast(data_v_1.getTotalDataBytes()), 26); + + // V_2 has an additional 5 bytes + create::Data data_v_2(create::V_2); + EXPECT_EQ(static_cast(data_v_2.getTotalDataBytes()), 25); + + // V_3 has an additional 21 bytes + create::Data data_v_3(create::V_3); + EXPECT_EQ(static_cast(data_v_3.getTotalDataBytes()), 41); +} + +TEST(DataTest, IsValidPacketID) +{ + create::Data data_v_1(create::V_1); + EXPECT_TRUE(data_v_1.isValidPacketID(create::ID_DIRT_DETECT_RIGHT)) + << "ID_DIRT_DETECT_RIGHT packet not found for protocol V_1"; + EXPECT_FALSE(data_v_1.isValidPacketID(create::ID_OI_MODE)) + << "ID_OI_MODE packet should not exist for protocol V_1"; + + // V_2 has an additional 5 bytes + create::Data data_v_2(create::V_2); + EXPECT_TRUE(data_v_2.isValidPacketID(create::ID_ANGLE)) + << "ID_ANGLE packet not found for protocol V_2"; + EXPECT_FALSE(data_v_2.isValidPacketID(create::ID_LIGHT)) + << "ID_LIGHT packet should not exist for protocol V_2"; + + // V_3 has an additional 21 bytes + create::Data data_v_3(create::V_3); + EXPECT_TRUE(data_v_3.isValidPacketID(create::ID_STASIS)) + << "ID_STATIS packet not found for protocol V_3"; + EXPECT_FALSE(data_v_3.isValidPacketID(create::ID_DISTANCE)) + << "ID_DISTANCE packet should not exist for protocol V_3"; +} + +TEST(DataTest, ValidateAll) +{ + create::Data data_v_3(create::V_3); + // Don't crash + data_v_3.validateAll(); +} diff --git a/tests/test_packet.cpp b/tests/test_packet.cpp new file mode 100644 index 0000000..f1482ce --- /dev/null +++ b/tests/test_packet.cpp @@ -0,0 +1,73 @@ +/** +Software License Agreement (BSD) + +\file test_packet.cpp +\authors Jacob Perron +\copyright Copyright (c) 2018, 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. +*/ +#include "create/packet.h" +#include "create/types.h" + +#include "gtest/gtest.h" + +TEST(PacketTest, Constructor) +{ + create::Packet empty_packet(0, std::string("")); + EXPECT_EQ(static_cast(empty_packet.nbytes), 0); + EXPECT_EQ(empty_packet.info, std::string("")); + + create::Packet some_packet(2, std::string("test_packet")); + EXPECT_EQ(static_cast(some_packet.nbytes), 2); + EXPECT_EQ(some_packet.info, std::string("test_packet")); +} + +TEST(PacketTest, SetValidateAndGetData) +{ + create::Packet packet(2, std::string("test_packet")); + + // Set some data and validate it + const uint16_t some_data = 123; + packet.setDataToValidate(some_data); + packet.validate(); + // Confirm data was validated + const uint16_t some_data_result = packet.getData(); + EXPECT_EQ(some_data_result, some_data); + + // Set zero data and validate it + const uint16_t zero_data = 0; + packet.setDataToValidate(zero_data); + packet.validate(); + // Confirm data was validated + const uint16_t zero_data_result = packet.getData(); + EXPECT_EQ(zero_data_result, zero_data); + + // Set some data but do not validate it + const uint16_t do_not_validate_data = 321; + packet.setDataToValidate(do_not_validate_data); + // Confirm data was not validated + const uint16_t unvalidated_data_result = packet.getData(); + EXPECT_NE(unvalidated_data_result, do_not_validate_data); +} diff --git a/tests/test_robot_model.cpp b/tests/test_robot_model.cpp new file mode 100644 index 0000000..7ddcc86 --- /dev/null +++ b/tests/test_robot_model.cpp @@ -0,0 +1,43 @@ +/** +Software License Agreement (BSD) + +\file test_robot_model.cpp +\authors Jacob Perron +\copyright Copyright (c) 2018, 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. +*/ +#include "create/types.h" + +#include "gtest/gtest.h" + +TEST(RobotModelTest, Equality) +{ + EXPECT_EQ(create::RobotModel::CREATE_1, create::RobotModel::CREATE_1); + EXPECT_EQ(create::RobotModel::CREATE_2, create::RobotModel::CREATE_2); + EXPECT_EQ(create::RobotModel::ROOMBA_400, create::RobotModel::ROOMBA_400); + EXPECT_NE(create::RobotModel::CREATE_1, create::RobotModel::CREATE_2); + EXPECT_NE(create::RobotModel::CREATE_1, create::RobotModel::ROOMBA_400); + EXPECT_NE(create::RobotModel::CREATE_2, create::RobotModel::ROOMBA_400); +} diff --git a/tests/test_serial_query.cpp b/tests/test_serial_query.cpp new file mode 100644 index 0000000..3527bb9 --- /dev/null +++ b/tests/test_serial_query.cpp @@ -0,0 +1,90 @@ +/** +Software License Agreement (BSD) + +\file test_serial_query.cpp +\authors Jacob Perron +\copyright Copyright (c) 2018, 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. +*/ +#include "create/data.h" +#include "create/serial_query.h" + +#include "gtest/gtest.h" + +#include + +TEST(SerialQueryTest, Constructor) +{ + boost::shared_ptr data_ptr = boost::make_shared(); + create::SerialQuery serial_query(data_ptr); +} + +TEST(SerialQueryTest, Connected) +{ + boost::shared_ptr data_ptr = boost::make_shared(); + create::SerialQuery serial_query(data_ptr); + + // Did not call connect and nothing to connect to, so expect false + EXPECT_FALSE(serial_query.connected()); +} + +TEST(SerialQueryTest, Disconnect) +{ + boost::shared_ptr data_ptr = boost::make_shared(); + create::SerialQuery serial_query(data_ptr); + + // Not connected, but should not fail + serial_query.disconnect(); +} + +TEST(SerialQueryTest, NumPackets) +{ + boost::shared_ptr data_ptr = boost::make_shared(); + create::SerialQuery serial_query(data_ptr); + + // Not connected, so zero packets should have been received + EXPECT_EQ(serial_query.getNumCorruptPackets(), 0); + EXPECT_EQ(serial_query.getTotalPackets(), 0); +} + +TEST(SerialQueryTest, Send) +{ + boost::shared_ptr data_ptr = boost::make_shared(); + create::SerialQuery serial_query(data_ptr); + + // Some bytes to send (to set date) + uint8_t bytes[4] = { create::OC_DATE, 0, 1, 2 }; + // Not connected, so failure expected + EXPECT_FALSE(serial_query.send(bytes, 4)); +} + +TEST(SerialQueryTest, SendOpcode) +{ + boost::shared_ptr data_ptr = boost::make_shared(); + create::SerialQuery serial_query(data_ptr); + + // Not connected, so failure expected + EXPECT_FALSE(serial_query.sendOpcode(create::OC_POWER)); +} diff --git a/tests/test_serial_stream.cpp b/tests/test_serial_stream.cpp new file mode 100644 index 0000000..7445939 --- /dev/null +++ b/tests/test_serial_stream.cpp @@ -0,0 +1,90 @@ +/** +Software License Agreement (BSD) + +\file test_serial_stream.cpp +\authors Jacob Perron +\copyright Copyright (c) 2018, 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. +*/ +#include "create/data.h" +#include "create/serial_stream.h" + +#include "gtest/gtest.h" + +#include + +TEST(SerialStreamTest, Constructor) +{ + boost::shared_ptr data_ptr = boost::make_shared(); + create::SerialStream serial_stream(data_ptr); +} + +TEST(SerialStreamTest, Connected) +{ + boost::shared_ptr data_ptr = boost::make_shared(); + create::SerialStream serial_stream(data_ptr); + + // Did not call connect and nothing to connect to, so expect false + EXPECT_FALSE(serial_stream.connected()); +} + +TEST(SerialStreamTest, Disconnect) +{ + boost::shared_ptr data_ptr = boost::make_shared(); + create::SerialStream serial_stream(data_ptr); + + // Not connected, but should not fail + serial_stream.disconnect(); +} + +TEST(SerialStreamTest, NumPackets) +{ + boost::shared_ptr data_ptr = boost::make_shared(); + create::SerialStream serial_stream(data_ptr); + + // Not connected, so zero packets should have been received + EXPECT_EQ(serial_stream.getNumCorruptPackets(), 0); + EXPECT_EQ(serial_stream.getTotalPackets(), 0); +} + +TEST(SerialStreamTest, Send) +{ + boost::shared_ptr data_ptr = boost::make_shared(); + create::SerialStream serial_stream(data_ptr); + + // Some bytes to send (to set date) + uint8_t bytes[4] = { create::OC_DATE, 0, 1, 2 }; + // Not connected, so failure expected + EXPECT_FALSE(serial_stream.send(bytes, 4)); +} + +TEST(SerialStreamTest, SendOpcode) +{ + boost::shared_ptr data_ptr = boost::make_shared(); + create::SerialStream serial_stream(data_ptr); + + // Not connected, so failure expected + EXPECT_FALSE(serial_stream.sendOpcode(create::OC_POWER)); +} From 59fcc041d946581f3b67497b0274873785d48f63 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sun, 1 Apr 2018 20:47:51 -0700 Subject: [PATCH 025/108] Run unit tests as part of CI --- .travis.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.travis.yml b/.travis.yml index 99d6a03..79e21ab 100644 --- a/.travis.yml +++ b/.travis.yml @@ -14,3 +14,5 @@ script: - cmake --version - cmake . - make + - export GTEST_OUTPUT="xml:test_results/" + - make test From c7e111d8eccc97959e8b885366134d51bd2f77d7 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sat, 7 Apr 2018 11:08:07 -0700 Subject: [PATCH 026/108] Add git as catkin build depend Needed for downloading gtest as external CMake project --- package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/package.xml b/package.xml index 46682b2..48b0a72 100644 --- a/package.xml +++ b/package.xml @@ -16,6 +16,8 @@ cmake + git + boost catkin From bb284be503e22c83d65aba705d4bb4e9ff258a8c Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sat, 7 Apr 2018 17:25:25 -0700 Subject: [PATCH 027/108] Update Changelog --- CHANGELOG.rst | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index e4037ee..b3060af 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,28 @@ Changelog for package libcreate ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Add unit tests (gtests) +* Refactor Packet API + * Declare setData member as protected + * Rename 'setTempData' to 'setDataToValidate' +* Remove redundant packets from Data constructor +* Updated setDigits function API comments + * added HTML to adjust for spacing in diagram, showing the proper ordering of segments. +* Update examples + * More concise and focusing on individual features: + * Battery level + * Bumpers + * Drive circle + * LEDs + * Serial packets + * Play song + * Wheeldrop +* Update README +* Refactor cmake files +* Contributors: Jacob Perron, K.Moriarty + 1.5.0 (2017-12-17) ------------------ * Add APIs for getting the measured velocities of the wheels From 7ee03b3d546c6965b75d4d5cc90ccb741aba1960 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sat, 7 Apr 2018 17:26:13 -0700 Subject: [PATCH 028/108] 1.6.0 --- CHANGELOG.rst | 4 ++-- CMakeLists.txt | 2 +- package.xml | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index b3060af..32db539 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package libcreate ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +1.6.0 (2018-04-07) +------------------ * Add unit tests (gtests) * Refactor Packet API * Declare setData member as protected diff --git a/CMakeLists.txt b/CMakeLists.txt index 325f554..1fc13ca 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -8,7 +8,7 @@ cmake_minimum_required(VERSION 2.8.12) project(libcreate) -set(PACKAGE_VERSION 1.5.0) +set(PACKAGE_VERSION 1.6.0) option(LIBCREATE_BUILD_TESTS "Enable the build of tests." ON) diff --git a/package.xml b/package.xml index 48b0a72..7205573 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ libcreate - 1.5.0 + 1.6.0 C++ library for interfacing with iRobot's Create 1 and Create 2 Jacob Perron From ec61febe20d97fd970644aefa78003e9e036530d Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 19 Apr 2018 13:39:59 -0700 Subject: [PATCH 029/108] Add test depend to gtest in package.xml --- package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/package.xml b/package.xml index 7205573..0783e0d 100644 --- a/package.xml +++ b/package.xml @@ -24,6 +24,8 @@ doxygen + gtest + cmake From 08da39e16e2d67d7cc9b9e46e9372c430223dc83 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 19 Apr 2018 13:49:38 -0700 Subject: [PATCH 030/108] Remove external cmake project for gtest Now only build tests if a gtest installation already exists on the system. This should expedite time to build for users that do not care about building/running unit tests and also eliminates the need for internet access when building. --- CMakeLists.txt | 43 ++++++++++--------------------------------- CMakeLists.txt.in | 15 --------------- package.xml | 2 -- 3 files changed, 10 insertions(+), 50 deletions(-) delete mode 100644 CMakeLists.txt.in diff --git a/CMakeLists.txt b/CMakeLists.txt index 1fc13ca..cfc4755 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -157,40 +157,15 @@ install( ########### if(LIBCREATE_BUILD_TESTS) + find_package(GTest) + include_directories(${GTEST_INCLUDE_DIRS}) +endif() + +if(LIBCREATE_BUILD_TESTS AND ${GTEST_FOUND}) + message("GTest installation found. Building tests.") + enable_testing() - # Download and unpack googletest at configure time - configure_file(CMakeLists.txt.in googletest-download/CMakeLists.txt) - execute_process(COMMAND ${CMAKE_COMMAND} -G "${CMAKE_GENERATOR}" . - RESULT_VARIABLE GTEST_DOWNLOAD_RESULT - WORKING_DIRECTORY ${CMAKE_BINARY_DIR}/googletest-download - ) - - if(GTEST_DOWNLOAD_RESULT) - message(FATAL_ERROR "CMake step for googletest failed: ${GTEST_DOWNLOAD_RESULT}") - endif() - - # Build googletest - execute_process(COMMAND ${CMAKE_COMMAND} --build . - RESULT_VARIABLE GTEST_BUILD_RESULT - WORKING_DIRECTORY ${CMAKE_BINARY_DIR}/googletest-download - ) - - if(GTEST_BUILD_RESULT) - message(FATAL_ERROR "Build step for googletest failed: ${GTEST_BUILD_RESULT}") - endif() - - # Add googletest directly to our build. This defines the gtest and gtest_main targets. - add_subdirectory(${CMAKE_BINARY_DIR}/googletest-src - ${CMAKE_BINARY_DIR}/googletest-build) - - # The gtest/gtest_main targets carry header search path - # dependencies automatically when using CMake 2.8.11 or - # later. Otherwise we have to add them here ourselves. - if (CMAKE_VERSION VERSION_LESS 2.8.11) - include_directories("${gtest_SOURCE_DIR}/include") - endif() - # Add tests set(LIBCREATE_TESTS test_create @@ -205,8 +180,8 @@ if(LIBCREATE_BUILD_TESTS) add_executable(${LIBCREATE_TEST} tests/${LIBCREATE_TEST}.cpp) target_link_libraries(${LIBCREATE_TEST} - # ${Boost_LIBRARIES} ${LIBRARY_NAME} + ${GTEST_LIBRARIES} gtest_main ) @@ -215,4 +190,6 @@ if(LIBCREATE_BUILD_TESTS) COMMAND ${LIBCREATE_TEST} ) endforeach() +else() + message("No GTest installation found. Skipping tests.") endif() diff --git a/CMakeLists.txt.in b/CMakeLists.txt.in deleted file mode 100644 index 4c67ef5..0000000 --- a/CMakeLists.txt.in +++ /dev/null @@ -1,15 +0,0 @@ -cmake_minimum_required(VERSION 2.8.2) - -project(googletest-download NONE) - -include(ExternalProject) -ExternalProject_Add(googletest - GIT_REPOSITORY https://github.com/google/googletest.git - GIT_TAG master - SOURCE_DIR "${CMAKE_BINARY_DIR}/googletest-src" - BINARY_DIR "${CMAKE_BINARY_DIR}/googletest-build" - CONFIGURE_COMMAND "" - BUILD_COMMAND "" - INSTALL_COMMAND "" - TEST_COMMAND "" -) diff --git a/package.xml b/package.xml index 0783e0d..296518c 100644 --- a/package.xml +++ b/package.xml @@ -16,8 +16,6 @@ cmake - git - boost catkin From 8b019092f68f6db6dcf01f72c72ab553546f4c61 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 19 Apr 2018 14:00:34 -0700 Subject: [PATCH 031/108] Update README with instructions for building and running unit tests --- README.md | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/README.md b/README.md index 249e635..badfb1a 100644 --- a/README.md +++ b/README.md @@ -18,6 +18,18 @@ C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com * [Boost System Library](http://www.boost.org/doc/libs/1_59_0/libs/system/doc/index.html) * [Boost Thread Library](http://www.boost.org/doc/libs/1_59_0/doc/html/thread.html) +* [Optional] [googletest](https://github.com/google/googletest) + +### Install ### + + sudo apt-get install build-essential cmake libboost-system-dev libboost-thread-dev + + # Optionally, install gtest for building unit tests + sudo apt-get install libgtest-dev + cd /usr/src/gtest + sudo cmake CMakeLists.txt + sudo make + sudo cp *.a /usr/lib #### Serial Permissions #### @@ -48,6 +60,12 @@ Note, the examples found in the "examples" directory are built with the library. git clone https://github.com/AutonomyLab/libcreate.git catkin build +## Running Tests ## + +To run unit tests, execute the following in the build directory: + + make test + ## Known Issues ## * _Clock_ and _Schedule_ buttons are not functional. This is a known bug related to the firmware. From 764981444a1676de6f3a2842b8c9e59b29cac74a Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 19 Apr 2018 14:02:36 -0700 Subject: [PATCH 032/108] Build and install gtest as part of CI --- .travis.yml | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/.travis.yml b/.travis.yml index 79e21ab..efc52e0 100644 --- a/.travis.yml +++ b/.travis.yml @@ -8,11 +8,15 @@ compiler: before_install: - sudo apt-get update -qq - - sudo apt-get install libboost-system-dev libboost-thread-dev + - sudo apt-get install build-essential cmake libboost-system-dev libboost-thread-dev libgtest-dev + - cd /usr/src/gtest + - sudo cmake CMakeLists.txt + - sudo make + - sudo cp *.a /usr/lib script: + - cd ${TRAVIS_BUILD_DIR} - cmake --version - cmake . - make - - export GTEST_OUTPUT="xml:test_results/" - make test From b69d2b830dcee5eabbdd06f5647d17968ad849db Mon Sep 17 00:00:00 2001 From: jacobperron Date: Sat, 21 Apr 2018 00:16:05 -0700 Subject: [PATCH 033/108] Update Changelog --- CHANGELOG.rst | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 32db539..4935ef1 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -1,6 +1,14 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package libcreate ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Build and install gtest as part of CI +* Update README with instructions for building and running unit tests +* Remove external cmake project for gtest + Now only build tests if a gtest installation already exists on the system. This should expedite time to build for users that do not care about building/running unit tests and also eliminates the need for internet access when building. +* Add test depend to gtest in package.xml +* Contributors: Jacob Perron 1.6.0 (2018-04-07) ------------------ From a8c5bf27478d2633c73d198d2388f81af170e040 Mon Sep 17 00:00:00 2001 From: jacobperron Date: Sat, 21 Apr 2018 00:17:14 -0700 Subject: [PATCH 034/108] 1.6.1 --- CHANGELOG.rst | 4 ++-- CMakeLists.txt | 2 +- package.xml | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 4935ef1..98959b8 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -1,8 +1,8 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package libcreate ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +1.6.1 (2018-04-21) +------------------ * Build and install gtest as part of CI * Update README with instructions for building and running unit tests * Remove external cmake project for gtest diff --git a/CMakeLists.txt b/CMakeLists.txt index cfc4755..7b35cdb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -8,7 +8,7 @@ cmake_minimum_required(VERSION 2.8.12) project(libcreate) -set(PACKAGE_VERSION 1.6.0) +set(PACKAGE_VERSION 1.6.1) option(LIBCREATE_BUILD_TESTS "Enable the build of tests." ON) diff --git a/package.xml b/package.xml index 296518c..7c3e2a9 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ libcreate - 1.6.0 + 1.6.1 C++ library for interfacing with iRobot's Create 1 and Create 2 Jacob Perron From 6037b8c3bb235bf106249adfc55b6ad3f30d185e Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sat, 1 Dec 2018 23:01:33 -0800 Subject: [PATCH 035/108] Remove std::cout statement --- src/data.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/data.cpp b/src/data.cpp index 340062c..f8eab92 100644 --- a/src/data.cpp +++ b/src/data.cpp @@ -66,7 +66,6 @@ namespace create { if (isValidPacketID(id)) { return packets[id]; } - std::cout << "Invalid packet " << (int) id << " requested" << std::endl; return boost::shared_ptr(); } From 228f9d6997096c30b2154a72a83c1472fd319dd7 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 11 Mar 2019 22:50:34 -0700 Subject: [PATCH 036/108] Add Xenial build to CI Signed-off-by: Jacob Perron --- .travis.yml | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index efc52e0..9793cd2 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,5 +1,11 @@ sudo: required -dist: trusty + +matrix: + include: + - os: linux + dist: trusty + - os: linux + dist: xenial language: cpp From 4d9f0e891aa91dd0fa156ffd3bf3be54aafd0d9f Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 11 Mar 2019 23:42:31 -0700 Subject: [PATCH 037/108] Use package.xml format 3 Make catkin dependency conditional on ROS 1. Signed-off-by: Jacob Perron --- package.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/package.xml b/package.xml index 7c3e2a9..bfd848d 100644 --- a/package.xml +++ b/package.xml @@ -1,5 +1,5 @@ - + libcreate 1.6.1 C++ library for interfacing with iRobot's Create 1 and Create 2 @@ -18,7 +18,7 @@ boost - catkin + catkin doxygen From 4e8d49702434de952daa19bf9b4a3904b15cea68 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Tue, 26 Mar 2019 22:03:10 -0700 Subject: [PATCH 038/108] Add static cast to fix compiler warnings Signed-off-by: Jacob Perron --- src/create.cpp | 42 +++++++++++++++++++++--------------------- 1 file changed, 21 insertions(+), 21 deletions(-) diff --git a/src/create.cpp b/src/create.cpp index 2e00cf1..eacc608 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -370,10 +370,10 @@ namespace create { } uint8_t cmd[5] = { OC_DRIVE, - vel_mm >> 8, - vel_mm & 0xff, - radius_mm >> 8, - radius_mm & 0xff + static_cast(vel_mm >> 8), + static_cast(vel_mm & 0xff), + static_cast(radius_mm >> 8), + static_cast(radius_mm & 0xff) }; return serial->send(cmd, 5); @@ -389,10 +389,10 @@ namespace create { int16_t rightCmd = roundf(boundedRightVel * 1000); uint8_t cmd[5] = { OC_DRIVE_DIRECT, - rightCmd >> 8, - rightCmd & 0xff, - leftCmd >> 8, - leftCmd & 0xff + static_cast(rightCmd >> 8), + static_cast(rightCmd & 0xff), + static_cast(leftCmd >> 8), + static_cast(leftCmd & 0xff) }; return serial->send(cmd, 5); } else { @@ -439,11 +439,11 @@ namespace create { int16_t rightPwm = roundf(rightWheel * PWM_COUNTS); uint8_t cmd[5] = { OC_DRIVE_PWM, - rightPwm >> 8, - rightPwm & 0xff, - leftPwm >> 8, - leftPwm & 0xff - }; + static_cast(rightPwm >> 8), + static_cast(rightPwm & 0xff), + static_cast(leftPwm >> 8), + static_cast(leftPwm & 0xff) + }; return serial->send(cmd, 5); } @@ -466,10 +466,10 @@ namespace create { vacuumMotorPower = roundf(vacuum * 127); uint8_t cmd[4] = { OC_MOTORS_PWM, - mainMotorPower, - sideMotorPower, - vacuumMotorPower - }; + mainMotorPower, + sideMotorPower, + vacuumMotorPower + }; return serial->send(cmd, 4); } @@ -489,10 +489,10 @@ namespace create { bool Create::updateLEDs() { uint8_t LEDByte = debrisLED + spotLED + dockLED + checkLED; uint8_t cmd[4] = { OC_LEDS, - LEDByte, - powerLED, - powerLEDIntensity - }; + LEDByte, + powerLED, + powerLEDIntensity + }; return serial->send(cmd, 4); } From 5779d0bf3bac4ee7895b4e0406b0efaed5867980 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Tue, 4 Jun 2019 00:18:37 -0700 Subject: [PATCH 039/108] Add Bionic CI job Signed-off-by: Jacob Perron --- .travis.yml | 70 +++++++++++++++++++++++++++++++++++++---------------- 1 file changed, 49 insertions(+), 21 deletions(-) diff --git a/.travis.yml b/.travis.yml index 9793cd2..63ef8fe 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,28 +1,56 @@ sudo: required -matrix: - include: - - os: linux - dist: trusty - - os: linux - dist: xenial - language: cpp +services: + - docker + compiler: - gcc -before_install: - - sudo apt-get update -qq - - sudo apt-get install build-essential cmake libboost-system-dev libboost-thread-dev libgtest-dev - - cd /usr/src/gtest - - sudo cmake CMakeLists.txt - - sudo make - - sudo cp *.a /usr/lib - -script: - - cd ${TRAVIS_BUILD_DIR} - - cmake --version - - cmake . - - make - - make test +jobs: + include: + - stage: test + dist: trusty + before_install: + - sudo apt-get update -qq + - sudo apt-get install build-essential cmake libboost-system-dev libboost-thread-dev libgtest-dev + - cd /usr/src/gtest + - sudo cmake CMakeLists.txt + - sudo make + - sudo cp *.a /usr/lib + script: + - cd ${TRAVIS_BUILD_DIR} + - cmake --version + - cmake . + - make + - make test + - dist: xenial + before_install: + - sudo apt-get update -qq + - sudo apt-get install build-essential cmake libboost-system-dev libboost-thread-dev libgtest-dev + - cd /usr/src/gtest + - sudo cmake CMakeLists.txt + - sudo make + - sudo cp *.a /usr/lib + script: + - cd ${TRAVIS_BUILD_DIR} + - cmake --version + - cmake . + - make + - make test + - dist: xenial + script: + - sudo docker run -it --rm -v ${TRAVIS_BUILD_DIR}:/repo ubuntu:bionic /bin/bash -c " + set -e + export DEBIAN_FRONTEND=noninteractive + sudo apt-get install build-essential cmake libboost-system-dev libboost-thread-dev libgtest-dev + cd /usr/src/gtest + sudo cmake CMakeLists.txt + sudo make + sudo cp *.a /usr/lib + cd /repo + cmake --version + cmake . + make + make test" From 572367314111c27a38fbabd41e50e504bc689d67 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Tue, 4 Jun 2019 00:38:14 -0700 Subject: [PATCH 040/108] Update wheel diameter for Create 2 Now matches the spec from iRobot. Signed-off-by: Jacob Perron --- src/types.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/types.cpp b/src/types.cpp index 3e237a7..f9b02e2 100644 --- a/src/types.cpp +++ b/src/types.cpp @@ -48,5 +48,5 @@ namespace create { RobotModel RobotModel::ROOMBA_400(V_1, 0.258, 57600); RobotModel RobotModel::CREATE_1(V_2, 0.258, 57600); - RobotModel RobotModel::CREATE_2(V_3, 0.235, 115200); + RobotModel RobotModel::CREATE_2(V_3, 0.235, 115200, 0.5, 0.072); } From 070550e655671dfd29430a9870585c57fa78f582 Mon Sep 17 00:00:00 2001 From: Anton Gerasimov Date: Thu, 21 Feb 2019 22:33:42 +0100 Subject: [PATCH 041/108] Fix for compatibility with Boost 1.66 Compatibility with at least as early as Boost 1.58 still persists Signed-off-by: Anton Gerasimov --- src/serial_query.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/serial_query.cpp b/src/serial_query.cpp index a0b7c00..987cd26 100644 --- a/src/serial_query.cpp +++ b/src/serial_query.cpp @@ -44,7 +44,7 @@ namespace create { void SerialQuery::flushInput() { // Only works with POSIX support - tcflush(port.lowest_layer().native(), TCIFLUSH); + tcflush(port.lowest_layer().native_handle(), TCIFLUSH); } void SerialQuery::processByte(uint8_t byteRead) { From 2442ba209cf2e049394c79796effd216d55467a6 Mon Sep 17 00:00:00 2001 From: Yutaka Kondo Date: Tue, 20 Aug 2019 02:32:00 +0900 Subject: [PATCH 042/108] Use shared pointer when binding callback for serial read (#38) * Resolves an issue with ROS Melodic on 18.04. --- include/create/serial.h | 3 ++- src/serial.cpp | 4 ++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/include/create/serial.h b/include/create/serial.h index 9dd9bc3..28b5f69 100644 --- a/include/create/serial.h +++ b/include/create/serial.h @@ -40,13 +40,14 @@ POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #include "create/data.h" #include "create/types.h" #include "create/util.h" namespace create { - class Serial { + class Serial : public boost::enable_shared_from_this { protected: boost::asio::io_service io; diff --git a/src/serial.cpp b/src/serial.cpp index 3894b9e..12876aa 100644 --- a/src/serial.cpp +++ b/src/serial.cpp @@ -72,7 +72,7 @@ namespace create { // Start continuously reading one byte at a time boost::asio::async_read(port, boost::asio::buffer(&byteRead, 1), - boost::bind(&Serial::onData, this, _1, _2)); + boost::bind(&Serial::onData, shared_from_this(), _1, _2)); ioThread = boost::thread(boost::bind(&boost::asio::io_service::run, &io)); @@ -145,7 +145,7 @@ namespace create { // Read the next byte boost::asio::async_read(port, boost::asio::buffer(&byteRead, 1), - boost::bind(&Serial::onData, this, _1, _2)); + boost::bind(&Serial::onData, shared_from_this(), _1, _2)); } bool Serial::send(const uint8_t* bytes, unsigned int numBytes) { From a5dfda66c959d3f1fc6ecd9a839963753631cbf2 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Tue, 20 Aug 2019 19:56:05 -0700 Subject: [PATCH 043/108] Use travis bionic image Signed-off-by: Jacob Perron --- .travis.yml | 27 +++++++++++++-------------- 1 file changed, 13 insertions(+), 14 deletions(-) diff --git a/.travis.yml b/.travis.yml index 63ef8fe..03c0321 100644 --- a/.travis.yml +++ b/.travis.yml @@ -39,18 +39,17 @@ jobs: - cmake . - make - make test - - dist: xenial + - dist: bionic + before_install: + - sudo apt-get update -qq + - sudo apt-get install build-essential cmake libboost-system-dev libboost-thread-dev libgtest-dev + - cd /usr/src/gtest + - sudo cmake CMakeLists.txt + - sudo make + - sudo cp *.a /usr/lib script: - - sudo docker run -it --rm -v ${TRAVIS_BUILD_DIR}:/repo ubuntu:bionic /bin/bash -c " - set -e - export DEBIAN_FRONTEND=noninteractive - sudo apt-get install build-essential cmake libboost-system-dev libboost-thread-dev libgtest-dev - cd /usr/src/gtest - sudo cmake CMakeLists.txt - sudo make - sudo cp *.a /usr/lib - cd /repo - cmake --version - cmake . - make - make test" + - cd ${TRAVIS_BUILD_DIR} + - cmake --version + - cmake . + - make + - make test From df149bdc12998504ccbf6ce3778d52b985f7d208 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 26 Aug 2019 20:16:24 -0700 Subject: [PATCH 044/108] Update maintainer info Signed-off-by: Jacob Perron --- package.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/package.xml b/package.xml index bfd848d..a5f6d7d 100644 --- a/package.xml +++ b/package.xml @@ -4,7 +4,7 @@ 1.6.1 C++ library for interfacing with iRobot's Create 1 and Create 2 - Jacob Perron + Jacob Perron BSD @@ -12,7 +12,7 @@ https://github.com/AutonomyLab/libcreate https://github.com/AutonomyLab/libcreate/issues - Jacob Perron + Jacob Perron cmake From 4a0f8ad72b3cc23fdffa8312d086516c64e077d2 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 26 Aug 2019 20:36:50 -0700 Subject: [PATCH 045/108] Add API for getting left and right wheeldrop Signed-off-by: Jacob Perron --- include/create/create.h | 10 ++++++++++ src/create.cpp | 20 ++++++++++++++++++++ 2 files changed, 30 insertions(+) diff --git a/include/create/create.h b/include/create/create.h index 1e4d262..40196c4 100644 --- a/include/create/create.h +++ b/include/create/create.h @@ -336,6 +336,16 @@ namespace create { */ bool isWheeldrop() const; + /** + * \return true if a left wheeldrop is detected, false otherwise. + */ + bool isLeftWheeldrop() const; + + /** + * \return true if a right wheeldrop is detected, false otherwise. + */ + bool isRightWheeldrop() const; + /** * \return true if left bumper is pressed, false otherwise. */ diff --git a/src/create.cpp b/src/create.cpp index eacc608..8279e2a 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -597,6 +597,26 @@ namespace create { } } + bool Create::isLeftWheeldrop() const { + if (data->isValidPacketID(ID_BUMP_WHEELDROP)) { + return (GET_DATA(ID_BUMP_WHEELDROP) & 0x08) != 0; + } + else { + CERR("[create::Create] ", "Wheeldrop sensor not supported!"); + return false; + } + } + + bool Create::isRightWheeldrop() const { + if (data->isValidPacketID(ID_BUMP_WHEELDROP)) { + return (GET_DATA(ID_BUMP_WHEELDROP) & 0x04) != 0; + } + else { + CERR("[create::Create] ", "Wheeldrop sensor not supported!"); + return false; + } + } + bool Create::isLeftBumper() const { if (data->isValidPacketID(ID_BUMP_WHEELDROP)) { return (GET_DATA(ID_BUMP_WHEELDROP) & 0x02) != 0; From fd2f05047e5ad8c4746a7272926ae3541a4a44a6 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 26 Aug 2019 21:09:59 -0700 Subject: [PATCH 046/108] Update wheeldrop example Now prints status of each wheel to screen. Signed-off-by: Jacob Perron --- examples/wheeldrop.cpp | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/examples/wheeldrop.cpp b/examples/wheeldrop.cpp index 5564539..59e02e6 100644 --- a/examples/wheeldrop.cpp +++ b/examples/wheeldrop.cpp @@ -64,13 +64,18 @@ int main(int argc, char** argv) { while (!robot->isCleanButtonPressed()) { // Get wheeldrop status - const bool wheeldrop = robot->isWheeldrop(); + const bool wheeldrop_left = robot->isLeftWheeldrop(); + const bool wheeldrop_right = robot->isRightWheeldrop(); // Print status - std::cout << "\rWheeldrop status: " << wheeldrop; + std::cout << "\rWheeldrop status (left and right): [ " << + wheeldrop_left << + ", " << + wheeldrop_right << + " ]"; // If dropped, then make light red - if (wheeldrop) + if (wheeldrop_left || wheeldrop_right) robot->setPowerLED(255); // Red else robot->setPowerLED(0); // Green From cafe0c5e56e45fbe106635da8551b872ed019f1c Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 26 Aug 2019 20:46:49 -0700 Subject: [PATCH 047/108] Add API for getting left and right cliff detections Signed-off-by: Jacob Perron --- include/create/create.h | 20 ++++++++++++++++++++ src/create.cpp | 40 ++++++++++++++++++++++++++++++++++++++++ 2 files changed, 60 insertions(+) diff --git a/include/create/create.h b/include/create/create.h index 40196c4..4e03b61 100644 --- a/include/create/create.h +++ b/include/create/create.h @@ -366,6 +366,26 @@ namespace create { */ bool isCliff() const; + /** + * \return true if the left sensor detects a cliff, false otherwise. + */ + bool isCliffLeft() const; + + /** + * \return true if the front left sensor detects a cliff, false otherwise. + */ + bool isCliffFrontLeft() const; + + /** + * \return true if the right sensor detects a cliff, false otherwise. + */ + bool isCliffRight() const; + + /** + * \return true if the front right sensor detects a cliff, false otherwise. + */ + bool isCliffFrontRight() const; + /** * \return true if there is a virtual wall signal is being received. */ diff --git a/src/create.cpp b/src/create.cpp index 8279e2a..e71a556 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -663,6 +663,46 @@ namespace create { } } + bool Create::isCliffLeft() const { + if (data->isValidPacketID(ID_CLIFF_LEFT)) { + return GET_DATA(ID_CLIFF_LEFT) == 1; + } + else { + CERR("[create::Create] ", "Left cliff sensors not supported!"); + return false; + } + } + + bool Create::isCliffFrontLeft() const { + if (data->isValidPacketID(ID_CLIFF_FRONT_LEFT)) { + return GET_DATA(ID_CLIFF_FRONT_LEFT) == 1; + } + else { + CERR("[create::Create] ", "Front left cliff sensors not supported!"); + return false; + } + } + + bool Create::isCliffRight() const { + if (data->isValidPacketID(ID_CLIFF_RIGHT)) { + return GET_DATA(ID_CLIFF_RIGHT) == 1; + } + else { + CERR("[create::Create] ", "Rightt cliff sensors not supported!"); + return false; + } + } + + bool Create::isCliffFrontRight() const { + if (data->isValidPacketID(ID_CLIFF_FRONT_RIGHT)) { + return GET_DATA(ID_CLIFF_FRONT_RIGHT) == 1; + } + else { + CERR("[create::Create] ", "Front right cliff sensors not supported!"); + return false; + } + } + bool Create::isVirtualWall() const { if (data->isValidPacketID(ID_VIRTUAL_WALL)) { return GET_DATA(ID_VIRTUAL_WALL); From 6c36bca74f6b2cf74c1fcd243dd3c971949a0ff9 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 26 Aug 2019 21:09:27 -0700 Subject: [PATCH 048/108] Add cliff sensor example Signed-off-by: Jacob Perron --- CMakeLists.txt | 1 + examples/cliffs.cpp | 96 +++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 97 insertions(+) create mode 100644 examples/cliffs.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 7b35cdb..4a3ad38 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -56,6 +56,7 @@ target_link_libraries(${LIBRARY_NAME} set(EXAMPLES battery_level bumpers + cliffs drive_circle leds packets diff --git a/examples/cliffs.cpp b/examples/cliffs.cpp new file mode 100644 index 0000000..ff0738a --- /dev/null +++ b/examples/cliffs.cpp @@ -0,0 +1,96 @@ +/** +Software License Agreement (BSD) + +\file cliffs.cpp +\authors Jacob Perron +\copyright Copyright (c) 2019, Jacob Perron, 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 the copyright holder 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. +*/ +#include "create/create.h" + +#include + +int main(int argc, char** argv) { + // Select robot. Assume Create 2 unless argument says otherwise + create::RobotModel model = create::RobotModel::CREATE_2; + std::string port = "/dev/ttyUSB0"; + int baud = 115200; + if (argc > 1 && std::string(argv[1]) == "create1") { + model = create::RobotModel::CREATE_1; + baud = 57600; + std::cout << "Running driver for Create 1" << std::endl; + } + else { + std::cout << "Running driver for Create 2" << std::endl; + } + + // Construct robot object + create::Create* robot = new create::Create(model); + + // Connect to robot + if (robot->connect(port, baud)) { + std::cout << "Connected to robot" << std::endl; + } + else { + std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; + return 1; + } + + // Switch to Full mode + robot->setMode(create::MODE_FULL); + + std::cout << std::endl << "Press center 'Clean' button to disconnect and end program" << std::endl; + + while (!robot->isCleanButtonPressed()) { + // Get cliff status + const bool cliff_left = robot->isCliffLeft(); + const bool cliff_front_left = robot->isCliffFrontLeft(); + const bool cliff_front_right = robot->isCliffFrontRight(); + const bool cliff_right = robot->isCliffRight(); + + // Print status + std::cout << "\rCliffs (left to right): [ " << + cliff_left << + ", " << + cliff_front_left << + ", " << + cliff_front_right << + ", " << + cliff_right << + " ]"; + + usleep(10000); // 10 Hz + } + + std::cout << std::endl; + + // Call disconnect to avoid leaving robot in Full mode + robot->disconnect(); + + // Clean up + delete robot; + + return 0; +} From 9b3e77d0fe7f1944aaf9bc71bd2d2a3f8276bab8 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 26 Aug 2019 22:15:00 -0700 Subject: [PATCH 049/108] Update README Signed-off-by: Jacob Perron --- README.md | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index badfb1a..68db4ce 100644 --- a/README.md +++ b/README.md @@ -4,9 +4,9 @@ C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com * [Code API](http://docs.ros.org/kinetic/api/libcreate/html/index.html) * Protocol documentation: - - [`V_1`](http://www.ecsl.cs.sunysb.edu/mint/Roomba_SCI_Spec_Manual.pdf) (Roomba 400 series ) - - [`V_2`](http://www.irobot.com/filelibrary/pdfs/hrd/create/Create%20Open%20Interface_v2.pdf) (Create 1, Roomba 500 series) - - [`V_3`](https://cdn-shop.adafruit.com/datasheets/create_2_Open_Interface_Spec.pdf) (Create 2, Roomba 600-800 series) + - [`V_1`](https://drive.google.com/open?id=0B9O4b91VYXMdUHlqNklDU09NU0k) (Roomba 400 series ) + - [`V_2`](https://drive.google.com/open?id=0B9O4b91VYXMdMmFPMVNDUEZ6d0U) (Create 1, Roomba 500 series) + - [`V_3`](https://drive.google.com/open?id=0B9O4b91VYXMdSVk4amw1N09mQ3c) (Create 2, Roomba 600-800 series) * Author: [Jacob Perron](http://jacobperron.ca) ([Autonomy Lab](http://autonomylab.org), [Simon Fraser University](http://www.sfu.ca)) * Contributors: [Mani Monajjemi](http:mani.im), [Ben Wolsieffer](https://github.com/lopsided98) @@ -53,6 +53,8 @@ Note, the examples found in the "examples" directory are built with the library. #### catkin #### +Requires [catkin_tools](https://catkin-tools.readthedocs.io/en/latest/). + mkdir -p create_ws/src cd create_ws catkin init From b42565be8ee0785e4e5c078772361b604f5bbeb2 Mon Sep 17 00:00:00 2001 From: Ryota Suzuki Date: Tue, 30 Jul 2019 12:43:19 +0900 Subject: [PATCH 050/108] add other serial communication options Otherwize, it can be happened that Operation "7" (0x07) turns to be "135" (0x87) --- src/serial.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/serial.cpp b/src/serial.cpp index 12876aa..9eba401 100644 --- a/src/serial.cpp +++ b/src/serial.cpp @@ -22,6 +22,9 @@ namespace create { using namespace boost::asio; port.open(portName); port.set_option(serial_port::baud_rate(baud)); + port.set_option(serial_port::character_size(8)); + port.set_option(serial_port::parity(serial_port::parity::none)); + port.set_option(serial_port::stop_bits(serial_port::stop_bits::one)); port.set_option(serial_port::flow_control(serial_port::flow_control::none)); usleep(1000000); From 04ab2ccd801fae718b6db7aa45c70e41f284fc9f Mon Sep 17 00:00:00 2001 From: Ryota Suzuki Date: Tue, 30 Jul 2019 12:53:35 +0900 Subject: [PATCH 051/108] add initializer of a variable for compiler compatibility --- src/serial_stream.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/serial_stream.cpp b/src/serial_stream.cpp index aac3184..b06f263 100644 --- a/src/serial_stream.cpp +++ b/src/serial_stream.cpp @@ -5,7 +5,7 @@ namespace create { - SerialStream::SerialStream(boost::shared_ptr d, const uint8_t& header) : Serial(d), headerByte(header){ + SerialStream::SerialStream(boost::shared_ptr d, const uint8_t& header) : Serial(d), readState(READ_HEADER), headerByte(header) { } bool SerialStream::startSensorStream() { From f5044c7ec8d3691a7bf18945d750b906d8195668 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Tue, 27 Aug 2019 00:11:29 -0700 Subject: [PATCH 052/108] Disconnect from serial cleanly on SIGINT Send the STOP opcode before exiting the program to ensure the robot is not left in a state that could potentially drain the battery. Signed-off-by: Jacob Perron --- include/create/serial.h | 3 ++- src/create.cpp | 2 -- src/serial.cpp | 15 +++++++++++++++ 3 files changed, 17 insertions(+), 3 deletions(-) diff --git a/include/create/serial.h b/include/create/serial.h index 28b5f69..6ae9eba 100644 --- a/include/create/serial.h +++ b/include/create/serial.h @@ -51,6 +51,7 @@ namespace create { protected: boost::asio::io_service io; + boost::asio::signal_set signals; boost::asio::serial_port port; private: @@ -62,7 +63,6 @@ namespace create { bool firstRead; uint8_t byteRead; - // Callback executed when data arrives from Create void onData(const boost::system::error_code& e, const std::size_t& size); // Callback to execute once data arrives @@ -80,6 +80,7 @@ namespace create { virtual bool startSensorStream() = 0; virtual void processByte(uint8_t byteRead) = 0; + void signalHandler(const boost::system::error_code& error, int signal_number); // Notifies main thread that data is fresh and makes the user callback void notifyDataReady(); diff --git a/src/create.cpp b/src/create.cpp index e71a556..f908661 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -15,8 +15,6 @@ namespace create { namespace ublas = boost::numeric::ublas; - // TODO: Handle SIGINT to do clean disconnect - void Create::init() { mainMotorPower = 0; sideMotorPower = 0; diff --git a/src/serial.cpp b/src/serial.cpp index 9eba401..8cf27eb 100644 --- a/src/serial.cpp +++ b/src/serial.cpp @@ -8,6 +8,7 @@ namespace create { Serial::Serial(boost::shared_ptr d) : data(d), port(io), + signals(io, SIGINT, SIGTERM), isReading(false), dataReady(false), corruptPackets(0), @@ -18,6 +19,18 @@ namespace create { disconnect(); } + void Serial::signalHandler(const boost::system::error_code& error, int signal_number) { + if (!error) { + if (connected()) { + // Ensure not in Safe/Full modes + sendOpcode(OC_START); + // Stop OI + sendOpcode(OC_STOP); + exit(signal_number); + } + } + } + bool Serial::connect(const std::string& portName, const int& baud, boost::function cb) { using namespace boost::asio; port.open(portName); @@ -27,6 +40,8 @@ namespace create { port.set_option(serial_port::stop_bits(serial_port::stop_bits::one)); port.set_option(serial_port::flow_control(serial_port::flow_control::none)); + signals.async_wait(boost::bind(&Serial::signalHandler, this, _1, _2)); + usleep(1000000); if (port.is_open()) { From c1c0ce6ea9bfc96543c5d5b4f57a81db4f434d5c Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Fri, 30 Aug 2019 00:13:04 -0700 Subject: [PATCH 053/108] Refactor travis.yml Shorten by using matrix key and add -Werror compiler flag. Signed-off-by: Jacob Perron --- .travis.yml | 67 +++++++++++++++++------------------------------------ 1 file changed, 21 insertions(+), 46 deletions(-) diff --git a/.travis.yml b/.travis.yml index 03c0321..0a7bf6b 100644 --- a/.travis.yml +++ b/.travis.yml @@ -2,54 +2,29 @@ sudo: required language: cpp -services: - - docker - compiler: - gcc -jobs: +matrix: include: - - stage: test + - os: linux dist: trusty - before_install: - - sudo apt-get update -qq - - sudo apt-get install build-essential cmake libboost-system-dev libboost-thread-dev libgtest-dev - - cd /usr/src/gtest - - sudo cmake CMakeLists.txt - - sudo make - - sudo cp *.a /usr/lib - script: - - cd ${TRAVIS_BUILD_DIR} - - cmake --version - - cmake . - - make - - make test - - dist: xenial - before_install: - - sudo apt-get update -qq - - sudo apt-get install build-essential cmake libboost-system-dev libboost-thread-dev libgtest-dev - - cd /usr/src/gtest - - sudo cmake CMakeLists.txt - - sudo make - - sudo cp *.a /usr/lib - script: - - cd ${TRAVIS_BUILD_DIR} - - cmake --version - - cmake . - - make - - make test - - dist: bionic - before_install: - - sudo apt-get update -qq - - sudo apt-get install build-essential cmake libboost-system-dev libboost-thread-dev libgtest-dev - - cd /usr/src/gtest - - sudo cmake CMakeLists.txt - - sudo make - - sudo cp *.a /usr/lib - script: - - cd ${TRAVIS_BUILD_DIR} - - cmake --version - - cmake . - - make - - make test + - os: linux + dist: xenial + - os: linux + dist: bionic + +before_install: + - sudo apt-get update -qq + - sudo apt-get install build-essential cmake libboost-system-dev libboost-thread-dev libgtest-dev + - cd /usr/src/gtest + - sudo cmake CMakeLists.txt + - sudo make + - sudo cp *.a /usr/lib + +script: + - cd ${TRAVIS_BUILD_DIR} + - cmake --version + - cmake -DCMAKE_CXX_FLAGS="-Werror" . + - make + - make test From dce7336bbe57f744bcf4d018d0ad422051df8817 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Fri, 30 Aug 2019 00:53:13 -0700 Subject: [PATCH 054/108] Add compiler flags '-Wall -Wextra -Wpedantic' Fix warnings as a result. Signed-off-by: Jacob Perron --- CMakeLists.txt | 2 ++ include/create/types.h | 2 +- include/create/util.h | 4 ++-- src/create.cpp | 21 ++++++++++----------- src/packet.cpp | 6 +++--- src/serial.cpp | 6 +++--- src/serial_stream.cpp | 14 ++++---------- 7 files changed, 25 insertions(+), 30 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4a3ad38..753993d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -8,6 +8,8 @@ cmake_minimum_required(VERSION 2.8.12) project(libcreate) +add_compile_options(-Wall -Wextra -Wpedantic) + set(PACKAGE_VERSION 1.6.1) option(LIBCREATE_BUILD_TESTS "Enable the build of tests." ON) diff --git a/include/create/types.h b/include/create/types.h index f9d99b0..4cf374f 100644 --- a/include/create/types.h +++ b/include/create/types.h @@ -181,7 +181,7 @@ namespace create { OC_SENSORS= 142, OC_QUERY_LIST=149, OC_STREAM = 148, - OC_TOGGLE_STREAM = 150, + OC_TOGGLE_STREAM = 150 }; enum BAUDCODE { diff --git a/include/create/util.h b/include/create/util.h index bbeaacd..6a28f06 100644 --- a/include/create/util.h +++ b/include/create/util.h @@ -55,13 +55,13 @@ namespace create { while (a < -PI) a += TWO_PI; while (a > PI) a -= TWO_PI; return a; - }; + } typedef unsigned long long timestamp_t; /** Get a timestamp for the current time in micro-seconds. */ - static timestamp_t getTimestamp() { + inline timestamp_t getTimestamp() { struct timeval now; gettimeofday(&now, NULL); return now.tv_usec + (timestamp_t) now.tv_sec * 1000000; diff --git a/src/create.cpp b/src/create.cpp index f908661..c023c8a 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -64,15 +64,15 @@ namespace create { } Create::Matrix Create::addMatrices(const Matrix &A, const Matrix &B) const { - int rows = A.size1(); - int cols = A.size2(); + size_t rows = A.size1(); + size_t cols = A.size2(); assert(rows == B.size1()); assert(cols == B.size2()); Matrix C(rows, cols); - for (int i = 0; i < rows; i++) { - for (int j = 0; j < cols; j++) { + for (size_t i = 0u; i < rows; i++) { + for (size_t j = 0u; j < cols; j++) { const float a = A(i, j); const float b = B(i, j); if (util::willFloatOverflow(a, b)) { @@ -345,8 +345,8 @@ namespace create { bool Create::setDate(const DayOfWeek& day, const uint8_t& hour, const uint8_t& min) const { if (day < 0 || day > 6 || - hour < 0 || hour > 23 || - min < 0 || min > 59) + hour > 23 || + min > 59) return false; uint8_t cmd[4] = { OC_DATE, day, hour, min }; @@ -362,7 +362,7 @@ namespace create { int16_t radius_mm = roundf(radius * 1000); // Bound radius if not a special case - if (radius_mm != 32768 && radius_mm != 32767 && + if (radius_mm != -32768 && radius_mm != 32767 && radius_mm != -1 && radius_mm != 1) { BOUND(radius_mm, -util::MAX_RADIUS * 1000, util::MAX_RADIUS * 1000); } @@ -561,7 +561,7 @@ namespace create { const float* durations) const { int i, j; uint8_t duration; - uint8_t cmd[2 * songLength + 3]; + std::vector cmd(2 * songLength + 3); cmd[0] = OC_SONG; cmd[1] = songNumber; cmd[2] = songLength; @@ -575,11 +575,11 @@ namespace create { j++; } - return serial->send(cmd, 2 * songLength + 3); + return serial->send(cmd.data(), cmd.size()); } bool Create::playSong(const uint8_t& songNumber) const { - if (songNumber < 0 || songNumber > 4) + if (songNumber > 4) return false; uint8_t cmd[2] = { OC_PLAY, songNumber }; return serial->send(cmd, 2); @@ -754,7 +754,6 @@ namespace create { ChargingState Create::getChargingState() const { if (data->isValidPacketID(ID_CHARGE_STATE)) { uint8_t chargeState = GET_DATA(ID_CHARGE_STATE); - assert(chargeState >= 0); assert(chargeState <= 5); return (ChargingState) chargeState; } diff --git a/src/packet.cpp b/src/packet.cpp index 9b65305..d408f75 100644 --- a/src/packet.cpp +++ b/src/packet.cpp @@ -3,10 +3,10 @@ namespace create { Packet::Packet(const uint8_t& numBytes, const std::string& comment) : - nbytes(numBytes), - info(comment), data(0), - tmpData(0) { } + tmpData(0), + nbytes(numBytes), + info(comment) { } Packet::~Packet() { } diff --git a/src/serial.cpp b/src/serial.cpp index 8cf27eb..ad9f7fc 100644 --- a/src/serial.cpp +++ b/src/serial.cpp @@ -6,11 +6,11 @@ namespace create { Serial::Serial(boost::shared_ptr d) : - data(d), - port(io), signals(io, SIGINT, SIGTERM), - isReading(false), + port(io), dataReady(false), + isReading(false), + data(d), corruptPackets(0), totalPackets(0) { } diff --git a/src/serial_stream.cpp b/src/serial_stream.cpp index b06f263..6cd8ea3 100644 --- a/src/serial_stream.cpp +++ b/src/serial_stream.cpp @@ -10,19 +10,13 @@ namespace create { bool SerialStream::startSensorStream() { // Request from Create that we want a stream containing all packets - uint8_t numPackets = data->getNumPackets(); + const uint8_t numPackets = data->getNumPackets(); std::vector packetIDs = data->getPacketIDs(); - uint8_t streamReq[2 + numPackets]; - streamReq[0] = OC_STREAM; - streamReq[1] = numPackets; - int i = 2; - for (std::vector::iterator it = packetIDs.begin(); it != packetIDs.end(); ++it) { - streamReq[i] = *it; - i++; - } + packetIDs.insert(packetIDs.begin(), numPackets); + packetIDs.insert(packetIDs.begin(), OC_STREAM); // Start streaming data - send(streamReq, 2 + numPackets); + send(packetIDs.data(), packetIDs.size()); expectedNumBytes = data->getTotalDataBytes() + numPackets; From 5348a9ab7a6ab5cb11b6180f950d2da72fd83268 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 2 Sep 2019 18:54:43 +0000 Subject: [PATCH 055/108] Default to C++11 Signed-off-by: Jacob Perron --- CMakeLists.txt | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 753993d..b406f58 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -17,6 +17,11 @@ option(LIBCREATE_BUILD_TESTS "Enable the build of tests." ON) find_package(Boost REQUIRED COMPONENTS system thread) find_package(Threads REQUIRED) +# Default to C++11 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 11) +endif() + ######### # Build # ######### From 111b0622514387052c2218b08c2234b12405e61f Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 2 Sep 2019 18:55:32 +0000 Subject: [PATCH 056/108] Remove Trusty CI job Since it is EOL. Signed-off-by: Jacob Perron --- .travis.yml | 2 -- 1 file changed, 2 deletions(-) diff --git a/.travis.yml b/.travis.yml index 0a7bf6b..d996656 100644 --- a/.travis.yml +++ b/.travis.yml @@ -7,8 +7,6 @@ compiler: matrix: include: - - os: linux - dist: trusty - os: linux dist: xenial - os: linux From eaeea24a219587be5097b87ebf10ae235734c44a Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 2 Sep 2019 18:56:32 +0000 Subject: [PATCH 057/108] Use std::chrono instead of custom timestamp function Signed-off-by: Jacob Perron --- include/create/create.h | 3 ++- include/create/util.h | 12 ------------ src/create.cpp | 6 +++--- 3 files changed, 5 insertions(+), 16 deletions(-) diff --git a/include/create/create.h b/include/create/create.h index 4e03b61..14ede01 100644 --- a/include/create/create.h +++ b/include/create/create.h @@ -34,6 +34,7 @@ POSSIBILITY OF SUCH DAMAGE. #include #include +#include #include #include @@ -79,7 +80,7 @@ namespace create { float totalLeftDist; float totalRightDist; bool firstOnData; - util::timestamp_t prevOnDataTime; + std::chrono::time_point prevOnDataTime; Matrix poseCovar; diff --git a/include/create/util.h b/include/create/util.h index 6a28f06..3d4d8c5 100644 --- a/include/create/util.h +++ b/include/create/util.h @@ -32,8 +32,6 @@ POSSIBILITY OF SUCH DAMAGE. #ifndef CREATE_UTIL_H #define CREATE_UTIL_H -#include - #define COUT(prefix,msg) (std::cout< std::numeric_limits::max() - std::abs(a) ); } diff --git a/src/create.cpp b/src/create.cpp index c023c8a..10846e5 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -94,13 +94,13 @@ namespace create { prevTicksLeft = GET_DATA(ID_LEFT_ENC); prevTicksRight = GET_DATA(ID_RIGHT_ENC); } - prevOnDataTime = util::getTimestamp(); + prevOnDataTime = std::chrono::system_clock::now(); firstOnData = false; } // Get current time - util::timestamp_t curTime = util::getTimestamp(); - float dt = (curTime - prevOnDataTime) / 1000000.0; + auto curTime = std::chrono::system_clock::now(); + float dt = static_cast>(curTime - prevOnDataTime).count(); float deltaDist, deltaX, deltaY, deltaYaw, leftWheelDist, rightWheelDist, wheelDistDiff; // Protocol versions 1 and 2 use distance and angle fields for odometry From dff0308b1b9d197f1a957d634b587131eb5164f1 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 2 Sep 2019 12:26:09 -0700 Subject: [PATCH 058/108] Cleanup examples Signed-off-by: Jacob Perron --- examples/battery_level.cpp | 23 +++++-------------- examples/bumpers.cpp | 47 +++++++++++++++----------------------- examples/cliffs.cpp | 26 +++++++-------------- examples/drive_circle.cpp | 24 +++++-------------- examples/leds.cpp | 33 +++++++++----------------- examples/packets.cpp | 24 ++++--------------- examples/play_song.cpp | 18 ++++++--------- examples/wheeldrop.cpp | 27 +++++++--------------- 8 files changed, 69 insertions(+), 153 deletions(-) diff --git a/examples/battery_level.cpp b/examples/battery_level.cpp index 49fd70d..24a4f54 100644 --- a/examples/battery_level.cpp +++ b/examples/battery_level.cpp @@ -47,10 +47,10 @@ int main(int argc, char** argv) { } // Construct robot object - create::Create* robot = new create::Create(model); + create::Create robot(model); // Connect to robot - if (robot->connect(port, baud)) + if (robot.connect(port, baud)) std::cout << "Connected to robot" << std::endl; else { std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; @@ -58,17 +58,15 @@ int main(int argc, char** argv) { } // Switch to Full mode - robot->setMode(create::MODE_FULL); - - std::cout << std::endl << "Press center 'Clean' button to disconnect and end program" << std::endl; + robot.setMode(create::MODE_FULL); // Get battery capacity (max charge) - const float battery_capacity = robot->getBatteryCapacity(); + const float battery_capacity = robot.getBatteryCapacity(); float battery_charge = 0.0f; - while (!robot->isCleanButtonPressed()) { + while (true) { // Get battery charge - battery_charge = robot->getBatteryCharge(); + battery_charge = robot.getBatteryCharge(); // Print battery percentage std::cout << "\rBattery level: " << (battery_charge / battery_capacity) * 100.0 << "%"; @@ -76,14 +74,5 @@ int main(int argc, char** argv) { usleep(100000); // 10 Hz } - std::cout << std::endl; - - // Call disconnect to avoid leaving robot in Full mode - robot->disconnect(); - - // Clean up - delete robot; - - std::cout << "Bye!" << std::endl; return 0; } diff --git a/examples/bumpers.cpp b/examples/bumpers.cpp index 52c6877..bb9b432 100644 --- a/examples/bumpers.cpp +++ b/examples/bumpers.cpp @@ -47,10 +47,10 @@ int main(int argc, char** argv) { } // Construct robot object - create::Create* robot = new create::Create(model); + create::Create robot(model); // Connect to robot - if (robot->connect(port, baud)) + if (robot.connect(port, baud)) std::cout << "Connected to robot" << std::endl; else { std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; @@ -58,37 +58,35 @@ int main(int argc, char** argv) { } // Switch to Full mode - robot->setMode(create::MODE_FULL); - - std::cout << std::endl << "Press center 'Clean' button to disconnect and end program" << std::endl; + robot.setMode(create::MODE_FULL); uint16_t light_signals[6]; bool light_bumpers[6]; bool contact_bumpers[2]; - while (!robot->isCleanButtonPressed()) { + while (true) { // Get light sensor data (only available for Create 2 or later robots) if (model == create::RobotModel::CREATE_2) { // Get raw light signal values - light_signals[0] = robot->getLightSignalLeft(); - light_signals[1] = robot->getLightSignalFrontLeft(); - light_signals[2] = robot->getLightSignalCenterLeft(); - light_signals[3] = robot->getLightSignalCenterRight(); - light_signals[4] = robot->getLightSignalFrontRight(); - light_signals[5] = robot->getLightSignalRight(); + light_signals[0] = robot.getLightSignalLeft(); + light_signals[1] = robot.getLightSignalFrontLeft(); + light_signals[2] = robot.getLightSignalCenterLeft(); + light_signals[3] = robot.getLightSignalCenterRight(); + light_signals[4] = robot.getLightSignalFrontRight(); + light_signals[5] = robot.getLightSignalRight(); // Get obstacle data from light sensors (true/false) - light_bumpers[0] = robot->isLightBumperLeft(); - light_bumpers[1] = robot->isLightBumperFrontLeft(); - light_bumpers[2] = robot->isLightBumperCenterLeft(); - light_bumpers[3] = robot->isLightBumperCenterRight(); - light_bumpers[4] = robot->isLightBumperFrontRight(); - light_bumpers[5] = robot->isLightBumperRight(); + light_bumpers[0] = robot.isLightBumperLeft(); + light_bumpers[1] = robot.isLightBumperFrontLeft(); + light_bumpers[2] = robot.isLightBumperCenterLeft(); + light_bumpers[3] = robot.isLightBumperCenterRight(); + light_bumpers[4] = robot.isLightBumperFrontRight(); + light_bumpers[5] = robot.isLightBumperRight(); } // Get state of bumpers - contact_bumpers[0] = robot->isLeftBumper(); - contact_bumpers[1] = robot->isRightBumper(); + contact_bumpers[0] = robot.isLeftBumper(); + contact_bumpers[1] = robot.isRightBumper(); // Print signals from left to right std::cout << "[ " << light_signals[0] << " , " @@ -113,14 +111,5 @@ int main(int argc, char** argv) { usleep(100000); // 10 Hz } - std::cout << std::endl; - - // Call disconnect to avoid leaving robot in Full mode - robot->disconnect(); - - // Clean up - delete robot; - - std::cout << "Bye!" << std::endl; return 0; } diff --git a/examples/cliffs.cpp b/examples/cliffs.cpp index ff0738a..0f004cc 100644 --- a/examples/cliffs.cpp +++ b/examples/cliffs.cpp @@ -47,10 +47,10 @@ int main(int argc, char** argv) { } // Construct robot object - create::Create* robot = new create::Create(model); + create::Create robot(model); // Connect to robot - if (robot->connect(port, baud)) { + if (robot.connect(port, baud)) { std::cout << "Connected to robot" << std::endl; } else { @@ -59,16 +59,14 @@ int main(int argc, char** argv) { } // Switch to Full mode - robot->setMode(create::MODE_FULL); + robot.setMode(create::MODE_FULL); - std::cout << std::endl << "Press center 'Clean' button to disconnect and end program" << std::endl; - - while (!robot->isCleanButtonPressed()) { + while (true) { // Get cliff status - const bool cliff_left = robot->isCliffLeft(); - const bool cliff_front_left = robot->isCliffFrontLeft(); - const bool cliff_front_right = robot->isCliffFrontRight(); - const bool cliff_right = robot->isCliffRight(); + const bool cliff_left = robot.isCliffLeft(); + const bool cliff_front_left = robot.isCliffFrontLeft(); + const bool cliff_front_right = robot.isCliffFrontRight(); + const bool cliff_right = robot.isCliffRight(); // Print status std::cout << "\rCliffs (left to right): [ " << @@ -84,13 +82,5 @@ int main(int argc, char** argv) { usleep(10000); // 10 Hz } - std::cout << std::endl; - - // Call disconnect to avoid leaving robot in Full mode - robot->disconnect(); - - // Clean up - delete robot; - return 0; } diff --git a/examples/drive_circle.cpp b/examples/drive_circle.cpp index f7e1fcf..5c4c8b9 100644 --- a/examples/drive_circle.cpp +++ b/examples/drive_circle.cpp @@ -48,10 +48,10 @@ int main(int argc, char** argv) { } // Construct robot object - create::Create* robot = new create::Create(model); + create::Create robot(model); // Connect to robot - if (robot->connect(port, baud)) + if (robot.connect(port, baud)) std::cout << "Connected to robot" << std::endl; else { std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; @@ -59,19 +59,17 @@ int main(int argc, char** argv) { } // Switch to Full mode - robot->setMode(create::MODE_FULL); - - std::cout << std::endl << "Press center 'Clean' button to disconnect and end program" << std::endl; + robot.setMode(create::MODE_FULL); // There's a delay between switching modes and when the robot will accept drive commands usleep(100000); // Command robot to drive a radius of 0.15 metres at 0.2 m/s - robot->driveRadius(0.2, 0.15); + robot.driveRadius(0.2, 0.15); - while (!robot->isCleanButtonPressed()) { + while (true) { // Get robot odometry and print - const create::Pose pose = robot->getPose(); + const create::Pose pose = robot.getPose(); std::cout << std::fixed << std::setprecision(2) << "\rOdometry (x, y, yaw): (" << pose.x << ", " << pose.y << ", " << pose.yaw << ") "; @@ -79,15 +77,5 @@ int main(int argc, char** argv) { usleep(10000); // 10 Hz } - std::cout << std::endl; - - // Call disconnect to avoid leaving robot in Full mode - // Also, this consequently stops the robot from moving - robot->disconnect(); - - // Clean up - delete robot; - - std::cout << "Bye!" << std::endl; return 0; } diff --git a/examples/leds.cpp b/examples/leds.cpp index 31a542d..e4c566f 100644 --- a/examples/leds.cpp +++ b/examples/leds.cpp @@ -47,10 +47,10 @@ int main(int argc, char** argv) { } // Construct robot object - create::Create* robot = new create::Create(model); + create::Create robot(model); // Connect to robot - if (robot->connect(port, baud)) + if (robot.connect(port, baud)) std::cout << "Connected to robot" << std::endl; else { std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; @@ -58,29 +58,27 @@ int main(int argc, char** argv) { } // Switch to Full mode - robot->setMode(create::MODE_FULL); - - std::cout << std::endl << "Press center 'Clean' button to disconnect and end program" << std::endl; + robot.setMode(create::MODE_FULL); bool enable_check_robot_led = true; bool enable_debris_led = false; bool enable_dock_led = true; bool enable_spot_led = false; - uint8_t power_led = 0; + uint8_t power_led = 0; char digit_buffer[5]; - while (!robot->isCleanButtonPressed()) { + while (true) { // Set LEDs - robot->enableCheckRobotLED(enable_check_robot_led); - robot->enableDebrisLED(enable_debris_led); - robot->enableDockLED(enable_dock_led); - robot->enableSpotLED(enable_spot_led); - robot->setPowerLED(power_led); + robot.enableCheckRobotLED(enable_check_robot_led); + robot.enableDebrisLED(enable_debris_led); + robot.enableDockLED(enable_dock_led); + robot.enableSpotLED(enable_spot_led); + robot.setPowerLED(power_led); // Set 7-segment displays const int len = sprintf(digit_buffer, "%d", power_led); for (int i = len; i < 4; i++) digit_buffer[i] = ' '; - robot->setDigitsASCII(digit_buffer[0], digit_buffer[1], digit_buffer[2], digit_buffer[3]); + robot.setDigitsASCII(digit_buffer[0], digit_buffer[1], digit_buffer[2], digit_buffer[3]); // Update LED values enable_check_robot_led = !enable_check_robot_led; @@ -92,14 +90,5 @@ int main(int argc, char** argv) { usleep(250000); // 5 Hz } - std::cout << std::endl; - - // Call disconnect to avoid leaving robot in Full mode - robot->disconnect(); - - // Clean up - delete robot; - - std::cout << "Bye!" << std::endl; return 0; } diff --git a/examples/packets.cpp b/examples/packets.cpp index 4e109c2..d367487 100644 --- a/examples/packets.cpp +++ b/examples/packets.cpp @@ -47,25 +47,20 @@ int main(int argc, char** argv) { } // Construct robot object - create::Create* robot = new create::Create(model); + create::Create robot(model); // Connect to robot - if (robot->connect(port, baud)) + if (robot.connect(port, baud)) std::cout << "Connected to robot" << std::endl; else { std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; return 1; } - // Switch to Full mode - // robot->setMode(create::MODE_FULL); - - std::cout << std::endl << "Press center 'Clean' button to disconnect and end program" << std::endl; - - while (!robot->isCleanButtonPressed()) { + while (true) { // Get serial packet statistics - const uint64_t total_packets = robot->getTotalPackets(); - const uint64_t num_corrupt_packets = robot->getNumCorruptPackets(); + const uint64_t total_packets = robot.getTotalPackets(); + const uint64_t num_corrupt_packets = robot.getNumCorruptPackets(); // Print packet stats std::cout << "\rTotal packets: " << total_packets << " Corrupt packets: " << num_corrupt_packets; @@ -73,14 +68,5 @@ int main(int argc, char** argv) { usleep(100000); // 10 Hz } - std::cout << std::endl; - - // Call disconnect to avoid leaving robot in Full mode - robot->disconnect(); - - // Clean up - delete robot; - - std::cout << "Bye!" << std::endl; return 0; } diff --git a/examples/play_song.cpp b/examples/play_song.cpp index 979ef84..61132b9 100644 --- a/examples/play_song.cpp +++ b/examples/play_song.cpp @@ -47,10 +47,10 @@ int main(int argc, char** argv) { } // Construct robot object - create::Create* robot = new create::Create(model); + create::Create robot(model); // Connect to robot - if (robot->connect(port, baud)) + if (robot.connect(port, baud)) std::cout << "Connected to robot" << std::endl; else { std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; @@ -58,7 +58,7 @@ int main(int argc, char** argv) { } // Switch to Full mode - robot->setMode(create::MODE_FULL); + robot.setMode(create::MODE_FULL); // Useful note defintions const uint8_t G = 55; @@ -66,14 +66,14 @@ int main(int argc, char** argv) { const uint8_t DS = 51; const float half = 1.0f; const float quarter = 0.5f; - const float dotted_eigth = 0.375f; + const float dotted_eigth = 0.375f; const float sixteenth = 0.125f; // Define a song const uint8_t song_len = 9; const uint8_t notes[song_len] = { G, G, G, DS, AS, G, DS, AS, G }; const float durations[song_len] = { quarter, quarter, quarter, dotted_eigth, sixteenth, quarter, dotted_eigth, sixteenth, half }; - robot->defineSong(0, song_len, notes, durations); + robot.defineSong(0, song_len, notes, durations); // Sleep to provide time for song to register usleep(1000000); @@ -81,17 +81,13 @@ int main(int argc, char** argv) { std::cout << "Playing a song!" << std::endl; // Request to play the song we just defined - robot->playSong(0); + robot.playSong(0); // Expect the song to take about four seconds usleep(4500000); // Call disconnect to avoid leaving robot in Full mode - robot->disconnect(); + robot.disconnect(); - // Clean up - delete robot; - - std::cout << "Bye!" << std::endl; return 0; } diff --git a/examples/wheeldrop.cpp b/examples/wheeldrop.cpp index 59e02e6..5e0bf66 100644 --- a/examples/wheeldrop.cpp +++ b/examples/wheeldrop.cpp @@ -47,10 +47,10 @@ int main(int argc, char** argv) { } // Construct robot object - create::Create* robot = new create::Create(model); + create::Create robot(model); // Connect to robot - if (robot->connect(port, baud)) + if (robot.connect(port, baud)) std::cout << "Connected to robot" << std::endl; else { std::cout << "Failed to connect to robot on port " << port.c_str() << std::endl; @@ -58,14 +58,12 @@ int main(int argc, char** argv) { } // Switch to Full mode - robot->setMode(create::MODE_FULL); + robot.setMode(create::MODE_FULL); - std::cout << std::endl << "Press center 'Clean' button to disconnect and end program" << std::endl; - - while (!robot->isCleanButtonPressed()) { + while (true) { // Get wheeldrop status - const bool wheeldrop_left = robot->isLeftWheeldrop(); - const bool wheeldrop_right = robot->isRightWheeldrop(); + const bool wheeldrop_left = robot.isLeftWheeldrop(); + const bool wheeldrop_right = robot.isRightWheeldrop(); // Print status std::cout << "\rWheeldrop status (left and right): [ " << @@ -76,21 +74,12 @@ int main(int argc, char** argv) { // If dropped, then make light red if (wheeldrop_left || wheeldrop_right) - robot->setPowerLED(255); // Red + robot.setPowerLED(255); // Red else - robot->setPowerLED(0); // Green + robot.setPowerLED(0); // Green usleep(10000); // 10 Hz } - std::cout << std::endl; - - // Call disconnect to avoid leaving robot in Full mode - robot->disconnect(); - - // Clean up - delete robot; - - std::cout << "Bye!" << std::endl; return 0; } From f9f3aa9d3dc87cf3ed0d8250205966ab01ce6f8a Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 2 Sep 2019 14:12:10 -0700 Subject: [PATCH 059/108] 2.0.0 --- CHANGELOG.rst | 33 +++++++++++++++++++++++++++++++++ package.xml | 2 +- 2 files changed, 34 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 98959b8..66c4dd6 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -1,6 +1,39 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package libcreate ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +2.0.0 (2019-09-02) +------------------ +* Cleanup examples +* Use std::chrono instead of custom timestamp function +* Remove Trusty CI job + * Since it is EOL. +* Default to C++11 +* Add compiler flags '-Wall -Wextra -Wpedantic' + * Fix warnings as a result. +* Disconnect from serial cleanly on SIGINT + * Send the STOP opcode before exiting the program to ensure the robot is not left in a state that could potentially drain the battery. +* Initialize variable for compiler compatibility +* Add other serial communication options + Otherwise, it's possible that Operation "7" (0x07) is confused for "135" (0x87) +* Add cliff sensor example +* Add API for getting left and right cliff detections +* Update wheeldrop example +* Add API for getting left and right wheeldrop +* Use shared pointer when binding callback for serial read (`#38 `_) + * Resolves an issue with ROS Melodic on 18.04. +* Fix for compatibility with Boost 1.66 + * Compatibility with at least as early as Boost 1.58 still persists +* Update wheel diameter for Create 2 + * Now matches the spec from iRobot. +* Add Bionic CI job +* Add static cast to fix compiler warnings +* Use package.xml format 3 + * Make catkin dependency conditional on ROS 1. +* Add Xenial build to CI +* Remove std::cout statement +* Contributors: Anton Gerasimov, Jacob Perron, Ryota Suzuki, Yutaka Kondo + 1.6.1 (2018-04-21) ------------------ * Build and install gtest as part of CI diff --git a/package.xml b/package.xml index a5f6d7d..aa633ad 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ libcreate - 1.6.1 + 2.0.0 C++ library for interfacing with iRobot's Create 1 and Create 2 Jacob Perron From ccf6d0cdc0e97d7abf170def16b0746d89b5274c Mon Sep 17 00:00:00 2001 From: Stefan Krupop Date: Wed, 4 Dec 2019 01:20:35 +0100 Subject: [PATCH 060/108] Use OC_MOTORS instead of OC_MOTORS_PWM on V_1 models (#55) SCI for older Roombas (V_1) did not include OC_MOTORS_PWM, but only OC_MOTORS. Use that instead of OC_MOTORS_PWM for V_1, interpeting values != 0 as "on" --- src/create.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/create.cpp b/src/create.cpp index 10846e5..a0f9da6 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -463,6 +463,15 @@ namespace create { sideMotorPower = roundf(side * 127); vacuumMotorPower = roundf(vacuum * 127); + if (model.getVersion() == V_1) { + uint8_t cmd[2] = { OC_MOTORS, + static_cast((side != 0.0 ? 1 : 0) | + (vacuum != 0.0 ? 2 : 0) | + (main != 0.0 ? 4 : 0)) + }; + return serial->send(cmd, 2); + } + uint8_t cmd[4] = { OC_MOTORS_PWM, mainMotorPower, sideMotorPower, From 850b011a55a04d87569d26f6a264b36a5857f33a Mon Sep 17 00:00:00 2001 From: Daniel Smith Date: Sun, 1 Nov 2020 20:42:57 -0500 Subject: [PATCH 061/108] Implement methods for getting overcurrent status. (#57) --- src/create.cpp | 30 ++++++++++++++++++++++++++++++ src/data.cpp | 2 +- tests/test_data.cpp | 24 ++++++++++++------------ 3 files changed, 43 insertions(+), 13 deletions(-) diff --git a/src/create.cpp b/src/create.cpp index a0f9da6..3fe68d2 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -1036,6 +1036,36 @@ namespace create { } } + bool Create::isSideBrushOvercurrent() const { + if (data->isValidPacketID(ID_OVERCURRENTS)) { + return (GET_DATA(ID_OVERCURRENTS) & 0x01) != 0; + } + else { + CERR("[create::Create] ", "Overcurrent sensor not supported!"); + return false; + } + } + + bool Create::isMainBrushOvercurrent() const { + if (data->isValidPacketID(ID_OVERCURRENTS)) { + return (GET_DATA(ID_OVERCURRENTS) & 0x04) != 0; + } + else { + CERR("[create::Create] ", "Overcurrent sensor not supported!"); + return false; + } + } + + bool Create::isWheelOvercurrent() const { + if (data->isValidPacketID(ID_OVERCURRENTS)) { + return (GET_DATA(ID_OVERCURRENTS) & 0x18) != 0; + } + else { + CERR("[create::Create] ", "Overcurrent sensor not supported!"); + return false; + } + } + float Create::getLeftWheelDistance() const { return totalLeftDist; } diff --git a/src/data.cpp b/src/data.cpp index f8eab92..fe3726a 100644 --- a/src/data.cpp +++ b/src/data.cpp @@ -17,7 +17,7 @@ namespace create { ADD_PACKET(ID_CLIFF_FRONT_RIGHT, 1, "cliff_front_right", V_ALL); ADD_PACKET(ID_CLIFF_RIGHT, 1, "cliff_right", V_ALL); ADD_PACKET(ID_VIRTUAL_WALL, 1, "virtual_wall", V_ALL); - ADD_PACKET(ID_OVERCURRENTS, 1, "overcurrents", V_1); + ADD_PACKET(ID_OVERCURRENTS, 1, "overcurrents", V_ALL); ADD_PACKET(ID_DIRT_DETECT_LEFT, 1, "dirt_detect_left", V_ALL); ADD_PACKET(ID_DIRT_DETECT_RIGHT, 1, "dirt_detect_right", V_1); ADD_PACKET(ID_IR_OMNI, 1, "ir_opcode", V_ALL); diff --git a/tests/test_data.cpp b/tests/test_data.cpp index 8f893fe..9978466 100644 --- a/tests/test_data.cpp +++ b/tests/test_data.cpp @@ -52,21 +52,21 @@ TEST(DataTest, Constructor) // Number of packets for a given protocol are determined in the Data() constructor TEST(DataTest, GetNumPackets) { - // Number of packets shared by all protocols is 16 + // Number of packets shared by all protocols is 17 create::Data data_v_1(create::V_1); - // Number exclusive to V_1 = 4 - // 16 + 4 = 20 + // Number exclusive to V_1 = 3 + // 17 + 3 = 20 EXPECT_EQ(static_cast(data_v_1.getNumPackets()), 20); create::Data data_v_2(create::V_2); // Number exclusive to V_2 = 3 - // 16 + 3 = 19 - EXPECT_EQ(static_cast(data_v_2.getNumPackets()), 19); + // 17 + 3 = 20 + EXPECT_EQ(static_cast(data_v_2.getNumPackets()), 20); create::Data data_v_3(create::V_3); // Number exclusive to V_3 = 13 - // 16 + 13 = 29 - EXPECT_EQ(static_cast(data_v_3.getNumPackets()), 29); + // 17 + 13 = 30 + EXPECT_EQ(static_cast(data_v_3.getNumPackets()), 30); create::Data data_v_all(create::V_ALL); EXPECT_EQ(static_cast(data_v_all.getNumPackets()), 33); @@ -108,7 +108,7 @@ TEST(DataTest, GetPacketIDs) create::Data data_v_3(create::V_3); const std::vector packet_ids = data_v_3.getPacketIDs(); // Vector should have same length as reported by getNumPackets() - ASSERT_EQ(static_cast(packet_ids.size()), 29); + ASSERT_EQ(static_cast(packet_ids.size()), 30); // Vector should contain ID_LEFT_ENC bool found = false; @@ -124,18 +124,18 @@ TEST(DataTest, GetPacketIDs) TEST(DataTest, GetTotalDataBytes) { - // All protocols have 20 mutual data bytes - // V_1 has an additional 6 bytes + // All protocols have 21 mutual data bytes + // V_1 has an additional 5 bytes create::Data data_v_1(create::V_1); EXPECT_EQ(static_cast(data_v_1.getTotalDataBytes()), 26); // V_2 has an additional 5 bytes create::Data data_v_2(create::V_2); - EXPECT_EQ(static_cast(data_v_2.getTotalDataBytes()), 25); + EXPECT_EQ(static_cast(data_v_2.getTotalDataBytes()), 26); // V_3 has an additional 21 bytes create::Data data_v_3(create::V_3); - EXPECT_EQ(static_cast(data_v_3.getTotalDataBytes()), 41); + EXPECT_EQ(static_cast(data_v_3.getTotalDataBytes()), 42); } TEST(DataTest, IsValidPacketID) From 2b9591f0f7330e7d5d4e89366eb40447c9eca20c Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Sun, 1 Nov 2020 18:05:17 -0800 Subject: [PATCH 062/108] Replace boost features with C++11 equivalents (#58) * Replace boost features with C++11 equivalents Signed-off-by: Jacob Perron * Include in util.h Needed for std::abs Signed-off-by: Jacob Perron --- include/create/create.h | 6 +++--- include/create/data.h | 7 +++---- include/create/packet.h | 6 +++--- include/create/serial.h | 27 ++++++++++++++------------- include/create/serial_query.h | 8 +++----- include/create/serial_stream.h | 8 ++------ include/create/util.h | 2 ++ src/create.cpp | 11 +++++------ src/data.cpp | 10 +++++----- src/packet.cpp | 10 ++++++---- src/serial.cpp | 30 ++++++++++++++++++++---------- src/serial_query.cpp | 6 ++++-- src/serial_stream.cpp | 3 ++- tests/test_create.cpp | 2 -- tests/test_data.cpp | 18 +++++++++--------- tests/test_serial_query.cpp | 14 +++++++------- tests/test_serial_stream.cpp | 14 +++++++------- 17 files changed, 95 insertions(+), 87 deletions(-) diff --git a/include/create/create.h b/include/create/create.h index 14ede01..6ca2fe9 100644 --- a/include/create/create.h +++ b/include/create/create.h @@ -32,9 +32,9 @@ POSSIBILITY OF SUCH DAMAGE. #ifndef CREATE_H #define CREATE_H -#include #include #include +#include #include #include @@ -96,8 +96,8 @@ namespace create { bool updateLEDs(); protected: - boost::shared_ptr data; - boost::shared_ptr serial; + std::shared_ptr data; + std::shared_ptr serial; public: /** diff --git a/include/create/data.h b/include/create/data.h index 345bd1a..c4392e8 100644 --- a/include/create/data.h +++ b/include/create/data.h @@ -32,9 +32,8 @@ POSSIBILITY OF SUCH DAMAGE. #ifndef CREATE_DATA_H #define CREATE_DATA_H -#include -#include #include +#include #include #include "create/packet.h" @@ -43,7 +42,7 @@ POSSIBILITY OF SUCH DAMAGE. namespace create { class Data { private: - std::map > packets; + std::map > packets; uint32_t totalDataBytes; std::vector ids; @@ -52,7 +51,7 @@ namespace create { ~Data(); bool isValidPacketID(const uint8_t id) const; - boost::shared_ptr getPacket(const uint8_t id); + std::shared_ptr getPacket(const uint8_t id); void validateAll(); uint32_t getTotalDataBytes() const; uint8_t getNumPackets() const; diff --git a/include/create/packet.h b/include/create/packet.h index da0a6e2..d1e7928 100644 --- a/include/create/packet.h +++ b/include/create/packet.h @@ -31,15 +31,15 @@ POSSIBILITY OF SUCH DAMAGE. #ifndef CREATE_PACKET_H #define CREATE_PACKET_H -#include +#include namespace create { class Packet { private: uint16_t data; uint16_t tmpData; - mutable boost::mutex dataMutex; - mutable boost::mutex tmpDataMutex; + mutable std::mutex dataMutex; + mutable std::mutex tmpDataMutex; protected: // Thread safe diff --git a/include/create/serial.h b/include/create/serial.h index 6ae9eba..5280040 100644 --- a/include/create/serial.h +++ b/include/create/serial.h @@ -35,19 +35,20 @@ POSSIBILITY OF SUCH DAMAGE. #ifndef CREATE_SERIAL_H #define CREATE_SERIAL_H +#include +#include +#include +#include +#include + #include -#include -#include -#include -#include -#include #include "create/data.h" #include "create/types.h" #include "create/util.h" namespace create { - class Serial : public boost::enable_shared_from_this { + class Serial : public std::enable_shared_from_this { protected: boost::asio::io_service io; @@ -55,9 +56,9 @@ namespace create { boost::asio::serial_port port; private: - boost::thread ioThread; - boost::condition_variable dataReadyCond; - boost::mutex dataReadyMut; + std::thread ioThread; + std::condition_variable dataReadyCond; + std::mutex dataReadyMut; bool dataReady; bool isReading; bool firstRead; @@ -66,13 +67,13 @@ namespace create { // Callback executed when data arrives from Create void onData(const boost::system::error_code& e, const std::size_t& size); // Callback to execute once data arrives - boost::function callback; + std::function callback; // Start and stop reading data from Create bool startReading(); void stopReading(); protected: - boost::shared_ptr data; + std::shared_ptr data; // These are for possible diagnostics uint64_t corruptPackets; uint64_t totalPackets; @@ -85,9 +86,9 @@ namespace create { void notifyDataReady(); public: - Serial(boost::shared_ptr data); + Serial(std::shared_ptr data); ~Serial(); - bool connect(const std::string& port, const int& baud = 115200, boost::function cb = 0); + bool connect(const std::string& port, const int& baud = 115200, std::function cb = 0); void disconnect(); inline bool connected() const { return port.is_open(); }; bool send(const uint8_t* bytes, const uint32_t numBytes); diff --git a/include/create/serial_query.h b/include/create/serial_query.h index 033785a..a10b34e 100644 --- a/include/create/serial_query.h +++ b/include/create/serial_query.h @@ -36,11 +36,9 @@ POSSIBILITY OF SUCH DAMAGE. #ifndef CREATE_SERIAL_QUERY_H #define CREATE_SERIAL_QUERY_H +#include + #include -#include -#include -#include -#include #include "create/data.h" #include "create/types.h" @@ -69,7 +67,7 @@ namespace create { void processByte(uint8_t byteRead); public: - SerialQuery(boost::shared_ptr data); + SerialQuery(std::shared_ptr data); }; } // namespace create diff --git a/include/create/serial_stream.h b/include/create/serial_stream.h index d59d126..07d4c05 100644 --- a/include/create/serial_stream.h +++ b/include/create/serial_stream.h @@ -35,11 +35,7 @@ POSSIBILITY OF SUCH DAMAGE. #ifndef CREATE_SERIAL_STREAM_H #define CREATE_SERIAL_STREAM_H -#include -#include -#include -#include -#include +#include #include "create/data.h" #include "create/types.h" @@ -73,7 +69,7 @@ namespace create { void processByte(uint8_t byteRead); public: - SerialStream(boost::shared_ptr data, const uint8_t& header = create::util::STREAM_HEADER); + SerialStream(std::shared_ptr data, const uint8_t& header = create::util::STREAM_HEADER); }; } // namespace create diff --git a/include/create/util.h b/include/create/util.h index 3d4d8c5..aa3d8f5 100644 --- a/include/create/util.h +++ b/include/create/util.h @@ -32,6 +32,8 @@ POSSIBILITY OF SUCH DAMAGE. #ifndef CREATE_UTIL_H #define CREATE_UTIL_H +#include + #define COUT(prefix,msg) (std::cout< -#include #include #include #include +#include #include #include "create/create.h" @@ -42,11 +41,11 @@ namespace create { poseCovar = Matrix(3, 3, 0.0); requestedLeftVel = 0; requestedRightVel = 0; - data = boost::shared_ptr(new Data(model.getVersion())); + data = std::shared_ptr(new Data(model.getVersion())); if (model.getVersion() == V_1) { - serial = boost::make_shared(data); + serial = std::make_shared(data); } else { - serial = boost::make_shared(data); + serial = std::make_shared(data); } } @@ -273,7 +272,7 @@ namespace create { float maxWait = 30; // seconds float retryInterval = 5; //seconds time(&start); - while (!serial->connect(port, baud, boost::bind(&Create::onData, this)) && !timeout) { + while (!serial->connect(port, baud, std::bind(&Create::onData, this)) && !timeout) { time(&now); if (difftime(now, start) > maxWait) { timeout = true; diff --git a/src/data.cpp b/src/data.cpp index fe3726a..5e8acce 100644 --- a/src/data.cpp +++ b/src/data.cpp @@ -1,6 +1,6 @@ #include "create/data.h" -#define ADD_PACKET(id,nbytes,info,enabledVersion) if ((enabledVersion) & version) packets[id]=boost::make_shared(nbytes,info) +#define ADD_PACKET(id,nbytes,info,enabledVersion) if ((enabledVersion) & version) packets[id]=std::make_shared(nbytes,info) namespace create { @@ -45,7 +45,7 @@ namespace create { ADD_PACKET(ID_STASIS, 1, "stasis", V_3); totalDataBytes = 0; - for (std::map >::iterator it = packets.begin(); + for (std::map >::iterator it = packets.begin(); it != packets.end(); ++it) { ids.push_back(it->first); @@ -62,15 +62,15 @@ namespace create { return false; } - boost::shared_ptr Data::getPacket(uint8_t id) { + std::shared_ptr Data::getPacket(uint8_t id) { if (isValidPacketID(id)) { return packets[id]; } - return boost::shared_ptr(); + return std::shared_ptr(); } void Data::validateAll() { - for (std::map >::iterator it = packets.begin(); + for (std::map >::iterator it = packets.begin(); it != packets.end(); ++it) { it->second->validate(); diff --git a/src/packet.cpp b/src/packet.cpp index d408f75..517e90d 100644 --- a/src/packet.cpp +++ b/src/packet.cpp @@ -1,3 +1,5 @@ +#include + #include "create/packet.h" namespace create { @@ -11,22 +13,22 @@ namespace create { Packet::~Packet() { } void Packet::setDataToValidate(const uint16_t& tmp) { - boost::mutex::scoped_lock lock(tmpDataMutex); + std::lock_guard lock(tmpDataMutex); tmpData = tmp; } void Packet::validate() { - boost::mutex::scoped_lock lock(tmpDataMutex); + std::lock_guard lock(tmpDataMutex); setData(tmpData); } void Packet::setData(const uint16_t& d) { - boost::mutex::scoped_lock lock(dataMutex); + std::lock_guard lock(dataMutex); data = d; } uint16_t Packet::getData() const { - boost::mutex::scoped_lock lock(dataMutex); + std::lock_guard lock(dataMutex); return data; } diff --git a/src/serial.cpp b/src/serial.cpp index ad9f7fc..2a87a8a 100644 --- a/src/serial.cpp +++ b/src/serial.cpp @@ -1,3 +1,5 @@ +#include +#include #include #include "create/serial.h" @@ -5,7 +7,7 @@ namespace create { - Serial::Serial(boost::shared_ptr d) : + Serial::Serial(std::shared_ptr d) : signals(io, SIGINT, SIGTERM), port(io), dataReady(false), @@ -31,7 +33,7 @@ namespace create { } } - bool Serial::connect(const std::string& portName, const int& baud, boost::function cb) { + bool Serial::connect(const std::string& portName, const int& baud, std::function cb) { using namespace boost::asio; port.open(portName); port.set_option(serial_port::baud_rate(baud)); @@ -40,7 +42,7 @@ namespace create { port.set_option(serial_port::stop_bits(serial_port::stop_bits::one)); port.set_option(serial_port::flow_control(serial_port::flow_control::none)); - signals.async_wait(boost::bind(&Serial::signalHandler, this, _1, _2)); + signals.async_wait(std::bind(&Serial::signalHandler, this, std::placeholders::_1, std::placeholders::_2)); usleep(1000000); @@ -90,17 +92,22 @@ namespace create { // Start continuously reading one byte at a time boost::asio::async_read(port, boost::asio::buffer(&byteRead, 1), - boost::bind(&Serial::onData, shared_from_this(), _1, _2)); + std::bind(&Serial::onData, + shared_from_this(), + std::placeholders::_1, + std::placeholders::_2)); - ioThread = boost::thread(boost::bind(&boost::asio::io_service::run, &io)); + ioThread = std::thread(std::bind( + static_cast( + &boost::asio::io_service::run), &io)); // Wait for first complete read to finish - boost::unique_lock lock(dataReadyMut); + std::unique_lock lock(dataReadyMut); int attempts = 1; int maxAttempts = 10; while (!dataReady) { - if (!dataReadyCond.timed_wait(lock, boost::get_system_time() + boost::posix_time::milliseconds(500))) { + if (dataReadyCond.wait_for(lock, std::chrono::milliseconds(500)) == std::cv_status::timeout) { if (attempts >= maxAttempts) { CERR("[create::Serial] ", "failed to receive data from Create. Check if robot is powered!"); io.stop(); @@ -125,7 +132,7 @@ namespace create { ioThread.join(); isReading = false; { - boost::lock_guard lock(dataReadyMut); + std::lock_guard lock(dataReadyMut); dataReady = false; } } @@ -138,7 +145,7 @@ namespace create { // Notify first data packets ready { - boost::lock_guard lock(dataReadyMut); + std::lock_guard lock(dataReadyMut); if (!dataReady) { dataReady = true; dataReadyCond.notify_one(); @@ -163,7 +170,10 @@ namespace create { // Read the next byte boost::asio::async_read(port, boost::asio::buffer(&byteRead, 1), - boost::bind(&Serial::onData, shared_from_this(), _1, _2)); + std::bind(&Serial::onData, + shared_from_this(), + std::placeholders::_1, + std::placeholders::_2)); } bool Serial::send(const uint8_t* bytes, unsigned int numBytes) { diff --git a/src/serial_query.cpp b/src/serial_query.cpp index 987cd26..2d3997b 100644 --- a/src/serial_query.cpp +++ b/src/serial_query.cpp @@ -1,4 +1,5 @@ #include +#include #include "create/serial_query.h" #include "create/types.h" @@ -7,7 +8,7 @@ namespace create { - SerialQuery::SerialQuery(boost::shared_ptr d) : Serial(d), + SerialQuery::SerialQuery(std::shared_ptr d) : Serial(d), streamRecoveryTimer(io), packetID(ID_BUMP_WHEELDROP), packetByte(0), @@ -30,7 +31,8 @@ namespace create { send(requestPacket, 2); // Automatically resend request if no response is received streamRecoveryTimer.expires_from_now(boost::posix_time::milliseconds(50)); - streamRecoveryTimer.async_wait(boost::bind(&SerialQuery::restartSensorStream, this, _1)); + streamRecoveryTimer.async_wait( + std::bind(&SerialQuery::restartSensorStream, this, std::placeholders::_1)); } void SerialQuery::restartSensorStream(const boost::system::error_code& err) { diff --git a/src/serial_stream.cpp b/src/serial_stream.cpp index 6cd8ea3..b22a07e 100644 --- a/src/serial_stream.cpp +++ b/src/serial_stream.cpp @@ -1,11 +1,12 @@ #include +#include #include "create/serial_stream.h" #include "create/types.h" namespace create { - SerialStream::SerialStream(boost::shared_ptr d, const uint8_t& header) : Serial(d), readState(READ_HEADER), headerByte(header) { + SerialStream::SerialStream(std::shared_ptr d, const uint8_t& header) : Serial(d), readState(READ_HEADER), headerByte(header) { } bool SerialStream::startSensorStream() { diff --git a/tests/test_create.cpp b/tests/test_create.cpp index 57e76e8..aaa8a26 100644 --- a/tests/test_create.cpp +++ b/tests/test_create.cpp @@ -33,8 +33,6 @@ POSSIBILITY OF SUCH DAMAGE. #include "gtest/gtest.h" -#include - TEST(CreateTest, ConstructorSingleParam) { create::Create create_default; diff --git a/tests/test_data.cpp b/tests/test_data.cpp index 9978466..e9752a0 100644 --- a/tests/test_data.cpp +++ b/tests/test_data.cpp @@ -34,7 +34,7 @@ POSSIBILITY OF SUCH DAMAGE. #include "gtest/gtest.h" -#include +#include TEST(DataTest, Constructor) { @@ -76,31 +76,31 @@ TEST(DataTest, GetPacket) { // Get a packet exclusive to V_1 create::Data data_v_1(create::V_1); - boost::shared_ptr v_1_packet_ptr = data_v_1.getPacket(create::ID_OVERCURRENTS); - EXPECT_NE(v_1_packet_ptr, boost::shared_ptr()) + std::shared_ptr v_1_packet_ptr = data_v_1.getPacket(create::ID_OVERCURRENTS); + EXPECT_NE(v_1_packet_ptr, std::shared_ptr()) << "ID_OVERCURRENTS packet not found for protocol V_1"; EXPECT_EQ(static_cast(v_1_packet_ptr->nbytes), 1); EXPECT_EQ(v_1_packet_ptr->info, std::string("overcurrents")); // Get a packet for V_2 create::Data data_v_2(create::V_2); - boost::shared_ptr v_2_packet_ptr = data_v_2.getPacket(create::ID_DISTANCE); - EXPECT_NE(v_2_packet_ptr, boost::shared_ptr()) + std::shared_ptr v_2_packet_ptr = data_v_2.getPacket(create::ID_DISTANCE); + EXPECT_NE(v_2_packet_ptr, std::shared_ptr()) << "ID_DISTANCE packet not found for protocol V_2"; EXPECT_EQ(static_cast(v_2_packet_ptr->nbytes), 2); EXPECT_EQ(v_2_packet_ptr->info, std::string("distance")); // Get a packet exclusive to V_3 create::Data data_v_3(create::V_3); - boost::shared_ptr v_3_packet_ptr = data_v_3.getPacket(create::ID_LIGHT_FRONT_RIGHT); - EXPECT_NE(v_3_packet_ptr, boost::shared_ptr()) + std::shared_ptr v_3_packet_ptr = data_v_3.getPacket(create::ID_LIGHT_FRONT_RIGHT); + EXPECT_NE(v_3_packet_ptr, std::shared_ptr()) << "ID_LIGHT_FRONT_RIGHT packet not found for protocol V_3"; EXPECT_EQ(static_cast(v_3_packet_ptr->nbytes), 2); EXPECT_EQ(v_3_packet_ptr->info, std::string("light_bumper_front_right")); // Get a non-existent packet - boost::shared_ptr not_a_packet_ptr = data_v_3.getPacket(60); - EXPECT_EQ(not_a_packet_ptr, boost::shared_ptr()); + std::shared_ptr not_a_packet_ptr = data_v_3.getPacket(60); + EXPECT_EQ(not_a_packet_ptr, std::shared_ptr()); } TEST(DataTest, GetPacketIDs) diff --git a/tests/test_serial_query.cpp b/tests/test_serial_query.cpp index 3527bb9..b88b101 100644 --- a/tests/test_serial_query.cpp +++ b/tests/test_serial_query.cpp @@ -33,17 +33,17 @@ POSSIBILITY OF SUCH DAMAGE. #include "gtest/gtest.h" -#include +#include TEST(SerialQueryTest, Constructor) { - boost::shared_ptr data_ptr = boost::make_shared(); + std::shared_ptr data_ptr = std::make_shared(); create::SerialQuery serial_query(data_ptr); } TEST(SerialQueryTest, Connected) { - boost::shared_ptr data_ptr = boost::make_shared(); + std::shared_ptr data_ptr = std::make_shared(); create::SerialQuery serial_query(data_ptr); // Did not call connect and nothing to connect to, so expect false @@ -52,7 +52,7 @@ TEST(SerialQueryTest, Connected) TEST(SerialQueryTest, Disconnect) { - boost::shared_ptr data_ptr = boost::make_shared(); + std::shared_ptr data_ptr = std::make_shared(); create::SerialQuery serial_query(data_ptr); // Not connected, but should not fail @@ -61,7 +61,7 @@ TEST(SerialQueryTest, Disconnect) TEST(SerialQueryTest, NumPackets) { - boost::shared_ptr data_ptr = boost::make_shared(); + std::shared_ptr data_ptr = std::make_shared(); create::SerialQuery serial_query(data_ptr); // Not connected, so zero packets should have been received @@ -71,7 +71,7 @@ TEST(SerialQueryTest, NumPackets) TEST(SerialQueryTest, Send) { - boost::shared_ptr data_ptr = boost::make_shared(); + std::shared_ptr data_ptr = std::make_shared(); create::SerialQuery serial_query(data_ptr); // Some bytes to send (to set date) @@ -82,7 +82,7 @@ TEST(SerialQueryTest, Send) TEST(SerialQueryTest, SendOpcode) { - boost::shared_ptr data_ptr = boost::make_shared(); + std::shared_ptr data_ptr = std::make_shared(); create::SerialQuery serial_query(data_ptr); // Not connected, so failure expected diff --git a/tests/test_serial_stream.cpp b/tests/test_serial_stream.cpp index 7445939..9ae789c 100644 --- a/tests/test_serial_stream.cpp +++ b/tests/test_serial_stream.cpp @@ -33,17 +33,17 @@ POSSIBILITY OF SUCH DAMAGE. #include "gtest/gtest.h" -#include +#include TEST(SerialStreamTest, Constructor) { - boost::shared_ptr data_ptr = boost::make_shared(); + std::shared_ptr data_ptr = std::make_shared(); create::SerialStream serial_stream(data_ptr); } TEST(SerialStreamTest, Connected) { - boost::shared_ptr data_ptr = boost::make_shared(); + std::shared_ptr data_ptr = std::make_shared(); create::SerialStream serial_stream(data_ptr); // Did not call connect and nothing to connect to, so expect false @@ -52,7 +52,7 @@ TEST(SerialStreamTest, Connected) TEST(SerialStreamTest, Disconnect) { - boost::shared_ptr data_ptr = boost::make_shared(); + std::shared_ptr data_ptr = std::make_shared(); create::SerialStream serial_stream(data_ptr); // Not connected, but should not fail @@ -61,7 +61,7 @@ TEST(SerialStreamTest, Disconnect) TEST(SerialStreamTest, NumPackets) { - boost::shared_ptr data_ptr = boost::make_shared(); + std::shared_ptr data_ptr = std::make_shared(); create::SerialStream serial_stream(data_ptr); // Not connected, so zero packets should have been received @@ -71,7 +71,7 @@ TEST(SerialStreamTest, NumPackets) TEST(SerialStreamTest, Send) { - boost::shared_ptr data_ptr = boost::make_shared(); + std::shared_ptr data_ptr = std::make_shared(); create::SerialStream serial_stream(data_ptr); // Some bytes to send (to set date) @@ -82,7 +82,7 @@ TEST(SerialStreamTest, Send) TEST(SerialStreamTest, SendOpcode) { - boost::shared_ptr data_ptr = boost::make_shared(); + std::shared_ptr data_ptr = std::make_shared(); create::SerialStream serial_stream(data_ptr); // Not connected, so failure expected From cc95ad35a01835cbc3ead0aef0a09b6c88272626 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 28 Dec 2020 21:06:48 -0800 Subject: [PATCH 063/108] Correct version in CMake package version file Signed-off-by: Jacob Perron --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b406f58..97cf437 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,7 +10,7 @@ project(libcreate) add_compile_options(-Wall -Wextra -Wpedantic) -set(PACKAGE_VERSION 1.6.1) +set(PACKAGE_VERSION 2.0.0) option(LIBCREATE_BUILD_TESTS "Enable the build of tests." ON) From fd1d0a220f026691f9e65ca64a5d19165889aee4 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 25 Mar 2021 16:04:41 -0700 Subject: [PATCH 064/108] Use steady clock for computing velocity (#59) Signed-off-by: Jacob Perron --- include/create/create.h | 2 +- src/create.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/include/create/create.h b/include/create/create.h index 6ca2fe9..deaa4ba 100644 --- a/include/create/create.h +++ b/include/create/create.h @@ -80,7 +80,7 @@ namespace create { float totalLeftDist; float totalRightDist; bool firstOnData; - std::chrono::time_point prevOnDataTime; + std::chrono::time_point prevOnDataTime; Matrix poseCovar; diff --git a/src/create.cpp b/src/create.cpp index 75bfe9a..e8e359e 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -93,12 +93,12 @@ namespace create { prevTicksLeft = GET_DATA(ID_LEFT_ENC); prevTicksRight = GET_DATA(ID_RIGHT_ENC); } - prevOnDataTime = std::chrono::system_clock::now(); + prevOnDataTime = std::chrono::steady_clock::now(); firstOnData = false; } // Get current time - auto curTime = std::chrono::system_clock::now(); + auto curTime = std::chrono::steady_clock::now(); float dt = static_cast>(curTime - prevOnDataTime).count(); float deltaDist, deltaX, deltaY, deltaYaw, leftWheelDist, rightWheelDist, wheelDistDiff; From 20ed0b16aeca5da637652b772f99e7a7bafa9c0a Mon Sep 17 00:00:00 2001 From: tim-fan Date: Mon, 19 Apr 2021 18:24:43 +1200 Subject: [PATCH 065/108] Use average dt values for velocity calculation (#60) --- include/create/create.h | 11 +++++++++++ src/create.cpp | 29 ++++++++++++++++++++++++----- 2 files changed, 35 insertions(+), 5 deletions(-) diff --git a/include/create/create.h b/include/create/create.h index deaa4ba..eadec1a 100644 --- a/include/create/create.h +++ b/include/create/create.h @@ -37,6 +37,7 @@ POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #include "create/serial_stream.h" #include "create/serial_query.h" @@ -81,6 +82,8 @@ namespace create { float totalRightDist; bool firstOnData; std::chrono::time_point prevOnDataTime; + std::deque dtHistory; + uint8_t dtHistoryLength; Matrix poseCovar; @@ -332,6 +335,14 @@ namespace create { */ bool playSong(const uint8_t& songNumber) const; + /** + * \brief Set dtHistoryLength parameter. + * Used to configure the size of the buffer for calculating average time delta (dt). + * between onData calls, which in turn is used for velocity calculation. + * \param dtHistoryLength number of historical samples to use for calculating average dt. + */ + void setDtHistoryLength(const uint8_t& dtHistoryLength); + /** * \return true if a left or right wheeldrop is detected, false otherwise. */ diff --git a/src/create.cpp b/src/create.cpp index e8e359e..a4f966f 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -41,6 +41,7 @@ namespace create { poseCovar = Matrix(3, 3, 0.0); requestedLeftVel = 0; requestedRightVel = 0; + dtHistoryLength = 100; data = std::shared_ptr(new Data(model.getVersion())); if (model.getVersion() == V_1) { serial = std::make_shared(data); @@ -167,8 +168,22 @@ namespace create { deltaYaw = wheelDistDiff / model.getAxleLength(); } - measuredLeftVel = leftWheelDist / dt; - measuredRightVel = rightWheelDist / dt; + // determine average dt over window + dtHistory.push_front(dt); + + if (dtHistory.size() > dtHistoryLength){ + dtHistory.pop_back(); + } + + float dtHistorySum = 0; + for (auto it = dtHistory.cbegin(); it != dtHistory.cend(); ++it) + { + dtHistorySum += *it; + } + auto dtAverage = dtHistorySum / dtHistory.size(); + + measuredLeftVel = leftWheelDist / dtAverage; + measuredRightVel = rightWheelDist / dtAverage; // Moving straight if (fabs(wheelDistDiff) < util::EPS) { @@ -183,10 +198,10 @@ namespace create { totalLeftDist += leftWheelDist; totalRightDist += rightWheelDist; - if (fabs(dt) > util::EPS) { - vel.x = deltaDist / dt; + if (fabs(dtAverage) > util::EPS) { + vel.x = deltaDist / dtAverage; vel.y = 0.0; - vel.yaw = deltaYaw / dt; + vel.yaw = deltaYaw / dtAverage; } else { vel.x = 0.0; vel.y = 0.0; @@ -593,6 +608,10 @@ namespace create { return serial->send(cmd, 2); } + void Create::setDtHistoryLength(const uint8_t& dtHistoryLength) { + this->dtHistoryLength = dtHistoryLength; + } + bool Create::isWheeldrop() const { if (data->isValidPacketID(ID_BUMP_WHEELDROP)) { return (GET_DATA(ID_BUMP_WHEELDROP) & 0x0C) != 0; From 449ed4b0938801ebc4ef9810a3ff5d3e4f438f42 Mon Sep 17 00:00:00 2001 From: Daniel Smith Date: Mon, 19 Apr 2021 02:29:20 -0400 Subject: [PATCH 066/108] Fix motor setting (#62) * Change 3 setAllMotor calls to use float parameter. * Use static_cast for proper conversion to float. --- src/create.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/create.cpp b/src/create.cpp index a4f966f..270e687 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -496,15 +496,15 @@ namespace create { } bool Create::setMainMotor(const float& main) { - return setAllMotors(main, sideMotorPower, vacuumMotorPower); + return setAllMotors(main, static_cast(sideMotorPower) / 127.0, static_cast(vacuumMotorPower) / 127.0); } bool Create::setSideMotor(const float& side) { - return setAllMotors(mainMotorPower, side, vacuumMotorPower); + return setAllMotors(static_cast(mainMotorPower) / 127.0, side, static_cast(vacuumMotorPower) / 127.0); } bool Create::setVacuumMotor(const float& vacuum) { - return setAllMotors(mainMotorPower, sideMotorPower, vacuum); + return setAllMotors(static_cast(mainMotorPower) / 127.0, static_cast(sideMotorPower) / 127.0, vacuum); } bool Create::updateLEDs() { From ca4c63b5a88ab4cc24ce212727613dc47af3904d Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 5 May 2021 21:10:18 -0700 Subject: [PATCH 067/108] Add GitHub workflow for CI Signed-off-by: Jacob Perron --- .github/workflows/ci.yaml | 41 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 41 insertions(+) create mode 100644 .github/workflows/ci.yaml diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml new file mode 100644 index 0000000..6653702 --- /dev/null +++ b/.github/workflows/ci.yaml @@ -0,0 +1,41 @@ +name: Build and test +on: + # Run for any commit in origin repository + push: + # And pull requests from forks + pull_request: + branches: + # This avoids running the job twice for PRs from origin repository + - '**:**' + +env: + BUILD_TYPE: Release + +jobs: + build: + runs-on: ${{ matrix.os }} + strategy: + matrix: + os: [ubuntu-18.04, ubuntu-20.04] + + steps: + - name: Install dependencies + run: | + sudo apt install build-essential cmake git libboost-system-dev libboost-thread-dev + git clone https://github.com/google/googletest.git + cd googletest + cmake CMakeLists.txt + make + sudo make install + + - uses: actions/checkout@v2 + + - name: Configure CMake + run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} -DCMAKE_CXX_FLAGS="-Werror" + + - name: Build + run: cmake --build ${{github.workspace}}/build --config ${{env.BUILD_TYPE}} + + - name: Test + working-directory: ${{github.workspace}}/build + run: ctest -C ${{env.BUILD_TYPE}} From 68ee257f1d688cf98ccf92c714df5b40ea4d492a Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 5 May 2021 21:10:31 -0700 Subject: [PATCH 068/108] Remove travis.yml Signed-off-by: Jacob Perron --- .travis.yml | 28 ---------------------------- 1 file changed, 28 deletions(-) delete mode 100644 .travis.yml diff --git a/.travis.yml b/.travis.yml deleted file mode 100644 index d996656..0000000 --- a/.travis.yml +++ /dev/null @@ -1,28 +0,0 @@ -sudo: required - -language: cpp - -compiler: - - gcc - -matrix: - include: - - os: linux - dist: xenial - - os: linux - dist: bionic - -before_install: - - sudo apt-get update -qq - - sudo apt-get install build-essential cmake libboost-system-dev libboost-thread-dev libgtest-dev - - cd /usr/src/gtest - - sudo cmake CMakeLists.txt - - sudo make - - sudo cp *.a /usr/lib - -script: - - cd ${TRAVIS_BUILD_DIR} - - cmake --version - - cmake -DCMAKE_CXX_FLAGS="-Werror" . - - make - - make test From 98660f6c2102d8183bfc1ec96d4cdcd476175af1 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 5 May 2021 21:18:04 -0700 Subject: [PATCH 069/108] Fix 'maybe-uninitialized' warnings Signed-off-by: Jacob Perron --- examples/bumpers.cpp | 6 +++--- src/create.cpp | 12 +++++++++--- 2 files changed, 12 insertions(+), 6 deletions(-) diff --git a/examples/bumpers.cpp b/examples/bumpers.cpp index bb9b432..80a62be 100644 --- a/examples/bumpers.cpp +++ b/examples/bumpers.cpp @@ -60,9 +60,9 @@ int main(int argc, char** argv) { // Switch to Full mode robot.setMode(create::MODE_FULL); - uint16_t light_signals[6]; - bool light_bumpers[6]; - bool contact_bumpers[2]; + uint16_t light_signals[6] = {0, 0, 0, 0, 0, 0}; + bool light_bumpers[6] = {false, false, false, false, false, false}; + bool contact_bumpers[2] = {false, false}; while (true) { // Get light sensor data (only available for Create 2 or later robots) diff --git a/src/create.cpp b/src/create.cpp index 270e687..6718d2e 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -101,10 +101,16 @@ namespace create { // Get current time auto curTime = std::chrono::steady_clock::now(); float dt = static_cast>(curTime - prevOnDataTime).count(); - float deltaDist, deltaX, deltaY, deltaYaw, leftWheelDist, rightWheelDist, wheelDistDiff; + float deltaDist = 0.0f; + float deltaX = 0.0f; + float deltaY = 0.0f; + float deltaYaw = 0.0f; + float leftWheelDist = 0.0f; + float rightWheelDist = 0.0f; + float wheelDistDiff = 0.0f; // Protocol versions 1 and 2 use distance and angle fields for odometry - int16_t angleField; + int16_t angleField = 0; if (model.getVersion() <= V_2) { // This is a standards compliant way of doing unsigned to signed conversion uint16_t distanceRaw = GET_DATA(ID_DISTANCE); @@ -318,7 +324,7 @@ namespace create { // Switch to safe mode (required for compatibility with V_1) if (!(serial->sendOpcode(OC_START) && serial->sendOpcode(OC_CONTROL))) return false; } - bool ret; + bool ret = false; switch (mode) { case MODE_OFF: if (model.getVersion() == V_2) { From fbc87dea3f811aabcc86a64f3e35f2e92972ebbf Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 5 May 2021 21:56:29 -0700 Subject: [PATCH 070/108] Update build badge Signed-off-by: Jacob Perron --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 68db4ce..4dd559a 100644 --- a/README.md +++ b/README.md @@ -12,7 +12,7 @@ C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com ## Build Status ## -![Build Status](https://api.travis-ci.org/AutonomyLab/libcreate.svg?branch=master) +![Build Status](https://github.com/AutonomyLab/libcreate/workflows/Build%20and%20test/badge.svg) ## Dependencies ## From 1563e2b3e180e55baa5fcc4cef147cb333227a5c Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 5 May 2021 23:25:40 -0700 Subject: [PATCH 071/108] Add option to disable signal handlers (#65) This gives the user the option to create their own signal handler without having create::Create interfere. They can disable the sigint/sigterm handler and be responsible for disconnecting from the robot themselves. Signed-off-by: Jacob Perron --- include/create/create.h | 12 ++++++++---- include/create/serial.h | 2 +- include/create/serial_query.h | 2 +- include/create/serial_stream.h | 5 ++++- src/create.cpp | 17 ++++++++++------- src/serial.cpp | 11 ++++++++--- src/serial_query.cpp | 3 ++- src/serial_stream.cpp | 2 +- 8 files changed, 35 insertions(+), 19 deletions(-) diff --git a/include/create/create.h b/include/create/create.h index eadec1a..0652861 100644 --- a/include/create/create.h +++ b/include/create/create.h @@ -92,7 +92,7 @@ namespace create { float requestedLeftVel; float requestedRightVel; - void init(); + void init(bool install_signal_handler); // Add two matrices and handle overflow case Matrix addMatrices(const Matrix &A, const Matrix &B) const; void onData(); @@ -109,8 +109,10 @@ namespace create { * Calling this constructor Does not attempt to establish a serial connection to the robot. * * \param model the type of the robot. See RobotModel to determine the value for your robot. - */ - Create(RobotModel model = RobotModel::CREATE_2); + * \param install_signal_handler if true, then register a signal handler to disconnect from + * the robot on SIGINT or SIGTERM. + */ + Create(RobotModel model = RobotModel::CREATE_2, bool install_signal_handler = true); /** * \brief Attempts to establish serial connection to Create. @@ -119,8 +121,10 @@ namespace create { * \param baud rate to communicate with Create. Typically, * 115200 for Create 2 and 57600 for Create 1. * \param model type of robot. See RobotModel to determine the value for your robot. + * \param install_signal_handler if true, then register a signal handler to disconnect from + * the robot on SIGINT or SIGTERM. */ - Create(const std::string& port, const int& baud, RobotModel model = RobotModel::CREATE_2); + Create(const std::string& port, const int& baud, RobotModel model = RobotModel::CREATE_2, bool install_signal_handler = true); /** * \brief Attempts to disconnect from serial. diff --git a/include/create/serial.h b/include/create/serial.h index 5280040..05ac648 100644 --- a/include/create/serial.h +++ b/include/create/serial.h @@ -86,7 +86,7 @@ namespace create { void notifyDataReady(); public: - Serial(std::shared_ptr data); + Serial(std::shared_ptr data, bool install_signal_handler); ~Serial(); bool connect(const std::string& port, const int& baud = 115200, std::function cb = 0); void disconnect(); diff --git a/include/create/serial_query.h b/include/create/serial_query.h index a10b34e..b6b372b 100644 --- a/include/create/serial_query.h +++ b/include/create/serial_query.h @@ -67,7 +67,7 @@ namespace create { void processByte(uint8_t byteRead); public: - SerialQuery(std::shared_ptr data); + SerialQuery(std::shared_ptr data, bool install_signal_handler = true); }; } // namespace create diff --git a/include/create/serial_stream.h b/include/create/serial_stream.h index 07d4c05..2f21892 100644 --- a/include/create/serial_stream.h +++ b/include/create/serial_stream.h @@ -69,7 +69,10 @@ namespace create { void processByte(uint8_t byteRead); public: - SerialStream(std::shared_ptr data, const uint8_t& header = create::util::STREAM_HEADER); + SerialStream( + std::shared_ptr data, + const uint8_t& header = create::util::STREAM_HEADER, + bool install_signal_handler = true); }; } // namespace create diff --git a/src/create.cpp b/src/create.cpp index 6718d2e..b87443d 100644 --- a/src/create.cpp +++ b/src/create.cpp @@ -14,7 +14,7 @@ namespace create { namespace ublas = boost::numeric::ublas; - void Create::init() { + void Create::init(bool install_signal_handler) { mainMotorPower = 0; sideMotorPower = 0; vacuumMotorPower = 0; @@ -44,18 +44,21 @@ namespace create { dtHistoryLength = 100; data = std::shared_ptr(new Data(model.getVersion())); if (model.getVersion() == V_1) { - serial = std::make_shared(data); + serial = std::make_shared(data, install_signal_handler); } else { - serial = std::make_shared(data); + serial = std::make_shared( + data, create::util::STREAM_HEADER, install_signal_handler); } } - Create::Create(RobotModel m) : model(m) { - init(); + Create::Create(RobotModel m, bool install_signal_handler) : model(m) { + init(install_signal_handler); } - Create::Create(const std::string& dev, const int& baud, RobotModel m) : model(m) { - init(); + Create::Create(const std::string& dev, const int& baud, RobotModel m, bool install_signal_handler) + : model(m) + { + init(install_signal_handler); serial->connect(dev, baud); } diff --git a/src/serial.cpp b/src/serial.cpp index 2a87a8a..97c6085 100644 --- a/src/serial.cpp +++ b/src/serial.cpp @@ -7,14 +7,19 @@ namespace create { - Serial::Serial(std::shared_ptr d) : - signals(io, SIGINT, SIGTERM), + Serial::Serial(std::shared_ptr d, bool install_signal_handler) : + signals(io), port(io), dataReady(false), isReading(false), data(d), corruptPackets(0), - totalPackets(0) { + totalPackets(0) + { + if (install_signal_handler) { + signals.add(SIGINT); + signals.add(SIGTERM); + } } Serial::~Serial() { diff --git a/src/serial_query.cpp b/src/serial_query.cpp index 2d3997b..2f069db 100644 --- a/src/serial_query.cpp +++ b/src/serial_query.cpp @@ -8,7 +8,8 @@ namespace create { - SerialQuery::SerialQuery(std::shared_ptr d) : Serial(d), + SerialQuery::SerialQuery(std::shared_ptr d, bool install_signal_handler) + : Serial(d, install_signal_handler), streamRecoveryTimer(io), packetID(ID_BUMP_WHEELDROP), packetByte(0), diff --git a/src/serial_stream.cpp b/src/serial_stream.cpp index b22a07e..96cd123 100644 --- a/src/serial_stream.cpp +++ b/src/serial_stream.cpp @@ -6,7 +6,7 @@ namespace create { - SerialStream::SerialStream(std::shared_ptr d, const uint8_t& header) : Serial(d), readState(READ_HEADER), headerByte(header) { + SerialStream::SerialStream(std::shared_ptr d, const uint8_t& header, bool install_signal_handler) : Serial(d, install_signal_handler), readState(READ_HEADER), headerByte(header) { } bool SerialStream::startSensorStream() { From 4304155f76592638017ab40fb5d662cbc31029b3 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 24 Feb 2022 14:05:07 -0800 Subject: [PATCH 072/108] Update links to serial protocol documentation --- README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 4dd559a..cbb6a65 100644 --- a/README.md +++ b/README.md @@ -4,9 +4,9 @@ C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com * [Code API](http://docs.ros.org/kinetic/api/libcreate/html/index.html) * Protocol documentation: - - [`V_1`](https://drive.google.com/open?id=0B9O4b91VYXMdUHlqNklDU09NU0k) (Roomba 400 series ) - - [`V_2`](https://drive.google.com/open?id=0B9O4b91VYXMdMmFPMVNDUEZ6d0U) (Create 1, Roomba 500 series) - - [`V_3`](https://drive.google.com/open?id=0B9O4b91VYXMdSVk4amw1N09mQ3c) (Create 2, Roomba 600-800 series) + - [`V_1`](https://drive.google.com/file/d/0B9O4b91VYXMdUHlqNklDU09NU0k) (Roomba 400 series ) + - [`V_2`](https://drive.google.com/file/d/0B9O4b91VYXMdMmFPMVNDUEZ6d0U) (Create 1, Roomba 500 series) + - [`V_3`](https://drive.google.com/file/d/0B9O4b91VYXMdSVk4amw1N09mQ3c) (Create 2, Roomba 600-800 series) * Author: [Jacob Perron](http://jacobperron.ca) ([Autonomy Lab](http://autonomylab.org), [Simon Fraser University](http://www.sfu.ca)) * Contributors: [Mani Monajjemi](http:mani.im), [Ben Wolsieffer](https://github.com/lopsided98) From 35270f58cf83562c003e9450240910e7099f7a21 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 24 Jan 2022 18:16:31 -0800 Subject: [PATCH 073/108] Update workflow Run CI on all PRs and not commits to default branch. Signed-off-by: Jacob Perron --- .github/workflows/ci.yaml | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 6653702..77852b5 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -1,12 +1,9 @@ name: Build and test + on: - # Run for any commit in origin repository push: - # And pull requests from forks + branches: ['master'] pull_request: - branches: - # This avoids running the job twice for PRs from origin repository - - '**:**' env: BUILD_TYPE: Release From db575de22a35ffb1c6410d51d36f8afa66ba85a1 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 24 Jan 2022 18:18:03 -0800 Subject: [PATCH 074/108] Remove trailing whitespace Signed-off-by: Jacob Perron --- include/create/create.h | 8 ++++---- src/create.cpp | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/include/create/create.h b/include/create/create.h index 0652861..8cc1d8c 100644 --- a/include/create/create.h +++ b/include/create/create.h @@ -286,15 +286,15 @@ namespace create { /** * \brief Set the four 7-segment display digits from left to right. * - * \todo This function is not yet implemented refer to https://github.com/AutonomyLab/libcreate/issues/7 + * \todo This function is not yet implemented refer to https://github.com/AutonomyLab/libcreate/issues/7 * \param segments to enable (true) or disable (false). * The size of segments should be less than 29. * The ordering of segments is left to right, top to bottom for each digit: * *
-                 0           7             14            21 
-               |‾‾‾|       |‾‾‾|         |‾‾‾|         |‾‾‾|  
-             1 |___| 2   8 |___| 9    15 |___| 16   22 |___| 23 
+                 0           7             14            21
+               |‾‾‾|       |‾‾‾|         |‾‾‾|         |‾‾‾|
+             1 |___| 2   8 |___| 9    15 |___| 16   22 |___| 23
                | 3 |       | 10|         | 17|         | 24|
              4 |___| 5   11|___| 12   18 |___| 19   25 |___| 26
                  6           13            20            27
diff --git a/src/create.cpp b/src/create.cpp
index b87443d..e59a8a0 100644
--- a/src/create.cpp
+++ b/src/create.cpp
@@ -1063,7 +1063,7 @@ namespace create {
     }
   }
 
-  bool Create::isSideBrushOvercurrent() const { 
+  bool Create::isSideBrushOvercurrent() const {
     if (data->isValidPacketID(ID_OVERCURRENTS)) {
       return (GET_DATA(ID_OVERCURRENTS) & 0x01) != 0;
     }
@@ -1073,7 +1073,7 @@ namespace create {
     }
   }
 
-  bool Create::isMainBrushOvercurrent() const { 
+  bool Create::isMainBrushOvercurrent() const {
     if (data->isValidPacketID(ID_OVERCURRENTS)) {
       return (GET_DATA(ID_OVERCURRENTS) & 0x04) != 0;
     }
@@ -1082,8 +1082,8 @@ namespace create {
       return false;
     }
   }
-  
-  bool Create::isWheelOvercurrent() const { 
+
+  bool Create::isWheelOvercurrent() const {
     if (data->isValidPacketID(ID_OVERCURRENTS)) {
       return (GET_DATA(ID_OVERCURRENTS) & 0x18) != 0;
     }

From e99939c785c33dc5f2e6efc2c55756bf9b4e9da6 Mon Sep 17 00:00:00 2001
From: Josh Gadeken 
Date: Wed, 6 Apr 2022 18:21:35 -0600
Subject: [PATCH 075/108] Mode report workaround (#67)

* Add option for OI mode reporting bug workaround

https://github.com/AutonomyLab/create_robot/issues/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
---
 README.md               |  4 +++-
 include/create/create.h | 18 ++++++++++++++++++
 src/create.cpp          | 16 +++++++++++++++-
 3 files changed, 36 insertions(+), 2 deletions(-)

diff --git a/README.md b/README.md
index cbb6a65..2d85f07 100644
--- a/README.md
+++ b/README.md
@@ -8,7 +8,7 @@ C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com
   - [`V_2`](https://drive.google.com/file/d/0B9O4b91VYXMdMmFPMVNDUEZ6d0U) (Create 1, Roomba 500 series)
   - [`V_3`](https://drive.google.com/file/d/0B9O4b91VYXMdSVk4amw1N09mQ3c) (Create 2, Roomba 600-800 series)
 * Author: [Jacob Perron](http://jacobperron.ca) ([Autonomy Lab](http://autonomylab.org), [Simon Fraser University](http://www.sfu.ca))
-* Contributors: [Mani Monajjemi](http:mani.im), [Ben Wolsieffer](https://github.com/lopsided98)
+* Contributors: [Mani Monajjemi](http:mani.im), [Ben Wolsieffer](https://github.com/lopsided98), [Josh Gadeken](https://github.com/process1183)
 
 ## Build Status ##
 
@@ -72,3 +72,5 @@ To run unit tests, execute the following in the build directory:
 
 * _Clock_ and _Schedule_ buttons are not functional. This is a known bug related to the firmware.
 * Inaccurate odometry angle for Create 1 ([#22](https://github.com/AutonomyLab/libcreate/issues/22))
+* Some 600 series models incorrectly report the OI Mode in their sensor stream ([create_robot #64](https://github.com/AutonomyLab/create_robot/issues/64))
+  - To enable or disable the OI Mode reporting workaround, pass `true` or `false` to `setModeReportWorkaround()`
diff --git a/include/create/create.h b/include/create/create.h
index 8cc1d8c..619205f 100644
--- a/include/create/create.h
+++ b/include/create/create.h
@@ -98,6 +98,10 @@ namespace create {
       void onData();
       bool updateLEDs();
 
+      // Flag to enable/disable the workaround for some 6xx incorrectly reporting OI mode
+      // https://github.com/AutonomyLab/create_robot/issues/64
+      bool modeReportWorkaround;
+
     protected:
       std::shared_ptr data;
       std::shared_ptr serial;
@@ -673,6 +677,20 @@ namespace create {
        * \return total number of serial packets.
        */
       uint64_t getTotalPackets() const;
+
+      /**
+       * \brief Enable or disable the mode reporting workaround.
+       * Some Roomba 6xx robots incorrectly report the OI mode in their sensor streams. Enabling the workaround
+       * will cause libcreate to decrement the reported OI mode in the sensor stream by 1.
+       * See https://github.com/AutonomyLab/create_robot/issues/64
+       */
+      void setModeReportWorkaround(const bool& enable);
+
+      /**
+       * \return true if the mode reporting workaround is enabled, false otherwise.
+       */
+      bool getModeReportWorkaround() const;
+
   };  // end Create class
 
 }  // namespace create
diff --git a/src/create.cpp b/src/create.cpp
index e59a8a0..21f71be 100644
--- a/src/create.cpp
+++ b/src/create.cpp
@@ -42,6 +42,7 @@ namespace create {
     requestedLeftVel = 0;
     requestedRightVel = 0;
     dtHistoryLength = 100;
+    modeReportWorkaround = false;
     data = std::shared_ptr(new Data(model.getVersion()));
     if (model.getVersion() == V_1) {
       serial = std::make_shared(data, install_signal_handler);
@@ -1117,10 +1118,23 @@ namespace create {
     return requestedRightVel;
   }
 
+  void Create::setModeReportWorkaround(const bool& enable) {
+    modeReportWorkaround = enable;
+  }
+
+  bool Create::getModeReportWorkaround() const {
+    return modeReportWorkaround;
+  }
+
   create::CreateMode Create::getMode() {
     if (data->isValidPacketID(ID_OI_MODE)) {
-      mode = (create::CreateMode) GET_DATA(ID_OI_MODE);
+      if (modeReportWorkaround) {
+        mode = (create::CreateMode) (GET_DATA(ID_OI_MODE) - 1);
+      } else {
+        mode = (create::CreateMode) GET_DATA(ID_OI_MODE);
+      }
     }
+
     return mode;
   }
 

From c694bd30d33a12a533e4de2be1a8e0140625a377 Mon Sep 17 00:00:00 2001
From: Jacob Perron 
Date: Wed, 6 Apr 2022 17:27:15 -0700
Subject: [PATCH 076/108] 3.0.0

---
 CHANGELOG.rst  | 16 ++++++++++++++++
 CMakeLists.txt |  2 +-
 package.xml    |  2 +-
 3 files changed, 18 insertions(+), 2 deletions(-)

diff --git a/CHANGELOG.rst b/CHANGELOG.rst
index 66c4dd6..77ce1e7 100644
--- a/CHANGELOG.rst
+++ b/CHANGELOG.rst
@@ -2,6 +2,22 @@
 Changelog for package libcreate
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+3.0.0 (2022-04-06)
+------------------
+* Add option to workaround bug where firmware reports unexpected OI mode (`#67 `_)
+* Update links to serial protocol documentation
+* Add option to disable signal handlers (`#65 `_)
+* Fix 'maybe-uninitialized' warnings
+* Remove travis.yml
+* Add GitHub workflow for CI
+* Fix motor setting (`#62 `_)
+* Use average dt values for velocity calculation (`#60 `_)
+* Use steady clock for computing velocity (`#59 `_)
+* Replace boost features with C++11 equivalents (`#58 `_)
+* Implement methods for getting overcurrent status (`#57 `_)
+* Use OC_MOTORS instead of OC_MOTORS_PWM on V_1 models (`#55 `_)
+* Contributors: Daniel Smith, Jacob Perron, Josh Gadeken, Stefan Krupop, tim-fan
+
 2.0.0 (2019-09-02)
 ------------------
 * Cleanup examples
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 97cf437..553f469 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -10,7 +10,7 @@ project(libcreate)
 
 add_compile_options(-Wall -Wextra -Wpedantic)
 
-set(PACKAGE_VERSION 2.0.0)
+set(PACKAGE_VERSION 3.0.0)
 
 option(LIBCREATE_BUILD_TESTS "Enable the build of tests." ON)
 
diff --git a/package.xml b/package.xml
index aa633ad..9704efe 100644
--- a/package.xml
+++ b/package.xml
@@ -1,7 +1,7 @@
 
 
   libcreate
-  2.0.0
+  3.0.0
   C++ library for interfacing with iRobot's Create 1 and Create 2
 
   Jacob Perron

From de253b6e81a8409087132ac5c5fe1d2973543d13 Mon Sep 17 00:00:00 2001
From: Swapnil Patel 
Date: Mon, 27 Jun 2022 22:38:18 -0400
Subject: [PATCH 077/108] catch boost exceptions in Serial.h

---
 include/create/serial.h |  2 ++
 src/serial.cpp          | 64 ++++++++++++++++++++++++++++++-----------
 2 files changed, 50 insertions(+), 16 deletions(-)

diff --git a/include/create/serial.h b/include/create/serial.h
index 05ac648..ccfdaea 100644
--- a/include/create/serial.h
+++ b/include/create/serial.h
@@ -71,6 +71,8 @@ namespace create {
       // Start and stop reading data from Create
       bool startReading();
       void stopReading();
+      bool openPort(const std::string& portName, const int& baud);
+      bool closePort();
 
     protected:
       std::shared_ptr data;
diff --git a/src/serial.cpp b/src/serial.cpp
index 97c6085..6617e50 100644
--- a/src/serial.cpp
+++ b/src/serial.cpp
@@ -40,26 +40,26 @@ namespace create {
 
   bool Serial::connect(const std::string& portName, const int& baud, std::function cb) {
     using namespace boost::asio;
-    port.open(portName);
-    port.set_option(serial_port::baud_rate(baud));
-    port.set_option(serial_port::character_size(8));
-    port.set_option(serial_port::parity(serial_port::parity::none));
-    port.set_option(serial_port::stop_bits(serial_port::stop_bits::one));
-    port.set_option(serial_port::flow_control(serial_port::flow_control::none));
+    if (!openPort(portName, baud)) {
+      return false;
+    }
 
     signals.async_wait(std::bind(&Serial::signalHandler, this, std::placeholders::_1, std::placeholders::_2));
 
     usleep(1000000);
 
-    if (port.is_open()) {
-      callback = cb;
-      bool startReadSuccess = startReading();
-      if (!startReadSuccess) {
-        port.close();
-      }
-      return startReadSuccess;
+    if (!port.is_open()) {
+      return false;
     }
-    return false;
+
+    callback = cb;
+    bool startReadSuccess = startReading();
+    if (!startReadSuccess) {
+      closePort();
+      return false;
+    }
+
+    return true;
   }
 
   void Serial::disconnect() {
@@ -76,6 +76,33 @@ namespace create {
     }
   }
 
+  bool Serial::openPort(const std::string& portName, const int& baud) {
+    using namespace boost::asio;
+    try {
+      port.open(portName);
+      port.set_option(serial_port::baud_rate(baud));
+      port.set_option(serial_port::character_size(8));
+      port.set_option(serial_port::parity(serial_port::parity::none));
+      port.set_option(serial_port::stop_bits(serial_port::stop_bits::one));
+      port.set_option(serial_port::flow_control(serial_port::flow_control::none));
+    } catch (const boost::system::system_error& /*e*/) {
+      CERR("[create::Serial] ", "failed to open port: " << portName);
+      return false;
+    }
+    return true;
+  }
+
+  bool Serial::closePort() {
+    using namespace boost::asio;
+    try {
+      port.close();
+    } catch (const boost::system::system_error& /*e*/) {
+      CERR("[create::Serial] ", "failed to close port");
+      return false;
+    }
+    return true;
+  }
+
   bool Serial::startReading() {
     if (!connected()) return false;
 
@@ -186,8 +213,13 @@ namespace create {
       CERR("[create::Serial] ", "send failed, not connected.");
       return false;
     }
-    // TODO: catch boost exceptions
-    boost::asio::write(port, boost::asio::buffer(bytes, numBytes));
+    
+    try {
+      boost::asio::write(port, boost::asio::buffer(bytes, numBytes));
+    } catch (const boost::system::system_error & e) {
+      CERR("[create::Serial] ", "failed to write bytes to port");
+      return false;
+    }
     return true;
   }
 

From d75d41c63843581cfd113fd8ceac976d65bc06b4 Mon Sep 17 00:00:00 2001
From: Swapnil Patel 
Date: Mon, 27 Jun 2022 22:42:24 -0400
Subject: [PATCH 078/108] address warnings and errors

---
 include/create/serial_query.h  | 1 +
 include/create/serial_stream.h | 1 +
 src/create.cpp                 | 6 +++---
 3 files changed, 5 insertions(+), 3 deletions(-)

diff --git a/include/create/serial_query.h b/include/create/serial_query.h
index b6b372b..ebd876a 100644
--- a/include/create/serial_query.h
+++ b/include/create/serial_query.h
@@ -68,6 +68,7 @@ namespace create {
 
     public:
       SerialQuery(std::shared_ptr data, bool install_signal_handler = true);
+      virtual ~SerialQuery() = default;
   };
 }  // namespace create
 
diff --git a/include/create/serial_stream.h b/include/create/serial_stream.h
index 2f21892..eeb2cb6 100644
--- a/include/create/serial_stream.h
+++ b/include/create/serial_stream.h
@@ -73,6 +73,7 @@ namespace create {
         std::shared_ptr data,
         const uint8_t& header = create::util::STREAM_HEADER,
         bool install_signal_handler = true);
+      virtual ~SerialStream() = default;
 
   };
 }  // namespace create
diff --git a/src/create.cpp b/src/create.cpp
index 21f71be..0517b4a 100644
--- a/src/create.cpp
+++ b/src/create.cpp
@@ -160,10 +160,10 @@ namespace create {
       prevTicksRight = totalTicksRight;
 
       // Handle wrap around
-      if (fabs(ticksLeft) > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
+      if (std::abs(ticksLeft) > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
         ticksLeft = (ticksLeft % util::V_3_MAX_ENCODER_TICKS) + 1;
       }
-      if (fabs(ticksRight) > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
+      if (std::abs(ticksRight) > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
         ticksRight = (ticksRight % util::V_3_MAX_ENCODER_TICKS) + 1;
       }
 
@@ -373,7 +373,7 @@ namespace create {
         min > 59)
       return false;
 
-    uint8_t cmd[4] = { OC_DATE, day, hour, min };
+    uint8_t cmd[4] = { OC_DATE, static_cast(day), hour, min };
     return serial->send(cmd, 4);
   }
 

From ca6e477d25de6ef553c8b5372b479b440440d941 Mon Sep 17 00:00:00 2001
From: Jacob Perron 
Date: Tue, 9 May 2023 14:50:03 -0700
Subject: [PATCH 079/108] 3.1.0

---
 CHANGELOG.rst | 6 ++++++
 package.xml   | 2 +-
 2 files changed, 7 insertions(+), 1 deletion(-)

diff --git a/CHANGELOG.rst b/CHANGELOG.rst
index 77ce1e7..0af0f5b 100644
--- a/CHANGELOG.rst
+++ b/CHANGELOG.rst
@@ -2,6 +2,12 @@
 Changelog for package libcreate
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+3.1.0 (2023-05-09)
+------------------
+* Address warnings and errors
+* Catch boost exceptions in Serial.h
+* Contributors: Swapnil Patel
+
 3.0.0 (2022-04-06)
 ------------------
 * Add option to workaround bug where firmware reports unexpected OI mode (`#67 `_)
diff --git a/package.xml b/package.xml
index 9704efe..85101b3 100644
--- a/package.xml
+++ b/package.xml
@@ -1,7 +1,7 @@
 
 
   libcreate
-  3.0.0
+  3.1.0
   C++ library for interfacing with iRobot's Create 1 and Create 2
 
   Jacob Perron

From 05e01c85a42af991b1072415e2601d03d76a2e9f Mon Sep 17 00:00:00 2001
From: Jacob Perron 
Date: Sun, 21 May 2023 16:54:35 -0700
Subject: [PATCH 080/108] Update CI workflow

Remove 18.04 since it is no longer supported by GitHub actions.
Add 22.04.

Signed-off-by: Jacob Perron 
---
 .github/workflows/ci.yaml | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml
index 77852b5..7fb7d18 100644
--- a/.github/workflows/ci.yaml
+++ b/.github/workflows/ci.yaml
@@ -13,7 +13,7 @@ jobs:
     runs-on: ${{ matrix.os }}
     strategy:
       matrix:
-        os: [ubuntu-18.04, ubuntu-20.04]
+        os: [ubuntu-20.04, ubuntu-22.04]
 
     steps:
     - name: Install dependencies

From a8e274be1559a5c921463629f57d5b6dfeed1583 Mon Sep 17 00:00:00 2001
From: Jacob Perron 
Date: Sun, 21 May 2023 16:59:38 -0700
Subject: [PATCH 081/108] Update README

Fix/remove broken or outdated links.

Signed-off-by: Jacob Perron 
---
 README.md | 10 +++++-----
 1 file changed, 5 insertions(+), 5 deletions(-)

diff --git a/README.md b/README.md
index 2d85f07..fa1232c 100644
--- a/README.md
+++ b/README.md
@@ -1,12 +1,12 @@
 # libcreate #
 
-C++ library for interfacing with iRobot's [Create 1 and 2](http://www.irobot.com/About-iRobot/STEM/Create-2.aspx) as well as most models of Roomba. [create_autonomy](http://wiki.ros.org/create_autonomy) is a [ROS](http://www.ros.org/) wrapper for this library.
+C++ library for interfacing with iRobot's Create 1 and 2 as well as most models of Roomba. [create_robot](http://wiki.ros.org/create_robot) is a [ROS](http://www.ros.org/) wrapper for this library.
 
-* [Code API](http://docs.ros.org/kinetic/api/libcreate/html/index.html)
+* [Code API](http://docs.ros.org/noetic/api/libcreate/html/index.html)
 * Protocol documentation:
-  - [`V_1`](https://drive.google.com/file/d/0B9O4b91VYXMdUHlqNklDU09NU0k) (Roomba 400 series )
-  - [`V_2`](https://drive.google.com/file/d/0B9O4b91VYXMdMmFPMVNDUEZ6d0U) (Create 1, Roomba 500 series)
-  - [`V_3`](https://drive.google.com/file/d/0B9O4b91VYXMdSVk4amw1N09mQ3c) (Create 2, Roomba 600-800 series)
+  - [`V_1`](https://drive.google.com/file/d/0B9O4b91VYXMdUHlqNklDU09NU0k/view?usp=sharing&resourcekey=0-KxMpRPBMsGAj7eSYC_9ewA) (Roomba 400 series )
+  - [`V_2`](https://drive.google.com/file/d/0B9O4b91VYXMdMmFPMVNDUEZ6d0U/view?usp=sharing&resourcekey=0-bqKH8xhtWdYtTik_LLWo9Q) (Create 1, Roomba 500 series)
+  - [`V_3`](https://drive.google.com/file/d/0B9O4b91VYXMdSVk4amw1N09mQ3c/view?usp=sharing&resourcekey=0-rKvug2IzC7nj4zV31EJtww) (Create 2, Roomba 600-800 series)
 * Author: [Jacob Perron](http://jacobperron.ca) ([Autonomy Lab](http://autonomylab.org), [Simon Fraser University](http://www.sfu.ca))
 * Contributors: [Mani Monajjemi](http:mani.im), [Ben Wolsieffer](https://github.com/lopsided98), [Josh Gadeken](https://github.com/process1183)
 

From fd2638114aa57cd743d5632ce983b7edd4461edb Mon Sep 17 00:00:00 2001
From: DuSack1220 
Date: Sat, 4 Feb 2023 17:03:31 +0100
Subject: [PATCH 082/108] added cliff sensor signals

---
 include/create/create.h | 20 ++++++++++++++++++++
 src/create.cpp          | 40 ++++++++++++++++++++++++++++++++++++++++
 src/data.cpp            |  4 ++++
 3 files changed, 64 insertions(+)

diff --git a/include/create/create.h b/include/create/create.h
index 619205f..80beee3 100644
--- a/include/create/create.h
+++ b/include/create/create.h
@@ -406,6 +406,26 @@ namespace create {
        */
       bool isCliffFrontRight() const;
 
+      /**
+       * \return true if the left sensor detects a cliff, false otherwise.
+       */
+      uint16_t getCliffSignalLeft() const;
+
+      /**
+       * \return true if the front left sensor detects a cliff, false otherwise.
+       */
+      uint16_t getCliffSignalFrontLeft() const;
+
+      /**
+       * \return true if the right sensor detects a cliff, false otherwise.
+       */
+      uint16_t getCliffSignalRight() const;
+
+      /**
+       * \return true if the front right sensor detects a cliff, false otherwise.
+       */
+      uint16_t getCliffSignalFrontRight() const;
+
       /**
        * \return true if there is a virtual wall signal is being received.
        */
diff --git a/src/create.cpp b/src/create.cpp
index 0517b4a..72dbd26 100644
--- a/src/create.cpp
+++ b/src/create.cpp
@@ -738,6 +738,46 @@ namespace create {
     }
   }
 
+  uint16_t Create::getCliffSignalLeft() const {
+    if (data->isValidPacketID(ID_CLIFF_LEFT)) {
+      return GET_DATA(ID_CLIFF_LEFT_SIGNAL);
+    }
+    else {
+      CERR("[create::Create] ", "Left cliff sensor signals not supported!");
+      return false;
+      }
+  }
+
+  uint16_t Create::getCliffSignalFrontLeft() const {
+    if (data->isValidPacketID(ID_CLIFF_FRONT_LEFT)) {
+      return GET_DATA(ID_CLIFF_FRONT_LEFT_SIGNAL);
+    }
+    else {
+      CERR("[create::Create] ", "Front left cliff sensor signals not supported!");
+      return false;
+    }
+  }
+
+  uint16_t Create::getCliffSignalRight() const {
+    if (data->isValidPacketID(ID_CLIFF_RIGHT)) {
+      return GET_DATA(ID_CLIFF_RIGHT_SIGNAL);
+    }
+    else {
+      CERR("[create::Create] ", "Rightt cliff sensor signals not supported!");
+      return false;
+    }
+  }
+
+  uint16_t Create::getCliffSignalFrontRight() const {
+    if (data->isValidPacketID(ID_CLIFF_FRONT_RIGHT)) {
+      return GET_DATA(ID_CLIFF_FRONT_RIGHT_SIGNAL);
+    }
+    else {
+      CERR("[create::Create] ", "Front right cliff sensor signals not supported!");
+      return false;
+    }
+  }
+
   bool Create::isVirtualWall() const {
     if (data->isValidPacketID(ID_VIRTUAL_WALL)) {
       return GET_DATA(ID_VIRTUAL_WALL);
diff --git a/src/data.cpp b/src/data.cpp
index 5e8acce..be20717 100644
--- a/src/data.cpp
+++ b/src/data.cpp
@@ -16,6 +16,10 @@ namespace create {
     ADD_PACKET(ID_CLIFF_FRONT_LEFT, 1, "cliff_front_left", V_ALL);
     ADD_PACKET(ID_CLIFF_FRONT_RIGHT, 1, "cliff_front_right", V_ALL);
     ADD_PACKET(ID_CLIFF_RIGHT, 1, "cliff_right", V_ALL);
+    ADD_PACKET(ID_CLIFF_LEFT_SIGNAL, 2, "cliff_left_signal", V_3);
+    ADD_PACKET(ID_CLIFF_FRONT_LEFT_SIGNAL, 2, "cliff_front_left_signal", V_3);
+    ADD_PACKET(ID_CLIFF_FRONT_RIGHT_SIGNAL, 2, "cliff_front_right_signal", V_3);
+    ADD_PACKET(ID_CLIFF_RIGHT_SIGNAL, 2, "cliff_right_signal", V_3);
     ADD_PACKET(ID_VIRTUAL_WALL, 1, "virtual_wall", V_ALL);
     ADD_PACKET(ID_OVERCURRENTS, 1, "overcurrents", V_ALL);
     ADD_PACKET(ID_DIRT_DETECT_LEFT, 1, "dirt_detect_left", V_ALL);

From 1bc2d768f7a1232fc31511d23910f3dfc45f1a63 Mon Sep 17 00:00:00 2001
From: DuSack1220 
Date: Mon, 13 Mar 2023 23:49:10 +0100
Subject: [PATCH 083/108] fixed encoder overflow

---
 src/create.cpp | 18 ++++++++++++------
 1 file changed, 12 insertions(+), 6 deletions(-)

diff --git a/src/create.cpp b/src/create.cpp
index 72dbd26..f6bd595 100644
--- a/src/create.cpp
+++ b/src/create.cpp
@@ -156,17 +156,23 @@ namespace create {
       // Compute ticks since last update
       int ticksLeft = totalTicksLeft - prevTicksLeft;
       int ticksRight = totalTicksRight - prevTicksRight;
-      prevTicksLeft = totalTicksLeft;
-      prevTicksRight = totalTicksRight;
 
       // Handle wrap around
-      if (std::abs(ticksLeft) > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
-        ticksLeft = (ticksLeft % util::V_3_MAX_ENCODER_TICKS) + 1;
+      if (ticksLeft > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
+        ticksLeft = 2 * util::V_3_MAX_ENCODER_TICKS + prevTicksLeft - ticksLeft;
+      } else if (ticksLeft < 0.9 * -util::V_3_MAX_ENCODER_TICKS) {
+        ticksLeft = util::V_3_MAX_ENCODER_TICKS - prevTicksLeft + util::V_3_MAX_ENCODER_TICKS + ticksLeft;
       }
-      if (std::abs(ticksRight) > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
-        ticksRight = (ticksRight % util::V_3_MAX_ENCODER_TICKS) + 1;
+
+      if (ticksRight > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
+        ticksRight = util::V_3_MAX_ENCODER_TICKS + prevTicksRight + util::V_3_MAX_ENCODER_TICKS - ticksRight;
+      } else if (ticksLeft < 0.9 * -util::V_3_MAX_ENCODER_TICKS) {
+        ticksRight = util::V_3_MAX_ENCODER_TICKS - prevTicksRight + util::V_3_MAX_ENCODER_TICKS + ticksRight;
       }
 
+      prevTicksLeft = totalTicksLeft;
+      prevTicksRight = totalTicksRight;
+
       // Compute distance travelled by each wheel
       leftWheelDist = (ticksLeft / util::V_3_TICKS_PER_REV)
           * model.getWheelDiameter() * util::PI;

From 2c58777e45a431e88c3e01854e369187389641f2 Mon Sep 17 00:00:00 2001
From: Bernhard Klauninger 
Date: Wed, 15 Mar 2023 13:14:06 +0100
Subject: [PATCH 084/108] Actually fixed wrap around

---
 src/create.cpp | 22 +++++++++++-----------
 1 file changed, 11 insertions(+), 11 deletions(-)

diff --git a/src/create.cpp b/src/create.cpp
index f6bd595..87c12c9 100644
--- a/src/create.cpp
+++ b/src/create.cpp
@@ -157,18 +157,18 @@ namespace create {
       int ticksLeft = totalTicksLeft - prevTicksLeft;
       int ticksRight = totalTicksRight - prevTicksRight;
 
-      // Handle wrap around
-      if (ticksLeft > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
-        ticksLeft = 2 * util::V_3_MAX_ENCODER_TICKS + prevTicksLeft - ticksLeft;
-      } else if (ticksLeft < 0.9 * -util::V_3_MAX_ENCODER_TICKS) {
-        ticksLeft = util::V_3_MAX_ENCODER_TICKS - prevTicksLeft + util::V_3_MAX_ENCODER_TICKS + ticksLeft;
-      }
+    // Handle wrap around
+    if (ticksLeft > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
+        ticksLeft -= util::V_3_MAX_ENCODER_TICKS;
+    } else if (ticksLeft < -0.9 * util::V_3_MAX_ENCODER_TICKS) {
+        ticksLeft += util::V_3_MAX_ENCODER_TICKS;
+    }
 
-      if (ticksRight > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
-        ticksRight = util::V_3_MAX_ENCODER_TICKS + prevTicksRight + util::V_3_MAX_ENCODER_TICKS - ticksRight;
-      } else if (ticksLeft < 0.9 * -util::V_3_MAX_ENCODER_TICKS) {
-        ticksRight = util::V_3_MAX_ENCODER_TICKS - prevTicksRight + util::V_3_MAX_ENCODER_TICKS + ticksRight;
-      }
+    if (ticksRight > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
+        ticksRight -= util::V_3_MAX_ENCODER_TICKS;
+    } else if (ticksRight < -0.9 * util::V_3_MAX_ENCODER_TICKS) {
+        ticksRight += util::V_3_MAX_ENCODER_TICKS;
+    }
 
       prevTicksLeft = totalTicksLeft;
       prevTicksRight = totalTicksRight;

From 7ade48545ed27d3beb6b7e823d75386b3cfc70f5 Mon Sep 17 00:00:00 2001
From: DuSack1220 
Date: Wed, 15 Mar 2023 15:28:46 +0100
Subject: [PATCH 085/108] fixed cliff signal documentation

---
 include/create/create.h | 8 ++++----
 1 file changed, 4 insertions(+), 4 deletions(-)

diff --git a/include/create/create.h b/include/create/create.h
index 80beee3..512d264 100644
--- a/include/create/create.h
+++ b/include/create/create.h
@@ -407,22 +407,22 @@ namespace create {
       bool isCliffFrontRight() const;
 
       /**
-       * \return true if the left sensor detects a cliff, false otherwise.
+       * \return the IR value of the left cliff sensor.
        */
       uint16_t getCliffSignalLeft() const;
 
       /**
-       * \return true if the front left sensor detects a cliff, false otherwise.
+       * \return the IR value of the front left cliff sensor.
        */
       uint16_t getCliffSignalFrontLeft() const;
 
       /**
-       * \return true if the right sensor detects a cliff, false otherwise.
+       * \return the IR value of the right cliff sensor.
        */
       uint16_t getCliffSignalRight() const;
 
       /**
-       * \return true if the front right sensor detects a cliff, false otherwise.
+       * \return the IR value of the front right cliff sensor.
        */
       uint16_t getCliffSignalFrontRight() const;
 

From d3a714cc51a68c86cc5aca1e5c51f4a10fecefe5 Mon Sep 17 00:00:00 2001
From: Joel Klimont 
Date: Fri, 3 May 2024 00:17:37 +0200
Subject: [PATCH 086/108] changed install dir

---
 CMakeLists.txt | 2 ++
 1 file changed, 2 insertions(+)

diff --git a/CMakeLists.txt b/CMakeLists.txt
index 553f469..4fb7345 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -84,6 +84,8 @@ endforeach()
 # Configuration #
 #################
 
+set(CMAKE_INSTALL_PREFIX "/usr/")
+
 # Install directories layout:
 #   * /lib/
 #   * /bin/

From aaa7b5076ee6175512f8be2ac9fc107118bf50da Mon Sep 17 00:00:00 2001
From: Bernhard Klauninger 
Date: Wed, 3 Jul 2024 16:13:33 +0200
Subject: [PATCH 087/108] Implemented Create reset method

---
 CMakeLists.txt          | 2 +-
 include/create/create.h | 5 +++++
 src/create.cpp          | 9 +++++++++
 3 files changed, 15 insertions(+), 1 deletion(-)

diff --git a/CMakeLists.txt b/CMakeLists.txt
index 4fb7345..ce7beb2 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -84,7 +84,7 @@ endforeach()
 # Configuration #
 #################
 
-set(CMAKE_INSTALL_PREFIX "/usr/")
+# set(CMAKE_INSTALL_PREFIX "/usr/") // complib needs  this, riplib doesn't
 
 # Install directories layout:
 #   * /lib/
diff --git a/include/create/create.h b/include/create/create.h
index 512d264..186192e 100644
--- a/include/create/create.h
+++ b/include/create/create.h
@@ -135,6 +135,11 @@ namespace create {
        */
       ~Create();
 
+      /**
+       * \brief Resets the create as if the battery was removed and reinserted.
+       */
+      void reset();
+
       /**
        * \brief Make a serial connection to Create.
        *
diff --git a/src/create.cpp b/src/create.cpp
index 87c12c9..75f28c5 100644
--- a/src/create.cpp
+++ b/src/create.cpp
@@ -67,6 +67,15 @@ namespace create {
     disconnect();
   }
 
+  void Create::reset() {
+    if (!connected()) {
+      CERR("[create::Serial] ", "send failed, not connected.");
+      return;
+    }
+    serial->sendOpcode(OC_START);
+    serial->sendOpcode(OC_RESET);
+  }
+
   Create::Matrix Create::addMatrices(const Matrix &A, const Matrix &B) const {
     size_t rows = A.size1();
     size_t cols = A.size2();

From 8b5167b3192bfb7b01206f441a1b8e62062df2ec Mon Sep 17 00:00:00 2001
From: Konstantin Lampalzer 
Date: Sun, 22 Sep 2024 18:13:22 +0200
Subject: [PATCH 088/108] fix tests for new cliff packets, add string to
 packet.h

---
 include/create/packet.h |  1 +
 tests/test_data.cpp     | 12 ++++++------
 2 files changed, 7 insertions(+), 6 deletions(-)

diff --git a/include/create/packet.h b/include/create/packet.h
index d1e7928..60ff0f2 100644
--- a/include/create/packet.h
+++ b/include/create/packet.h
@@ -32,6 +32,7 @@ POSSIBILITY OF SUCH DAMAGE.
 #define CREATE_PACKET_H
 
 #include 
+#include 
 
 namespace create {
   class Packet {
diff --git a/tests/test_data.cpp b/tests/test_data.cpp
index e9752a0..e347fb1 100644
--- a/tests/test_data.cpp
+++ b/tests/test_data.cpp
@@ -65,11 +65,11 @@ TEST(DataTest, GetNumPackets)
 
   create::Data data_v_3(create::V_3);
   // Number exclusive to V_3 = 13
-  // 17 + 13 = 30
-  EXPECT_EQ(static_cast(data_v_3.getNumPackets()), 30);
+  // 17 + 17 = 34
+  EXPECT_EQ(static_cast(data_v_3.getNumPackets()), 34);
 
   create::Data data_v_all(create::V_ALL);
-  EXPECT_EQ(static_cast(data_v_all.getNumPackets()), 33);
+  EXPECT_EQ(static_cast(data_v_all.getNumPackets()), 37);
 }
 
 TEST(DataTest, GetPacket)
@@ -108,7 +108,7 @@ TEST(DataTest, GetPacketIDs)
   create::Data data_v_3(create::V_3);
   const std::vector packet_ids = data_v_3.getPacketIDs();
   // Vector should have same length as reported by getNumPackets()
-  ASSERT_EQ(static_cast(packet_ids.size()), 30);
+  ASSERT_EQ(static_cast(packet_ids.size()), 34);
 
   // Vector should contain ID_LEFT_ENC
   bool found = false;
@@ -133,9 +133,9 @@ TEST(DataTest, GetTotalDataBytes)
   create::Data data_v_2(create::V_2);
   EXPECT_EQ(static_cast(data_v_2.getTotalDataBytes()), 26);
 
-  // V_3 has an additional 21 bytes
+  // V_3 has an additional 29 bytes
   create::Data data_v_3(create::V_3);
-  EXPECT_EQ(static_cast(data_v_3.getTotalDataBytes()), 42);
+  EXPECT_EQ(static_cast(data_v_3.getTotalDataBytes()), 50);
 }
 
 TEST(DataTest, IsValidPacketID)

From 7ae7155f25c484d9c328115a60cd992887b99ab6 Mon Sep 17 00:00:00 2001
From: Konstantin Lampalzer 
Date: Sun, 22 Sep 2024 18:29:51 +0200
Subject: [PATCH 089/108] ci: add Packing cmake and dockerfile to run packing

---
 .dockerignore       |  2 ++
 CMakeLists.txt      |  9 +++++++-
 ci/Dockerfile       | 17 +++++++++++++++
 cmake/Packing.cmake | 50 +++++++++++++++++++++++++++++++++++++++++++++
 package.sh          |  0
 5 files changed, 77 insertions(+), 1 deletion(-)
 create mode 100644 .dockerignore
 create mode 100644 ci/Dockerfile
 create mode 100644 cmake/Packing.cmake
 create mode 100755 package.sh

diff --git a/.dockerignore b/.dockerignore
new file mode 100644
index 0000000..7846b39
--- /dev/null
+++ b/.dockerignore
@@ -0,0 +1,2 @@
+.github
+ci
\ No newline at end of file
diff --git a/CMakeLists.txt b/CMakeLists.txt
index ce7beb2..2d37b18 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -5,7 +5,7 @@
 #    target_link_libraries(... ${libcreate_LIBRARIES})
 #
 
-cmake_minimum_required(VERSION 2.8.12)
+cmake_minimum_required(VERSION 3.28)
 project(libcreate)
 
 add_compile_options(-Wall -Wextra -Wpedantic)
@@ -203,3 +203,10 @@ if(LIBCREATE_BUILD_TESTS AND ${GTEST_FOUND})
 else()
   message("No GTest installation found. Skipping tests.")
 endif()
+
+#############
+# Packaging #
+#############
+
+set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake")
+include(Packing)
\ No newline at end of file
diff --git a/ci/Dockerfile b/ci/Dockerfile
new file mode 100644
index 0000000..c303ca9
--- /dev/null
+++ b/ci/Dockerfile
@@ -0,0 +1,17 @@
+FROM ubuntu:24.04
+
+RUN apt update && \
+    apt install -y \
+        build-essential cmake file \
+        libboost-system-dev libboost-thread-dev \
+        libgtest-dev googletest && \
+    rm -rf /var/lib/apt/lists/*
+
+WORKDIR /libcreate
+COPY . .
+
+WORKDIR /libcreate/build
+RUN cmake -B /libcreate/build -S /libcreate -DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_FLAGS="-Werror" && \
+    cmake --build /libcreate/build --config Release && \
+    ctest -C Release --output-on-failure && \
+    cpack --build /libcreate/build -G DEB
diff --git a/cmake/Packing.cmake b/cmake/Packing.cmake
new file mode 100644
index 0000000..93b1feb
--- /dev/null
+++ b/cmake/Packing.cmake
@@ -0,0 +1,50 @@
+# these are cache variables, so they could be overwritten with -D,
+set(CPACK_PACKAGE_NAME ${PROJECT_NAME}
+    CACHE STRING "The resulting package name"
+)
+# which is useful in case of packing only selected components instead of the whole thing
+set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "C++ library for interfacing with iRobot's Create 1 and 2"
+    CACHE STRING "Package description for the package metadata"
+)
+set(CPACK_PACKAGE_VENDOR "Verein zur Förderung von Jugendlichen durch Robotikwettbewerbe")
+
+set(CPACK_VERBATIM_VARIABLES YES)
+
+set(CPACK_PACKAGE_INSTALL_DIRECTORY ${CPACK_PACKAGE_NAME})
+SET(CPACK_OUTPUT_FILE_PREFIX "${CMAKE_SOURCE_DIR}/_packages")
+
+# https://unix.stackexchange.com/a/11552/254512
+set(CPACK_PACKAGING_INSTALL_PREFIX "/opt/some")#/${CMAKE_PROJECT_VERSION}")
+
+set(CPACK_PACKAGE_VERSION_MAJOR ${PROJECT_VERSION_MAJOR})
+set(CPACK_PACKAGE_VERSION_MINOR ${PROJECT_VERSION_MINOR})
+set(CPACK_PACKAGE_VERSION_PATCH ${PROJECT_VERSION_PATCH})
+
+set(CPACK_PACKAGE_CONTACT "kontakt@comp-air.at")
+set(CPACK_DEBIAN_PACKAGE_MAINTAINER "comp-air dev team")
+
+set(CPACK_RESOURCE_FILE_LICENSE "${CMAKE_CURRENT_SOURCE_DIR}/LICENSE")
+set(CPACK_RESOURCE_FILE_README "${CMAKE_CURRENT_SOURCE_DIR}/README.md")
+
+# Discover and set dependencies correcly
+set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS YES)
+
+# The installation path directory should have 0755 permissions
+set(
+    CPACK_INSTALL_DEFAULT_DIRECTORY_PERMISSIONS
+    OWNER_READ OWNER_WRITE OWNER_EXECUTE
+    GROUP_READ GROUP_EXECUTE
+    WORLD_READ WORLD_EXECUTE
+)
+
+# package name for deb. If set, then instead of some-application-0.9.2-Linux.deb
+# you'll get some-application_0.9.2_amd64.deb (note the underscores too)
+set(CPACK_DEBIAN_FILE_NAME DEB-DEFAULT)
+# that is if you want every group to have its own package,
+# although the same will happen if this is not set (so it defaults to ONE_PER_GROUP)
+# and CPACK_DEB_COMPONENT_INSTALL is set to YES
+set(CPACK_COMPONENTS_GROUPING ALL_COMPONENTS_IN_ONE)#ONE_PER_GROUP)
+# without this you won't be able to pack only specified component
+set(CPACK_DEB_COMPONENT_INSTALL YES)
+
+include(CPack)
\ No newline at end of file
diff --git a/package.sh b/package.sh
new file mode 100755
index 0000000..e69de29

From 1791063fa8644434c001b50b8543bad698ae713c Mon Sep 17 00:00:00 2001
From: Konstantin Lampalzer 
Date: Mon, 23 Sep 2024 13:34:10 +0200
Subject: [PATCH 090/108] cmake: add versioning module

---
 CMakeLists.txt         | 20 +++++++++++++++++---
 cmake/Versioning.cmake | 26 ++++++++++++++++++++++++++
 2 files changed, 43 insertions(+), 3 deletions(-)
 create mode 100644 cmake/Versioning.cmake

diff --git a/CMakeLists.txt b/CMakeLists.txt
index 2d37b18..54d6ded 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -1,3 +1,15 @@
+#########
+# Setup #
+#########
+
+set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake")
+
+include(Versioning)
+
+########
+# Main #
+########
+
 # After installation this project can be found by 'find_package' command:
 #
 #    find_package(libcreate REQUIRED)
@@ -6,11 +18,14 @@
 #
 
 cmake_minimum_required(VERSION 3.28)
-project(libcreate)
+project(
+  libcreate 
+  VERSION ${TAG_VERSION_MAJOR}.${TAG_VERSION_MINOR}.${TAG_VERSION_PATCH}
+)
 
 add_compile_options(-Wall -Wextra -Wpedantic)
 
-set(PACKAGE_VERSION 3.0.0)
+set(PACKAGE_VERSION ${TAG_VERSION_MAJOR}.${TAG_VERSION_MINOR}.${TAG_VERSION_PATCH})
 
 option(LIBCREATE_BUILD_TESTS "Enable the build of tests." ON)
 
@@ -208,5 +223,4 @@ endif()
 # Packaging #
 #############
 
-set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake")
 include(Packing)
\ No newline at end of file
diff --git a/cmake/Versioning.cmake b/cmake/Versioning.cmake
new file mode 100644
index 0000000..b082127
--- /dev/null
+++ b/cmake/Versioning.cmake
@@ -0,0 +1,26 @@
+find_package(Git)
+
+if(GIT_EXECUTABLE)
+    execute_process(
+        COMMAND ${GIT_EXECUTABLE} describe --tags
+        OUTPUT_VARIABLE TAG_VERSION
+        RESULT_VARIABLE ERROR_CODE
+        OUTPUT_STRIP_TRAILING_WHITESPACE
+    )
+
+    if(TAG_VERSION STREQUAL "")
+        set(TAG_VERSION 0.0.0)
+        message(WARNING "Failed to determine version from Git tags. Using default version \"${TAG_VERSION}\".")
+    endif()
+
+    message(STATUS "Project version: ${TAG_VERSION}")
+
+    # Split into major, minor, patch
+    string(
+        REGEX MATCH "([0-9]+)\\.([0-9]+)\\.([0-9]+)"
+        TAG_VERSION_MATCH ${TAG_VERSION}
+    )
+    set(TAG_VERSION_MAJOR ${CMAKE_MATCH_1})
+    set(TAG_VERSION_MINOR ${CMAKE_MATCH_2})
+    set(TAG_VERSION_PATCH ${CMAKE_MATCH_3})
+endif()
\ No newline at end of file

From 3836d1480b3b9e9a773464d895ce4ffc2182537d Mon Sep 17 00:00:00 2001
From: Konstantin Lampalzer 
Date: Mon, 23 Sep 2024 13:34:34 +0200
Subject: [PATCH 091/108] ci: add packing job

---
 .dockerignore                  |  2 +-
 .github/workflows/ci.yaml      | 38 ----------------------------------
 .github/workflows/package.yaml | 29 ++++++++++++++++++++++++++
 .github/workflows/test.yaml    | 30 +++++++++++++++++++++++++++
 ci/Dockerfile                  |  7 ++-----
 ci/entrypoint.sh               | 10 +++++++++
 6 files changed, 72 insertions(+), 44 deletions(-)
 delete mode 100644 .github/workflows/ci.yaml
 create mode 100644 .github/workflows/package.yaml
 create mode 100644 .github/workflows/test.yaml
 create mode 100755 ci/entrypoint.sh

diff --git a/.dockerignore b/.dockerignore
index 7846b39..d71d4b3 100644
--- a/.dockerignore
+++ b/.dockerignore
@@ -1,2 +1,2 @@
 .github
-ci
\ No newline at end of file
+ci/Dockerfile
\ No newline at end of file
diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml
deleted file mode 100644
index 7fb7d18..0000000
--- a/.github/workflows/ci.yaml
+++ /dev/null
@@ -1,38 +0,0 @@
-name: Build and test
-
-on:
-  push:
-    branches: ['master']
-  pull_request:
-
-env:
-  BUILD_TYPE: Release
-
-jobs:
-  build:
-    runs-on: ${{ matrix.os }}
-    strategy:
-      matrix:
-        os: [ubuntu-20.04, ubuntu-22.04]
-
-    steps:
-    - name: Install dependencies
-      run: |
-        sudo apt install build-essential cmake git libboost-system-dev libboost-thread-dev
-        git clone https://github.com/google/googletest.git
-        cd googletest
-        cmake CMakeLists.txt
-        make
-        sudo make install
-
-    - uses: actions/checkout@v2
-
-    - name: Configure CMake
-      run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} -DCMAKE_CXX_FLAGS="-Werror"
-
-    - name: Build
-      run: cmake --build ${{github.workspace}}/build --config ${{env.BUILD_TYPE}}
-
-    - name: Test
-      working-directory: ${{github.workspace}}/build
-      run: ctest -C ${{env.BUILD_TYPE}}
diff --git a/.github/workflows/package.yaml b/.github/workflows/package.yaml
new file mode 100644
index 0000000..bbc7e80
--- /dev/null
+++ b/.github/workflows/package.yaml
@@ -0,0 +1,29 @@
+name: Package
+
+on:
+  push:
+
+jobs:
+  package:
+    runs-on: ubuntu-24.04
+    strategy:
+      matrix:
+        platform: [linux/arm64/v8]
+
+    steps:
+      - name: Checkout
+        uses: actions/checkout@v4
+        with:
+          fetch-depth: 0
+
+      - name: Set up QEMU
+        uses: docker/setup-qemu-action@v3
+      - name: Set up Docker Buildx
+        uses: docker/setup-buildx-action@v3
+        with:
+          platforms: linux/arm64
+
+      - name: Prepare container
+        run: docker buildx build -f ci/Dockerfile . -t libcreate --platform ${{ matrix.platform }} --load
+      - name: Build
+        run: docker run --platform ${{ matrix.platform }} -v ./output:/libcreate/_packages libcreate
diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml
new file mode 100644
index 0000000..986dc29
--- /dev/null
+++ b/.github/workflows/test.yaml
@@ -0,0 +1,30 @@
+name: Build and test
+
+on:
+  push:
+    branches: ["master"]
+  pull_request:
+
+env:
+  BUILD_TYPE: Release
+
+jobs:
+  test:
+    runs-on: ubuntu-24.04
+
+    steps:
+      - name: Install dependencies
+        run: |
+          sudo apt install build-essential cmake git libboost-system-dev libboost-thread-dev file libgtest-dev googletest
+
+      - uses: actions/checkout@v4
+
+      - name: Configure CMake
+        run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} -DCMAKE_CXX_FLAGS="-Werror"
+
+      - name: Build
+        run: cmake --build ${{github.workspace}}/build --config ${{env.BUILD_TYPE}}
+
+      - name: Test
+        working-directory: ${{github.workspace}}/build
+        run: ctest -C ${{env.BUILD_TYPE}}
diff --git a/ci/Dockerfile b/ci/Dockerfile
index c303ca9..6516bf9 100644
--- a/ci/Dockerfile
+++ b/ci/Dockerfile
@@ -2,7 +2,7 @@ FROM ubuntu:24.04
 
 RUN apt update && \
     apt install -y \
-        build-essential cmake file \
+        build-essential cmake git file \
         libboost-system-dev libboost-thread-dev \
         libgtest-dev googletest && \
     rm -rf /var/lib/apt/lists/*
@@ -11,7 +11,4 @@ WORKDIR /libcreate
 COPY . .
 
 WORKDIR /libcreate/build
-RUN cmake -B /libcreate/build -S /libcreate -DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_FLAGS="-Werror" && \
-    cmake --build /libcreate/build --config Release && \
-    ctest -C Release --output-on-failure && \
-    cpack --build /libcreate/build -G DEB
+ENTRYPOINT ["/bin/bash", "/libcreate/ci/entrypoint.sh"] 
diff --git a/ci/entrypoint.sh b/ci/entrypoint.sh
new file mode 100755
index 0000000..c371918
--- /dev/null
+++ b/ci/entrypoint.sh
@@ -0,0 +1,10 @@
+#!/usr/bin/env bash
+
+set -o errexit
+set -o nounset
+set -o pipefail
+
+cmake -B /libcreate/build -S /libcreate -DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_FLAGS='-Werror'
+cmake --build /libcreate/build --config Release
+ctest -C Release --output-on-failure
+cpack --build /libcreate/build -G DEB
\ No newline at end of file

From efd9cf02c9229f5f1776f8579f1d447098c547ee Mon Sep 17 00:00:00 2001
From: Konstantin Lampalzer 
Date: Mon, 23 Sep 2024 14:06:29 +0200
Subject: [PATCH 092/108] ci: add tag extraction from github_ref var

---
 .github/workflows/package.yaml | 2 ++
 cmake/Versioning.cmake         | 5 +++++
 2 files changed, 7 insertions(+)

diff --git a/.github/workflows/package.yaml b/.github/workflows/package.yaml
index bbc7e80..1253655 100644
--- a/.github/workflows/package.yaml
+++ b/.github/workflows/package.yaml
@@ -2,6 +2,8 @@ name: Package
 
 on:
   push:
+    tags:
+      - "**"
 
 jobs:
   package:
diff --git a/cmake/Versioning.cmake b/cmake/Versioning.cmake
index b082127..7665011 100644
--- a/cmake/Versioning.cmake
+++ b/cmake/Versioning.cmake
@@ -8,6 +8,11 @@ if(GIT_EXECUTABLE)
         OUTPUT_STRIP_TRAILING_WHITESPACE
     )
 
+    if(DEFINED ENV{GITHUB_REF})
+        set(TAG_VERSION $ENV{GITHUB_REF})
+        message(STATUS "Extracted version from GITHUB_REF")
+    endif()
+
     if(TAG_VERSION STREQUAL "")
         set(TAG_VERSION 0.0.0)
         message(WARNING "Failed to determine version from Git tags. Using default version \"${TAG_VERSION}\".")

From f8b977336a6372d0bcef1099d85c7ac4c30272ce Mon Sep 17 00:00:00 2001
From: Konstantin Lampalzer 
Date: Mon, 23 Sep 2024 14:09:47 +0200
Subject: [PATCH 093/108] ci: change tag filter

---
 .github/workflows/package.yaml | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/.github/workflows/package.yaml b/.github/workflows/package.yaml
index 1253655..04fc237 100644
--- a/.github/workflows/package.yaml
+++ b/.github/workflows/package.yaml
@@ -3,7 +3,7 @@ name: Package
 on:
   push:
     tags:
-      - "**"
+      - "*"
 
 jobs:
   package:

From 1979a5d4058cce3b49f700d42285cd5b8b2d9535 Mon Sep 17 00:00:00 2001
From: Konstantin Lampalzer 
Date: Mon, 23 Sep 2024 14:31:09 +0200
Subject: [PATCH 094/108] ci: add push to compREP

---
 .github/workflows/package.yaml | 8 ++++++++
 1 file changed, 8 insertions(+)

diff --git a/.github/workflows/package.yaml b/.github/workflows/package.yaml
index 04fc237..3fe9610 100644
--- a/.github/workflows/package.yaml
+++ b/.github/workflows/package.yaml
@@ -29,3 +29,11 @@ jobs:
         run: docker buildx build -f ci/Dockerfile . -t libcreate --platform ${{ matrix.platform }} --load
       - name: Build
         run: docker run --platform ${{ matrix.platform }} -v ./output:/libcreate/_packages libcreate
+      - name: Push deb to compREP
+        uses: cpina/github-action-push-to-another-repository@main
+        with:
+          source-directory: "output/"
+          target-directory: "debs/complib/"
+          destination-github-username: "F-WuTS"
+          destination-repository-name: "compREP"
+          target-branch: master

From 52201a39324e6d0c0b04b20d44dbd0ef343c04db Mon Sep 17 00:00:00 2001
From: Konstantin Lampalzer 
Date: Mon, 23 Sep 2024 15:51:44 +0200
Subject: [PATCH 095/108] ci: fix SSH_DEPLOY_KEY env var

---
 .github/workflows/package.yaml | 2 ++
 1 file changed, 2 insertions(+)

diff --git a/.github/workflows/package.yaml b/.github/workflows/package.yaml
index 3fe9610..113c7bb 100644
--- a/.github/workflows/package.yaml
+++ b/.github/workflows/package.yaml
@@ -31,6 +31,8 @@ jobs:
         run: docker run --platform ${{ matrix.platform }} -v ./output:/libcreate/_packages libcreate
       - name: Push deb to compREP
         uses: cpina/github-action-push-to-another-repository@main
+        env:
+          SSH_DEPLOY_KEY: ${{ secrets.SSH_DEPLOY_KEY }}
         with:
           source-directory: "output/"
           target-directory: "debs/complib/"

From f3cafc241d96b60b89d6522a0ae40ee67faeced3 Mon Sep 17 00:00:00 2001
From: Konstantin Lampalzer 
Date: Mon, 23 Sep 2024 17:12:41 +0200
Subject: [PATCH 096/108] ci: change from ubuntu base to debian base

---
 CMakeLists.txt | 3 ++-
 ci/Dockerfile  | 2 +-
 2 files changed, 3 insertions(+), 2 deletions(-)

diff --git a/CMakeLists.txt b/CMakeLists.txt
index 54d6ded..007b56b 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -2,6 +2,8 @@
 # Setup #
 #########
 
+cmake_minimum_required(VERSION 3.25)
+
 set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake")
 
 include(Versioning)
@@ -17,7 +19,6 @@ include(Versioning)
 #    target_link_libraries(... ${libcreate_LIBRARIES})
 #
 
-cmake_minimum_required(VERSION 3.28)
 project(
   libcreate 
   VERSION ${TAG_VERSION_MAJOR}.${TAG_VERSION_MINOR}.${TAG_VERSION_PATCH}
diff --git a/ci/Dockerfile b/ci/Dockerfile
index 6516bf9..3274bbe 100644
--- a/ci/Dockerfile
+++ b/ci/Dockerfile
@@ -1,4 +1,4 @@
-FROM ubuntu:24.04
+FROM debian:bookworm
 
 RUN apt update && \
     apt install -y \

From 78424d187c78b34df71efae599b06f4dca96665e Mon Sep 17 00:00:00 2001
From: Konstantin Lampalzer 
Date: Mon, 23 Sep 2024 21:13:21 +0200
Subject: [PATCH 097/108] cmake: do not install to opt

---
 ci/Dockerfile       | 2 +-
 ci/entrypoint.sh    | 7 ++++++-
 cmake/Packing.cmake | 9 ---------
 3 files changed, 7 insertions(+), 11 deletions(-)

diff --git a/ci/Dockerfile b/ci/Dockerfile
index 3274bbe..bf82ed3 100644
--- a/ci/Dockerfile
+++ b/ci/Dockerfile
@@ -2,7 +2,7 @@ FROM debian:bookworm
 
 RUN apt update && \
     apt install -y \
-        build-essential cmake git file \
+        build-essential cmake git file tree \
         libboost-system-dev libboost-thread-dev \
         libgtest-dev googletest && \
     rm -rf /var/lib/apt/lists/*
diff --git a/ci/entrypoint.sh b/ci/entrypoint.sh
index c371918..680207f 100755
--- a/ci/entrypoint.sh
+++ b/ci/entrypoint.sh
@@ -7,4 +7,9 @@ set -o pipefail
 cmake -B /libcreate/build -S /libcreate -DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_FLAGS='-Werror'
 cmake --build /libcreate/build --config Release
 ctest -C Release --output-on-failure
-cpack --build /libcreate/build -G DEB
\ No newline at end of file
+cpack --build /libcreate/build -G DEB
+
+debs=(/libcreate/_packages/*.deb)
+cp "${debs[0]}" /tmp/libcreate.deb
+dpkg-deb -R /tmp/libcreate.deb /tmp/libcreate
+tree /tmp/libcreate
\ No newline at end of file
diff --git a/cmake/Packing.cmake b/cmake/Packing.cmake
index 93b1feb..58d81b8 100644
--- a/cmake/Packing.cmake
+++ b/cmake/Packing.cmake
@@ -13,9 +13,6 @@ set(CPACK_VERBATIM_VARIABLES YES)
 set(CPACK_PACKAGE_INSTALL_DIRECTORY ${CPACK_PACKAGE_NAME})
 SET(CPACK_OUTPUT_FILE_PREFIX "${CMAKE_SOURCE_DIR}/_packages")
 
-# https://unix.stackexchange.com/a/11552/254512
-set(CPACK_PACKAGING_INSTALL_PREFIX "/opt/some")#/${CMAKE_PROJECT_VERSION}")
-
 set(CPACK_PACKAGE_VERSION_MAJOR ${PROJECT_VERSION_MAJOR})
 set(CPACK_PACKAGE_VERSION_MINOR ${PROJECT_VERSION_MINOR})
 set(CPACK_PACKAGE_VERSION_PATCH ${PROJECT_VERSION_PATCH})
@@ -40,11 +37,5 @@ set(
 # package name for deb. If set, then instead of some-application-0.9.2-Linux.deb
 # you'll get some-application_0.9.2_amd64.deb (note the underscores too)
 set(CPACK_DEBIAN_FILE_NAME DEB-DEFAULT)
-# that is if you want every group to have its own package,
-# although the same will happen if this is not set (so it defaults to ONE_PER_GROUP)
-# and CPACK_DEB_COMPONENT_INSTALL is set to YES
-set(CPACK_COMPONENTS_GROUPING ALL_COMPONENTS_IN_ONE)#ONE_PER_GROUP)
-# without this you won't be able to pack only specified component
-set(CPACK_DEB_COMPONENT_INSTALL YES)
 
 include(CPack)
\ No newline at end of file

From 3ac90c382e5db2b87348264add23be3bcdd455a7 Mon Sep 17 00:00:00 2001
From: Konstantin Lampalzer 
Date: Mon, 23 Sep 2024 22:46:52 +0200
Subject: [PATCH 098/108] ci: change target-dir in comprep to debs/libcreate

---
 .github/workflows/package.yaml | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/.github/workflows/package.yaml b/.github/workflows/package.yaml
index 113c7bb..5a1e8f4 100644
--- a/.github/workflows/package.yaml
+++ b/.github/workflows/package.yaml
@@ -35,7 +35,7 @@ jobs:
           SSH_DEPLOY_KEY: ${{ secrets.SSH_DEPLOY_KEY }}
         with:
           source-directory: "output/"
-          target-directory: "debs/complib/"
+          target-directory: "debs/libcreate/"
           destination-github-username: "F-WuTS"
           destination-repository-name: "compREP"
           target-branch: master

From e51895fa18a9599a3173975679d39bb691e69afb Mon Sep 17 00:00:00 2001
From: Konstantin Lampalzer 
Date: Wed, 25 Sep 2024 21:54:46 +0200
Subject: [PATCH 099/108] cmake: add default Werror, extract version only from
 GITHUB_REF if tag

---
 .github/workflows/test.yaml | 2 +-
 CMakeLists.txt              | 2 +-
 cmake/Versioning.cmake      | 2 +-
 3 files changed, 3 insertions(+), 3 deletions(-)

diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml
index 986dc29..fb0bcce 100644
--- a/.github/workflows/test.yaml
+++ b/.github/workflows/test.yaml
@@ -20,7 +20,7 @@ jobs:
       - uses: actions/checkout@v4
 
       - name: Configure CMake
-        run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} -DCMAKE_CXX_FLAGS="-Werror"
+        run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}}
 
       - name: Build
         run: cmake --build ${{github.workspace}}/build --config ${{env.BUILD_TYPE}}
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 007b56b..e39cf16 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -24,7 +24,7 @@ project(
   VERSION ${TAG_VERSION_MAJOR}.${TAG_VERSION_MINOR}.${TAG_VERSION_PATCH}
 )
 
-add_compile_options(-Wall -Wextra -Wpedantic)
+add_compile_options(-Wall -Wextra -Wpedantic -Werror)
 
 set(PACKAGE_VERSION ${TAG_VERSION_MAJOR}.${TAG_VERSION_MINOR}.${TAG_VERSION_PATCH})
 
diff --git a/cmake/Versioning.cmake b/cmake/Versioning.cmake
index 7665011..d659c5c 100644
--- a/cmake/Versioning.cmake
+++ b/cmake/Versioning.cmake
@@ -8,7 +8,7 @@ if(GIT_EXECUTABLE)
         OUTPUT_STRIP_TRAILING_WHITESPACE
     )
 
-    if(DEFINED ENV{GITHUB_REF})
+    if(DEFINED ENV{GITHUB_REF} AND ENV{GITHUB_REF_TYPE} EQUAL "tag")
         set(TAG_VERSION $ENV{GITHUB_REF})
         message(STATUS "Extracted version from GITHUB_REF")
     endif()

From 5a591cfbbad809c82f1d9370418ae9b01ab18348 Mon Sep 17 00:00:00 2001
From: Konstantin Lampalzer 
Date: Wed, 25 Sep 2024 21:58:36 +0200
Subject: [PATCH 100/108] ci: remove Werror from entrypoint

---
 ci/entrypoint.sh | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/ci/entrypoint.sh b/ci/entrypoint.sh
index 680207f..779d753 100755
--- a/ci/entrypoint.sh
+++ b/ci/entrypoint.sh
@@ -4,7 +4,7 @@ set -o errexit
 set -o nounset
 set -o pipefail
 
-cmake -B /libcreate/build -S /libcreate -DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_FLAGS='-Werror'
+cmake -B /libcreate/build -S /libcreate -DCMAKE_BUILD_TYPE=Release
 cmake --build /libcreate/build --config Release
 ctest -C Release --output-on-failure
 cpack --build /libcreate/build -G DEB

From d07add7a9130133eddf1fa73f9e7bb5b2afd503c Mon Sep 17 00:00:00 2001
From: Christoph Heiss 
Date: Thu, 26 Sep 2024 09:20:57 +0200
Subject: [PATCH 101/108] chore: delete empty file

Signed-off-by: Christoph Heiss 
---
 package.sh | 0
 1 file changed, 0 insertions(+), 0 deletions(-)
 delete mode 100755 package.sh

diff --git a/package.sh b/package.sh
deleted file mode 100755
index e69de29..0000000

From f49a76c7e4d360d1bb515ba690753066dbb23876 Mon Sep 17 00:00:00 2001
From: Christoph Heiss 
Date: Thu, 26 Sep 2024 09:21:10 +0200
Subject: [PATCH 102/108] gitignore: add cmake/cpack output directories

Signed-off-by: Christoph Heiss 
---
 .gitignore | 3 +++
 1 file changed, 3 insertions(+)
 create mode 100644 .gitignore

diff --git a/.gitignore b/.gitignore
new file mode 100644
index 0000000..28408a6
--- /dev/null
+++ b/.gitignore
@@ -0,0 +1,3 @@
+# CMake/CPack
+build/
+_packages/

From 8df56b61badb4cd7c44cfeca81e1934736345bac Mon Sep 17 00:00:00 2001
From: Christoph Heiss 
Date: Mon, 7 Oct 2024 11:55:33 +0200
Subject: [PATCH 103/108] ci: switch workflows to `Default` runner group

Signed-off-by: Christoph Heiss 
---
 .github/workflows/package.yaml | 4 +++-
 .github/workflows/test.yaml    | 6 ++++--
 2 files changed, 7 insertions(+), 3 deletions(-)

diff --git a/.github/workflows/package.yaml b/.github/workflows/package.yaml
index 5a1e8f4..32188e0 100644
--- a/.github/workflows/package.yaml
+++ b/.github/workflows/package.yaml
@@ -7,7 +7,9 @@ on:
 
 jobs:
   package:
-    runs-on: ubuntu-24.04
+    runs-on:
+      group: Default
+
     strategy:
       matrix:
         platform: [linux/arm64/v8]
diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml
index fb0bcce..00f8247 100644
--- a/.github/workflows/test.yaml
+++ b/.github/workflows/test.yaml
@@ -2,7 +2,8 @@ name: Build and test
 
 on:
   push:
-    branches: ["master"]
+    branches:
+      - master
   pull_request:
 
 env:
@@ -10,7 +11,8 @@ env:
 
 jobs:
   test:
-    runs-on: ubuntu-24.04
+    runs-on:
+      group: Default
 
     steps:
       - name: Install dependencies

From f07973e42645c84ba4378ad9fe087689b54f59f1 Mon Sep 17 00:00:00 2001
From: Christoph Heiss 
Date: Tue, 8 Oct 2024 11:48:52 +0200
Subject: [PATCH 104/108] Revert "ci: switch workflows to `Default` runner
 group"

This reverts commit 8df56b61badb4cd7c44cfeca81e1934736345bac.
---
 .github/workflows/package.yaml | 4 +---
 .github/workflows/test.yaml    | 6 ++----
 2 files changed, 3 insertions(+), 7 deletions(-)

diff --git a/.github/workflows/package.yaml b/.github/workflows/package.yaml
index 32188e0..5a1e8f4 100644
--- a/.github/workflows/package.yaml
+++ b/.github/workflows/package.yaml
@@ -7,9 +7,7 @@ on:
 
 jobs:
   package:
-    runs-on:
-      group: Default
-
+    runs-on: ubuntu-24.04
     strategy:
       matrix:
         platform: [linux/arm64/v8]
diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml
index 00f8247..fb0bcce 100644
--- a/.github/workflows/test.yaml
+++ b/.github/workflows/test.yaml
@@ -2,8 +2,7 @@ name: Build and test
 
 on:
   push:
-    branches:
-      - master
+    branches: ["master"]
   pull_request:
 
 env:
@@ -11,8 +10,7 @@ env:
 
 jobs:
   test:
-    runs-on:
-      group: Default
+    runs-on: ubuntu-24.04
 
     steps:
       - name: Install dependencies

From 6c8a7b3accb0a68e92b38ca8160f20827f0cef27 Mon Sep 17 00:00:00 2001
From: Christoph Heiss 
Date: Fri, 6 Jun 2025 20:15:42 +0200
Subject: [PATCH 105/108] ci: switch to forgejo actions

Signed-off-by: Christoph Heiss 
---
 .forgejo/workflows/package.yaml | 64 +++++++++++++++++++++++++++++++++
 .forgejo/workflows/test.yaml    | 34 ++++++++++++++++++
 .github/workflows/package.yaml  | 41 ---------------------
 .github/workflows/test.yaml     | 30 ----------------
 ci/Dockerfile                   | 14 --------
 ci/entrypoint.sh                | 15 --------
 6 files changed, 98 insertions(+), 100 deletions(-)
 create mode 100644 .forgejo/workflows/package.yaml
 create mode 100644 .forgejo/workflows/test.yaml
 delete mode 100644 .github/workflows/package.yaml
 delete mode 100644 .github/workflows/test.yaml
 delete mode 100644 ci/Dockerfile
 delete mode 100755 ci/entrypoint.sh

diff --git a/.forgejo/workflows/package.yaml b/.forgejo/workflows/package.yaml
new file mode 100644
index 0000000..f47b5e4
--- /dev/null
+++ b/.forgejo/workflows/package.yaml
@@ -0,0 +1,64 @@
+---
+name: Package
+
+on:
+  push:
+    tags:
+      - "*"
+
+jobs:
+  package:
+    strategy:
+      matrix:
+        platform:
+          - dpkg: arm64
+            runs-on: debian-12-arm64
+
+    runs-on: debian-12-arm64
+
+    steps:
+      - uses: actions/checkout@11bd71901bbe5b1630ceea73d27597364c9af683 # v4.2.2
+        with:
+          fetch-depth: 0
+
+      - name: Install dependencies
+        run: |
+          apt update
+          apt install -y \
+            build-essential cmake git libboost-system-dev libboost-thread-dev file libgtest-dev googletest
+
+      - uses: actions/checkout@v4
+
+      - name: configure
+        run: cmake -B build -DCMAKE_BUILD_TYPE=Release -DCPACK_DEBIAN_PACKAGE_RELEASE=compair1
+
+      - name: build
+        run: cmake --build build --config Release -j2
+
+      - name: test
+        working-directory: build
+        run: ctest -C Release
+
+      - name: build deb
+        working-directory: build
+        run: cpack --build . -G DEB
+
+      - name: get tag
+        run: |
+          echo "TAG=$(git describe --abbrev=0 --tags)-compair1" >>$GITHUB_ENV
+
+      # https://forgejo.org/docs/latest/user/packages/debian/#publish-a-package
+      - name: push deb to apt repository
+        env:
+          REPO: ${{ github.repository }}
+        run: |
+          url="${GITHUB_SERVER_URL}/api/packages/${{ github.repository_owner }}/debian/pool/bookworm/compair/upload"
+          echo "api url: $url"
+          debfile="_packages/libcreate_${TAG}_${{ matrix.platform.dpkg }}.deb"
+          echo "uploading file: $debfile"
+          curl --fail-with-body \
+            -X PUT \
+            --user "oauth2:${{ secrets.PACKAGE_REGISTRY_TOKEN }}" \
+            --upload-file "$debfile" \
+            "$url"
+          echo "final url: ${GITHUB_SERVER_URL}/${{ github.repository_owner }}/-/packages/debian/libcreate/${TAG}"
diff --git a/.forgejo/workflows/test.yaml b/.forgejo/workflows/test.yaml
new file mode 100644
index 0000000..2b55f1a
--- /dev/null
+++ b/.forgejo/workflows/test.yaml
@@ -0,0 +1,34 @@
+---
+name: Build and test
+
+on:
+  push:
+    branches:
+      - master
+  pull_request:
+
+env:
+  BUILD_TYPE: Release
+
+jobs:
+  test:
+    runs-on: debian-12
+
+    steps:
+      - name: Install dependencies
+        run: |
+          apt update
+          apt install -y \
+            build-essential cmake git libboost-system-dev libboost-thread-dev file libgtest-dev googletest
+
+      - uses: actions/checkout@v4
+
+      - name: Configure CMake
+        run: cmake -B ${{ github.workspace }}/build -DCMAKE_BUILD_TYPE=${{ env.BUILD_TYPE }}
+
+      - name: Build
+        run: cmake --build ${{ github.workspace }}/build --config ${{ env.BUILD_TYPE }}
+
+      - name: Test
+        working-directory: ${{ github.workspace }}/build
+        run: ctest -C ${{ env.BUILD_TYPE }}
diff --git a/.github/workflows/package.yaml b/.github/workflows/package.yaml
deleted file mode 100644
index 5a1e8f4..0000000
--- a/.github/workflows/package.yaml
+++ /dev/null
@@ -1,41 +0,0 @@
-name: Package
-
-on:
-  push:
-    tags:
-      - "*"
-
-jobs:
-  package:
-    runs-on: ubuntu-24.04
-    strategy:
-      matrix:
-        platform: [linux/arm64/v8]
-
-    steps:
-      - name: Checkout
-        uses: actions/checkout@v4
-        with:
-          fetch-depth: 0
-
-      - name: Set up QEMU
-        uses: docker/setup-qemu-action@v3
-      - name: Set up Docker Buildx
-        uses: docker/setup-buildx-action@v3
-        with:
-          platforms: linux/arm64
-
-      - name: Prepare container
-        run: docker buildx build -f ci/Dockerfile . -t libcreate --platform ${{ matrix.platform }} --load
-      - name: Build
-        run: docker run --platform ${{ matrix.platform }} -v ./output:/libcreate/_packages libcreate
-      - name: Push deb to compREP
-        uses: cpina/github-action-push-to-another-repository@main
-        env:
-          SSH_DEPLOY_KEY: ${{ secrets.SSH_DEPLOY_KEY }}
-        with:
-          source-directory: "output/"
-          target-directory: "debs/libcreate/"
-          destination-github-username: "F-WuTS"
-          destination-repository-name: "compREP"
-          target-branch: master
diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml
deleted file mode 100644
index fb0bcce..0000000
--- a/.github/workflows/test.yaml
+++ /dev/null
@@ -1,30 +0,0 @@
-name: Build and test
-
-on:
-  push:
-    branches: ["master"]
-  pull_request:
-
-env:
-  BUILD_TYPE: Release
-
-jobs:
-  test:
-    runs-on: ubuntu-24.04
-
-    steps:
-      - name: Install dependencies
-        run: |
-          sudo apt install build-essential cmake git libboost-system-dev libboost-thread-dev file libgtest-dev googletest
-
-      - uses: actions/checkout@v4
-
-      - name: Configure CMake
-        run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}}
-
-      - name: Build
-        run: cmake --build ${{github.workspace}}/build --config ${{env.BUILD_TYPE}}
-
-      - name: Test
-        working-directory: ${{github.workspace}}/build
-        run: ctest -C ${{env.BUILD_TYPE}}
diff --git a/ci/Dockerfile b/ci/Dockerfile
deleted file mode 100644
index bf82ed3..0000000
--- a/ci/Dockerfile
+++ /dev/null
@@ -1,14 +0,0 @@
-FROM debian:bookworm
-
-RUN apt update && \
-    apt install -y \
-        build-essential cmake git file tree \
-        libboost-system-dev libboost-thread-dev \
-        libgtest-dev googletest && \
-    rm -rf /var/lib/apt/lists/*
-
-WORKDIR /libcreate
-COPY . .
-
-WORKDIR /libcreate/build
-ENTRYPOINT ["/bin/bash", "/libcreate/ci/entrypoint.sh"] 
diff --git a/ci/entrypoint.sh b/ci/entrypoint.sh
deleted file mode 100755
index 779d753..0000000
--- a/ci/entrypoint.sh
+++ /dev/null
@@ -1,15 +0,0 @@
-#!/usr/bin/env bash
-
-set -o errexit
-set -o nounset
-set -o pipefail
-
-cmake -B /libcreate/build -S /libcreate -DCMAKE_BUILD_TYPE=Release
-cmake --build /libcreate/build --config Release
-ctest -C Release --output-on-failure
-cpack --build /libcreate/build -G DEB
-
-debs=(/libcreate/_packages/*.deb)
-cp "${debs[0]}" /tmp/libcreate.deb
-dpkg-deb -R /tmp/libcreate.deb /tmp/libcreate
-tree /tmp/libcreate
\ No newline at end of file

From 661fa82f6e620ba2288d94f733d6891ec4e159e9 Mon Sep 17 00:00:00 2001
From: "jakob.kampichler" 
Date: Fri, 6 Jun 2025 18:35:09 +0000
Subject: [PATCH 106/108] ci: also include Botball repo

---
 .forgejo/workflows/package.yaml | 12 ++++++++++++
 1 file changed, 12 insertions(+)

diff --git a/.forgejo/workflows/package.yaml b/.forgejo/workflows/package.yaml
index f47b5e4..2007e54 100644
--- a/.forgejo/workflows/package.yaml
+++ b/.forgejo/workflows/package.yaml
@@ -53,12 +53,24 @@ jobs:
           REPO: ${{ github.repository }}
         run: |
           url="${GITHUB_SERVER_URL}/api/packages/${{ github.repository_owner }}/debian/pool/bookworm/compair/upload"
+          urlBotball="${GITHUB_SERVER_URL}/api/packages/Botball/debian/pool/bookworm/wombatos/upload"
+
           echo "api url: $url"
           debfile="_packages/libcreate_${TAG}_${{ matrix.platform.dpkg }}.deb"
+          
           echo "uploading file: $debfile"
           curl --fail-with-body \
             -X PUT \
             --user "oauth2:${{ secrets.PACKAGE_REGISTRY_TOKEN }}" \
             --upload-file "$debfile" \
             "$url"
+          
+          echo "uploading file for WombatOs: $debfile"
+          curl --fail-with-body \
+            -X PUT \
+            --user "oauth2:${{ secrets.PACKAGE_REGISTRY_TOKEN }}" \
+            --upload-file "$debfile" \
+            "$urlBotball"
+
           echo "final url: ${GITHUB_SERVER_URL}/${{ github.repository_owner }}/-/packages/debian/libcreate/${TAG}"
+          echo "final url for Botball: ${GITHUB_SERVER_URL}/Botball/-/packages/debian/libcreate/${TAG}"

From ac3968e0551db9b7b1a47ab2230c084361db2c0a Mon Sep 17 00:00:00 2001
From: Christoph Heiss 
Date: Fri, 6 Jun 2025 23:01:25 +0200
Subject: [PATCH 107/108] ci: package: fix whitespace errors

Signed-off-by: Christoph Heiss 
---
 .forgejo/workflows/package.yaml | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/.forgejo/workflows/package.yaml b/.forgejo/workflows/package.yaml
index 2007e54..b090971 100644
--- a/.forgejo/workflows/package.yaml
+++ b/.forgejo/workflows/package.yaml
@@ -57,14 +57,14 @@ jobs:
 
           echo "api url: $url"
           debfile="_packages/libcreate_${TAG}_${{ matrix.platform.dpkg }}.deb"
-          
+
           echo "uploading file: $debfile"
           curl --fail-with-body \
             -X PUT \
             --user "oauth2:${{ secrets.PACKAGE_REGISTRY_TOKEN }}" \
             --upload-file "$debfile" \
             "$url"
-          
+
           echo "uploading file for WombatOs: $debfile"
           curl --fail-with-body \
             -X PUT \

From d1071443ff183751d3a421b105712501270f5868 Mon Sep 17 00:00:00 2001
From: Jacob Perron 
Date: Sun, 13 Apr 2025 14:01:07 -0700
Subject: [PATCH 108/108] Update Autonomy Lab link

(cherry picked from commit 116be443e7970de1574b5dc5f91e414828854c08)
---
 README.md | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/README.md b/README.md
index fa1232c..b1eb336 100644
--- a/README.md
+++ b/README.md
@@ -7,7 +7,7 @@ C++ library for interfacing with iRobot's Create 1 and 2 as well as most models
   - [`V_1`](https://drive.google.com/file/d/0B9O4b91VYXMdUHlqNklDU09NU0k/view?usp=sharing&resourcekey=0-KxMpRPBMsGAj7eSYC_9ewA) (Roomba 400 series )
   - [`V_2`](https://drive.google.com/file/d/0B9O4b91VYXMdMmFPMVNDUEZ6d0U/view?usp=sharing&resourcekey=0-bqKH8xhtWdYtTik_LLWo9Q) (Create 1, Roomba 500 series)
   - [`V_3`](https://drive.google.com/file/d/0B9O4b91VYXMdSVk4amw1N09mQ3c/view?usp=sharing&resourcekey=0-rKvug2IzC7nj4zV31EJtww) (Create 2, Roomba 600-800 series)
-* Author: [Jacob Perron](http://jacobperron.ca) ([Autonomy Lab](http://autonomylab.org), [Simon Fraser University](http://www.sfu.ca))
+* Author: [Jacob Perron](http://jacobperron.ca) ([Autonomy Lab](https://autonomy.cs.sfu.ca), [Simon Fraser University](http://www.sfu.ca))
 * Contributors: [Mani Monajjemi](http:mani.im), [Ben Wolsieffer](https://github.com/lopsided98), [Josh Gadeken](https://github.com/process1183)
 
 ## Build Status ##