Skip to content

Commit

Permalink
WIP lucid on jetson
Browse files Browse the repository at this point in the history
  • Loading branch information
tuas-travis-ci committed Apr 19, 2024
1 parent d414e69 commit 77f70d0
Show file tree
Hide file tree
Showing 14 changed files with 277 additions and 80 deletions.
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
// See this page for reference of options: https://containers.dev/implementors/json_reference
{
"name": "Existing Dockerfile",
"image": "ghcr.io/tritonuas/obcpp:x86",
"name": "Jetson",
"image": "tritonuas/obcpp:jetson",
// enable when need to connect over USB to pixhawk
// also: need to run obcpp with sudo or add tuas user to dialout group with
// `sudo usermod -aG dialout tuas && newgrp && bash`
Expand Down
28 changes: 28 additions & 0 deletions .devcontainer/x86/devcontainer.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
// See this page for reference of options: https://containers.dev/implementors/json_reference
{
"name": "x86",
"image": "ghcr.io/tritonuas/obcpp:main",
// enable when need to connect over USB to pixhawk
// also: need to run obcpp with sudo or add tuas user to dialout group with
// `sudo usermod -aG dialout tuas && newgrp && bash`
// "runArgs": ["--device=/dev/ttyACM0"],

"customizations": {
"vscode": {
"settings": {
// Use bash instead ofk sh
"terminal.integrated.defaultProfile.linux": "bash"
},
"extensions": [
"shd101wyy.markdown-preview-enhanced",
"ms-vscode.cpptools",
"nick-dimeglio.family-guy-funny-moments",
"twxs.cmake",
"me-dutour-mathieu.vscode-github-actions"
]
}
}

// Use 'postCreateCommand' to run commands after the container is created.
// "postCreateCommand": ""
}
2 changes: 1 addition & 1 deletion .gitmodules
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
[submodule "protos"]
path = protos
url = git@github.com:tritonuas/protos.git
url = https://github.com/tritonuas/protos.git
19 changes: 17 additions & 2 deletions docker/Dockerfile.jetson
Original file line number Diff line number Diff line change
Expand Up @@ -87,15 +87,30 @@ RUN update-alternatives --install /usr/bin/g++ g++ /usr/bin/g++-10 10
RUN update-alternatives --set gcc /usr/bin/gcc-10
RUN update-alternatives --set g++ /usr/bin/g++-10

RUN pip3 install gdown
ENV PATH="${PATH}:${HOME}/.local/bin"

ARG ARENA_INSTALL_DIR=/arena-tmp
ARG ARENA_TAR_PATH="${ARENA_INSTALL_DIR}ArenaSDK_Linux.tar.gz"
ARG ARENA_EXTRACTED_PATH="${ARENA_INSTALL_DIR}/ArenaSDK_Linux_ARM64"
WORKDIR ${ARENA_INSTALL_DIR}
RUN gdown 1VtBji-cWfetM5nXZwt55JuHPWPGahQOH -O ${ARENA_TAR_PATH}
RUN tar -xvzf ${ARENA_TAR_PATH}
WORKDIR ${ARENA_EXTRACTED_PATH}
RUN sh Arena_SDK_ARM64.conf

RUN apt-get update && apt-get install ninja-build

WORKDIR /obcpp
COPY . .

RUN git submodule update --init
RUN rm -rf /obcpp/build
WORKDIR /obcpp/build
ENV CMAKE_PREFIX_PATH="/usr/local/lib/python3.8/dist-packages/torch/share/cmake/Torch;/usr/local/share/cmake/TorchVision"
RUN GITHUB_ACTIONS=true cmake -DCMAKE_PREFIX_PATH="/usr/local/lib/python3.8/dist-packages/torch/share/cmake/Torch;/usr/local/share/cmake/TorchVision" -DCMAKE_MODULE_PATH="/usr/local/share/cmake/TorchVision" -DCMAKE_BUILD_TYPE="Release" ..
RUN GITHUB_ACTIONS=true cmake -DCMAKE_PREFIX_PATH="/usr/local/lib/python3.8/dist-packages/torch/share/cmake/Torch;/usr/local/share/cmake/TorchVision" -DCMAKE_MODULE_PATH="/usr/local/share/cmake/TorchVision" -DCMAKE_BUILD_TYPE="Release" -DCMAKE_JOB_POOLS="j=2" ..

RUN make obcpp cuda_check load_torchvision_model VERBOSE=1
RUN ninja obcpp cuda_check load_torchvision_model

# login as non-root user
# USER $USERNAME
Expand Down
47 changes: 7 additions & 40 deletions include/camera/interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
#include <string>
#include <vector>
#include <memory>
#include <optional>

#include <nlohmann/json.hpp>
#include <opencv2/opencv.hpp>
Expand Down Expand Up @@ -54,67 +55,33 @@ class ImageData {
class CameraConfiguration {
private:
nlohmann::json configJson;

public:
explicit CameraConfiguration(nlohmann::json config);

void updateConfig(nlohmann::json newSetting);

// void updateConfigField(std::string key, T value);

nlohmann::json getConfig();

nlohmann::json getConfigField();
// void updateConfigField(std::string key, T value);
};

class CameraInterface {
private:
CameraConfiguration config;
std::unique_ptr<ImageData> recentPicture; // might need to move it to public
bool doneTakingPicture; // overengineering time
std::string uploadPath;
// Interpreter interp
// TODO: SERVER CONNECTION HERE ?

void imgConvert();

public:
explicit CameraInterface(CameraConfiguration config);

virtual ~CameraInterface() = default;

virtual void connect() = 0;
virtual bool isConnected() = 0;

virtual bool verifyConnection() = 0;

virtual void takePicture() = 0;

virtual ImageData getLastPicture() = 0;

virtual bool takePictureForSeconds(int sec) = 0;
virtual void startTakingPictures(std::chrono::seconds interval) = 0;
virtual void stopTakingPictures() = 0;

virtual void startTakingPictures(double intervalSec) = 0;

virtual bool isDoneTakingPictures() = 0;
virtual std::optional<ImageData> getLatestImage() = 0;
virtual std::queue<ImageData> getAllImages() = 0;

CameraConfiguration getConfig();

void updateConfig(CameraConfiguration newConfig);

void updateConfig(nlohmann::json newJsonConfig);

std::string getUploadPath();

void setUploadPath(std::string path);

void uploadPicture(ImageData img);

std::vector<ImageData> listPicturesFromUploadPath();

ImageData getImageByName(std::string name);

// server connection methods here
// virtual methods for all possible camera actions
};

#endif // INCLUDE_CAMERA_INTERFACE_HPP_
39 changes: 36 additions & 3 deletions include/camera/lucid.hpp
Original file line number Diff line number Diff line change
@@ -1,14 +1,47 @@
#ifndef INCLUDE_CAMERA_LUCID_HPP_
#define INCLUDE_CAMERA_LUCID_HPP_

#ifdef ARENA_SDK_INSTALLED
// #ifdef ARENA_SDK_INSTALLED

#include <memory>

#include "camera/interface.hpp"

class LucidCamera : public CameraInterface {
// override all the camera connection interface functions
public:
LucidCamera();
~LucidCamera();

void connect();
bool isConnected();

void startTakingPictures(std::chrono::seconds interval) override;
void stopTakingPictures() override;

std::optional<ImageData> getLatestImage() override;
std::queue<ImageData> getAllImages() override;

private:
static std::shared_mutex arenaSystemLock;
static Arena::ISystem* pSystem;


std::atomic_bool isConnected;

std::atomic_bool isTakingPictures;

void captureEvery(std::chrono::seconds interval);

std::queue<ImageData> imageQueue;
std::shared_mutex imageQueueLock;

std::thread captureThread;

ImageData takePicture();
std::shared_mutex imageQueueMut;

};

#endif // ARENA_SDK_INSTALLED
// #endif // ARENA_SDK_INSTALLED

#endif // INCLUDE_CAMERA_LUCID_HPP_
29 changes: 21 additions & 8 deletions include/camera/mock.hpp
Original file line number Diff line number Diff line change
@@ -1,24 +1,37 @@
#ifndef INCLUDE_CAMERA_MOCK_HPP_
#define INCLUDE_CAMERA_MOCK_HPP_

#include <thread>
#include <memory>
#include <shared_mutex>

#include "camera/interface.hpp"

class MockCamera : public CameraInterface {
public:
explicit MockCamera(CameraConfiguration config);
~MockCamera() = default;
~MockCamera();

void connect() override;
bool verifyConnection() override;
void takePicture() override;
ImageData getLastPicture() override;
bool takePictureForSeconds(int sec) override;
void startTakingPictures(double intervalSec) override;
bool isDoneTakingPictures() override;
bool isConnected() override;

void startTakingPictures(std::chrono::seconds interval) override;
void stopTakingPictures() override;

std::optional<ImageData> getLatestImage() override;
std::queue<ImageData> getAllImages() override;

private:
std::unique_ptr<ImageData> lastPicture;
std::atomic_bool isTakingPictures;

void captureEvery(std::chrono::seconds interval);

std::queue<ImageData> imageQueue;
std::shared_mutex imageQueueLock;

std::thread captureThread;

ImageData takePicture();
};

#endif // INCLUDE_CAMERA_MOCK_HPP_
17 changes: 9 additions & 8 deletions include/pathing/cartesian.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <tuple>
#include <algorithm>
#include <limits>
#include "math.h"

#include "protos/obc.pb.h"
#include "utilities/datatypes.hpp"
Expand Down Expand Up @@ -34,13 +35,13 @@ class CartesianConverter {
this->center.set_longitude((min_lng + max_lng) / 2.0);

this->latlng_0.set_altitude(this->center.altitude());
this->latlng_0.set_latitude(this->center.latitude() * std::numbers::pi / 180.0);
this->latlng_0.set_longitude(this->center.longitude() * std::numbers::pi / 180.0);
this->latlng_0.set_latitude(this->center.latitude() * M_PI / 180.0);
this->latlng_0.set_longitude(this->center.longitude() * M_PI / 180.0);

// Essentially what is localizing us to this part of the globe
// "Standard Parallels"
this->phi_0 = (min_lat - 1) * std::numbers::pi / 180.0;
this->phi_1 = (max_lat + 1) * std::numbers::pi / 180.0;
this->phi_0 = (min_lat - 1) * M_PI / 180.0;
this->phi_1 = (max_lat + 1) * M_PI / 180.0;
}

GPSCoord toLatLng(XYZCoord coord) const {
Expand All @@ -52,15 +53,15 @@ class CartesianConverter {
std::pow(rho0 - coord.y, 2.0)) / EARTH_RADIUS_METERS;
double theta = std::atan(coord.x / (rho0 - coord.y));

double lat = std::asin((c - rho * rho * n * n) / 2.0 / n) * 180.0 / std::numbers::pi;
double lng = (this->latlng_0.longitude() + theta / n) * 180.0 / std::numbers::pi;
double lat = std::asin((c - rho * rho * n * n) / 2.0 / n) * 180.0 / M_PI;
double lng = (this->latlng_0.longitude() + theta / n) * 180.0 / M_PI;

return makeGPSCoord(lat, lng, coord.z);
}

XYZCoord toXYZ(GPSCoord coord) const {
double lat = coord.latitude() * std::numbers::pi / 180.0;
double lng = coord.longitude() * std::numbers::pi / 180.0;
double lat = coord.latitude() * M_PI / 180.0;
double lng = coord.longitude() * M_PI / 180.0;

double n = 1.0 / 2.0 * (std::sin(this->phi_0) + std::sin(this->phi_1));
double theta = n * (lng - this->latlng_0.longitude());
Expand Down
30 changes: 30 additions & 0 deletions src/camera/lucid.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#include "camera/lucid.hpp"

#include <chrono>
#include <thread>
#include <optional>

#include <loguru.hpp>

#include "utilities/locks.hpp"

LucidCamera::LucidCamera() {

}

LucidCamera::~LucidCamera() {

}

void LucidCamera::connect() {
WriteLock lock(this->arenaSystemLock)
pSystem = Arena::OpenSystem();
}

bool LucidCamera::isConnected();

void LucidCamera::startTakingPictures(std::chrono::seconds interval) override;
void LucidCamera::stopTakingPictures() override;

std::optional<ImageData> LucidCamera::getLatestImage() override;
std::queue<ImageData> LucidCamera::getAllImages() override;
Loading

0 comments on commit 77f70d0

Please sign in to comment.