Compare commits
30 commits
Author | SHA1 | Date | |
---|---|---|---|
|
d1071443ff | ||
ac3968e055 | |||
661fa82f6e | |||
6c8a7b3acc | |||
f07973e426 | |||
8df56b61ba | |||
f49a76c7e4 | |||
d07add7a91 | |||
d5885d4d39 | |||
|
5a591cfbba | ||
|
e51895fa18 | ||
|
3ac90c382e | ||
|
78424d187c | ||
|
f3cafc241d | ||
|
52201a3932 | ||
|
1979a5d405 | ||
|
f8b977336a | ||
|
efd9cf02c9 | ||
|
3836d1480b | ||
|
1791063fa8 | ||
|
7ae7155f25 | ||
|
8b5167b319 | ||
|
aaa7b5076e | ||
|
d3a714cc51 | ||
|
7ade48545e | ||
|
2c58777e45 | ||
|
1bc2d768f7 | ||
|
fd2638114a | ||
|
a8e274be15 | ||
|
05e01c85a4 |
14 changed files with 320 additions and 62 deletions
2
.dockerignore
Normal file
2
.dockerignore
Normal file
|
@ -0,0 +1,2 @@
|
|||
.github
|
||||
ci/Dockerfile
|
76
.forgejo/workflows/package.yaml
Normal file
76
.forgejo/workflows/package.yaml
Normal file
|
@ -0,0 +1,76 @@
|
|||
---
|
||||
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"
|
||||
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}"
|
34
.forgejo/workflows/test.yaml
Normal file
34
.forgejo/workflows/test.yaml
Normal file
|
@ -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 }}
|
38
.github/workflows/ci.yaml
vendored
38
.github/workflows/ci.yaml
vendored
|
@ -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-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}}
|
3
.gitignore
vendored
Normal file
3
.gitignore
vendored
Normal file
|
@ -0,0 +1,3 @@
|
|||
# CMake/CPack
|
||||
build/
|
||||
_packages/
|
|
@ -1,3 +1,17 @@
|
|||
#########
|
||||
# Setup #
|
||||
#########
|
||||
|
||||
cmake_minimum_required(VERSION 3.25)
|
||||
|
||||
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)
|
||||
|
@ -5,12 +19,14 @@
|
|||
# target_link_libraries(... ${libcreate_LIBRARIES})
|
||||
#
|
||||
|
||||
cmake_minimum_required(VERSION 2.8.12)
|
||||
project(libcreate)
|
||||
project(
|
||||
libcreate
|
||||
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 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)
|
||||
|
||||
|
@ -84,6 +100,8 @@ endforeach()
|
|||
# Configuration #
|
||||
#################
|
||||
|
||||
# set(CMAKE_INSTALL_PREFIX "/usr/") // complib needs this, riplib doesn't
|
||||
|
||||
# Install directories layout:
|
||||
# * <prefix>/lib/
|
||||
# * <prefix>/bin/
|
||||
|
@ -201,3 +219,9 @@ if(LIBCREATE_BUILD_TESTS AND ${GTEST_FOUND})
|
|||
else()
|
||||
message("No GTest installation found. Skipping tests.")
|
||||
endif()
|
||||
|
||||
#############
|
||||
# Packaging #
|
||||
#############
|
||||
|
||||
include(Packing)
|
12
README.md
12
README.md
|
@ -1,13 +1,13 @@
|
|||
# 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)
|
||||
* Author: [Jacob Perron](http://jacobperron.ca) ([Autonomy Lab](http://autonomylab.org), [Simon Fraser University](http://www.sfu.ca))
|
||||
- [`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](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 ##
|
||||
|
|
41
cmake/Packing.cmake
Normal file
41
cmake/Packing.cmake
Normal file
|
@ -0,0 +1,41 @@
|
|||
# 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")
|
||||
|
||||
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)
|
||||
|
||||
include(CPack)
|
31
cmake/Versioning.cmake
Normal file
31
cmake/Versioning.cmake
Normal file
|
@ -0,0 +1,31 @@
|
|||
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(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()
|
||||
|
||||
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()
|
|
@ -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.
|
||||
*
|
||||
|
@ -406,6 +411,26 @@ namespace create {
|
|||
*/
|
||||
bool isCliffFrontRight() const;
|
||||
|
||||
/**
|
||||
* \return the IR value of the left cliff sensor.
|
||||
*/
|
||||
uint16_t getCliffSignalLeft() const;
|
||||
|
||||
/**
|
||||
* \return the IR value of the front left cliff sensor.
|
||||
*/
|
||||
uint16_t getCliffSignalFrontLeft() const;
|
||||
|
||||
/**
|
||||
* \return the IR value of the right cliff sensor.
|
||||
*/
|
||||
uint16_t getCliffSignalRight() const;
|
||||
|
||||
/**
|
||||
* \return the IR value of the front right cliff sensor.
|
||||
*/
|
||||
uint16_t getCliffSignalFrontRight() const;
|
||||
|
||||
/**
|
||||
* \return true if there is a virtual wall signal is being received.
|
||||
*/
|
||||
|
|
|
@ -32,6 +32,7 @@ POSSIBILITY OF SUCH DAMAGE.
|
|||
#define CREATE_PACKET_H
|
||||
|
||||
#include <mutex>
|
||||
#include <string>
|
||||
|
||||
namespace create {
|
||||
class Packet {
|
||||
|
|
|
@ -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();
|
||||
|
@ -156,17 +165,23 @@ namespace create {
|
|||
// Compute ticks since last update
|
||||
int ticksLeft = totalTicksLeft - prevTicksLeft;
|
||||
int ticksRight = totalTicksRight - prevTicksRight;
|
||||
|
||||
// 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;
|
||||
} else if (ticksRight < -0.9 * util::V_3_MAX_ENCODER_TICKS) {
|
||||
ticksRight += util::V_3_MAX_ENCODER_TICKS;
|
||||
}
|
||||
|
||||
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 (std::abs(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::V_3_TICKS_PER_REV)
|
||||
* model.getWheelDiameter() * util::PI;
|
||||
|
@ -738,6 +753,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);
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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<int>(data_v_3.getNumPackets()), 30);
|
||||
// 17 + 17 = 34
|
||||
EXPECT_EQ(static_cast<int>(data_v_3.getNumPackets()), 34);
|
||||
|
||||
create::Data data_v_all(create::V_ALL);
|
||||
EXPECT_EQ(static_cast<int>(data_v_all.getNumPackets()), 33);
|
||||
EXPECT_EQ(static_cast<int>(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<uint8_t> packet_ids = data_v_3.getPacketIDs();
|
||||
// Vector should have same length as reported by getNumPackets()
|
||||
ASSERT_EQ(static_cast<int>(packet_ids.size()), 30);
|
||||
ASSERT_EQ(static_cast<int>(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<int>(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<int>(data_v_3.getTotalDataBytes()), 42);
|
||||
EXPECT_EQ(static_cast<int>(data_v_3.getTotalDataBytes()), 50);
|
||||
}
|
||||
|
||||
TEST(DataTest, IsValidPacketID)
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue