Skip to content

Commit

Permalink
fixed formatting and cmake
Browse files Browse the repository at this point in the history
  • Loading branch information
slimeth committed Dec 1, 2020
1 parent b3219b3 commit 16fd627
Show file tree
Hide file tree
Showing 2 changed files with 48 additions and 56 deletions.
8 changes: 0 additions & 8 deletions flightlib/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -50,13 +50,6 @@ include(cmake/yaml.cmake)
find_package(OpenCV REQUIRED)
find_package(OpenMP REQUIRED)

if(OPENMP_FOUND)
message("OPENMP FOUND")
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}")
endif()

if(ENABLE_BLAS)
set(BLA_VENDOR "Generic")
find_package(BLAS REQUIRED)
Expand Down Expand Up @@ -209,7 +202,6 @@ else()
add_library(${PROJECT_NAME} ${FLIGHTLIB_SOURCES})
target_link_libraries(${PROJECT_NAME} PRIVATE
${OpenCV_LIBRARIES}
openmp
yaml-cpp
zmq
zmqpp
Expand Down
96 changes: 48 additions & 48 deletions flightlib/src/bridges/unity_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -217,55 +217,55 @@ bool UnityBridge::handleOutput() {
layer_idx++) {
if (!layer_idx == 0 && !cam.enabled_layers[layer_idx - 1]) continue;

if(layer_idx==1)
{
// depth
uint32_t image_len = cam.width * cam.height * 4;
// Get raw image bytes from ZMQ message.
// WARNING: This is a zero-copy operation that also casts the input to
// an array of unit8_t. when the message is deleted, this pointer is
// also dereferenced.
const uint8_t* image_data;
msg.get(image_data, image_i);
image_i = image_i + 1;
// Pack image into cv::Mat
cv::Mat new_image =
cv::Mat(cam.height, cam.width, CV_32FC1);
memcpy(new_image.data, image_data, image_len);
// Flip image since OpenCV origin is upper left, but Unity's is lower
// left.
new_image = new_image * (100.f);
cv::flip(new_image, new_image, 0);


unity_quadrotors_[idx]->getCameras()[cam.output_index]->feedImageQueue(
layer_idx, new_image);


}else{
uint32_t image_len = cam.width * cam.height * cam.channels;
// Get raw image bytes from ZMQ message.
// WARNING: This is a zero-copy operation that also casts the input to
// an array of unit8_t. when the message is deleted, this pointer is
// also dereferenced.
const uint8_t* image_data;
msg.get(image_data, image_i);
image_i = image_i + 1;
// Pack image into cv::Mat
cv::Mat new_image =
cv::Mat(cam.height, cam.width, CV_MAKETYPE(CV_8U, cam.channels));
memcpy(new_image.data, image_data, image_len);
// Flip image since OpenCV origin is upper left, but Unity's is lower
// left.
cv::flip(new_image, new_image, 0);

// Tell OpenCv that the input is RGB.
if (cam.channels == 3) {
cv::cvtColor(new_image, new_image, CV_RGB2BGR);
if (layer_idx == 1) {
// depth
uint32_t image_len = cam.width * cam.height * 4;
// Get raw image bytes from ZMQ message.
// WARNING: This is a zero-copy operation that also casts the input to
// an array of unit8_t. when the message is deleted, this pointer is
// also dereferenced.
const uint8_t* image_data;
msg.get(image_data, image_i);
image_i = image_i + 1;
// Pack image into cv::Mat
cv::Mat new_image = cv::Mat(cam.height, cam.width, CV_32FC1);
memcpy(new_image.data, image_data, image_len);
// Flip image since OpenCV origin is upper left, but Unity's is lower
// left.
new_image = new_image * (100.f);
cv::flip(new_image, new_image, 0);


unity_quadrotors_[idx]
->getCameras()[cam.output_index]
->feedImageQueue(layer_idx, new_image);


} else {
uint32_t image_len = cam.width * cam.height * cam.channels;
// Get raw image bytes from ZMQ message.
// WARNING: This is a zero-copy operation that also casts the input to
// an array of unit8_t. when the message is deleted, this pointer is
// also dereferenced.
const uint8_t* image_data;
msg.get(image_data, image_i);
image_i = image_i + 1;
// Pack image into cv::Mat
cv::Mat new_image =
cv::Mat(cam.height, cam.width, CV_MAKETYPE(CV_8U, cam.channels));
memcpy(new_image.data, image_data, image_len);
// Flip image since OpenCV origin is upper left, but Unity's is lower
// left.
cv::flip(new_image, new_image, 0);

// Tell OpenCv that the input is RGB.
if (cam.channels == 3) {
cv::cvtColor(new_image, new_image, CV_RGB2BGR);
}
unity_quadrotors_[idx]
->getCameras()[cam.output_index]
->feedImageQueue(layer_idx, new_image);
}
unity_quadrotors_[idx]->getCameras()[cam.output_index]->feedImageQueue(
layer_idx, new_image);
}
}
}
}
Expand Down

0 comments on commit 16fd627

Please sign in to comment.