Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 10 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra)
add_compile_options(-Wno-deprecated)
endif()

find_package(ament_cmake REQUIRED)
Expand All @@ -27,6 +28,12 @@ endif()

include(ExternalProject)

if(WIN32)
set(patch_exe patch.exe)
else()
set(patch_exe patch)
endif()

ExternalProject_Add(astra_openni2
PREFIX astra_openni2
# SOURCE_DIR ${CMAKE_CURRENT_SOURCE_DIR}/astra_openni2/OpenNI2
Expand All @@ -38,6 +45,9 @@ ExternalProject_Add(astra_openni2
BUILD_COMMAND make release FILTER=${obfilter}
INSTALL_DIR openni2
INSTALL_COMMAND tar -xjf <SOURCE_DIR>/Packaging/Final/OpenNI-Linux-2.3.tar.bz2 -C <INSTALL_DIR> --strip 1 && mkdir -p <INSTALL_DIR>/include && ln -fs <INSTALL_DIR>/Include <INSTALL_DIR>/include/openni2
PATCH_COMMAND
${patch_exe} -p1 -N < ${CMAKE_CURRENT_SOURCE_DIR}/astra_openni2-patch.diff

)

link_directories(${CMAKE_CURRENT_BINARY_DIR}/openni2/Redist)
Expand Down
100 changes: 100 additions & 0 deletions astra_openni2-patch.diff
Original file line number Diff line number Diff line change
@@ -0,0 +1,100 @@
diff --git a/Source/Drivers/orbbec/Formats/XnFormatsMirror.cpp b/Source/Drivers/orbbec/Formats/XnFormatsMirror.cpp
index bbbf213..cc8bfe0 100644
--- a/Source/Drivers/orbbec/Formats/XnFormatsMirror.cpp
+++ b/Source/Drivers/orbbec/Formats/XnFormatsMirror.cpp
@@ -43,8 +43,14 @@ XnStatus XnMirrorOneBytePixels(XnUChar* pBuffer, XnUInt32 nBufferSize, XnUInt32
XnUInt8* pSrcEnd = pSrc + nBufferSize;
XnUInt8* pDest = NULL;
XnUInt8* pDestVal = &pLineBuffer[0] + nLineSize - 1;
+#ifndef _WIN32
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Warray-bounds"
+#endif
XnUInt8* pDestEnd = &pLineBuffer[0] - 1;
-
+#ifndef _WIN32
+#pragma GCC diagnostic pop
+#endif
if (nLineSize > XN_MIRROR_MAX_LINE_SIZE)
{
return (XN_STATUS_INTERNAL_BUFFER_TOO_SMALL);
@@ -76,7 +82,14 @@ XnStatus XnMirrorTwoBytePixels(XnUChar* pBuffer, XnUInt32 nBufferSize, XnUInt32
XnUInt16* pSrcEnd = pSrc + nBufferSize / sizeof(XnUInt16);
XnUInt16* pDest = NULL;
XnUInt16* pDestVal = &pLineBuffer[0] + nLineSize - 1;
+#ifndef _WIN32
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Warray-bounds"
+#endif
XnUInt16* pDestEnd = &pLineBuffer[0] - 1;
+#ifndef _WIN32
+#pragma GCC diagnostic pop
+#endif
XnUInt16 nMemCpyLineSize = (XnUInt16)(nLineSize * sizeof(XnUInt16));
XnUInt16 nValue;

@@ -112,7 +125,14 @@ XnStatus XnMirrorThreeBytePixels(XnUChar* pBuffer, XnUInt32 nBufferSize, XnUInt3
XnUInt8* pSrcEnd = pSrc + nBufferSize;
XnUInt8* pDest = NULL;
XnUInt8* pDestVal = &pLineBuffer[0] + nLineSize * 3 - 1;
+#ifndef _WIN32
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Warray-bounds"
+#endif
XnUInt8* pDestEnd = &pLineBuffer[0] - 1;
+#ifndef _WIN32
+#pragma GCC diagnostic pop
+#endif
XnUInt16 nMemCpyLineSize = (XnUInt16)(nLineSize * 3);

if (nMemCpyLineSize > XN_MIRROR_MAX_LINE_SIZE)
diff --git a/Source/Drivers/orbbec/Sensor/XnFrameStreamProcessor.cpp b/Source/Drivers/orbbec/Sensor/XnFrameStreamProcessor.cpp
index d6105ec..fc459e3 100644
--- a/Source/Drivers/orbbec/Sensor/XnFrameStreamProcessor.cpp
+++ b/Source/Drivers/orbbec/Sensor/XnFrameStreamProcessor.cpp
@@ -28,6 +28,10 @@
//---------------------------------------------------------------------------
// Code
//---------------------------------------------------------------------------
+#ifndef _WIN32
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wformat-overflow="
+#endif
XnFrameStreamProcessor::XnFrameStreamProcessor(XnFrameStream* pStream, XnSensorStreamHelper* pHelper, XnFrameBufferManager* pBufferManager, XnUInt16 nTypeSOF, XnUInt16 nTypeEOF) :
XnStreamProcessor(pStream, pHelper),
m_nTypeSOF(nTypeSOF),
@@ -45,6 +49,9 @@ XnFrameStreamProcessor::XnFrameStreamProcessor(XnFrameStream* pStream, XnSensorS
m_InDump = xnDumpFileOpen(m_csInDumpMask, "%s_0.raw", m_csInDumpMask);
m_InternalDump = xnDumpFileOpen(m_csInternalDumpMask, "%s_0.raw", m_csInternalDumpMask);
}
+#ifndef _WIN32
+#pragma GCC diagnostic pop
+#endif

XnFrameStreamProcessor::~XnFrameStreamProcessor()
{
diff --git a/Source/Drivers/orbbec/Sensor/XnSensorFirmwareParams.cpp b/Source/Drivers/orbbec/Sensor/XnSensorFirmwareParams.cpp
index 476b88d..7046b76 100644
--- a/Source/Drivers/orbbec/Sensor/XnSensorFirmwareParams.cpp
+++ b/Source/Drivers/orbbec/Sensor/XnSensorFirmwareParams.cpp
@@ -251,6 +251,10 @@ void XnSensorFirmwareParams::Free()
m_AllFirmwareParams.Clear();
}

+#ifndef _WIN32
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wformat-overflow="
+#endif
XnStatus XnSensorFirmwareParams::AddFirmwareParam(XnActualIntProperty& Property, XnUInt16 nFirmwareParam, XnFWVer nMinVer /* = XN_SENSOR_FW_VER_UNKNOWN */, XnFWVer nMaxVer /* = XN_SENSOR_FW_VER_UNKNOWN */, XnUInt16 nValueIfNotSupported /* = 0 */)
{
XnStatus nRetVal = XN_STATUS_OK;
@@ -275,6 +279,9 @@ XnStatus XnSensorFirmwareParams::AddFirmwareParam(XnActualIntProperty& Property,

return (XN_STATUS_OK);
}
+#ifndef _WIN32
+#pragma GCC diagnostic pop
+#endif

XnStatus XnSensorFirmwareParams::AddFirmwareAudioParam(XnActualIntProperty& Property, XnUInt16 nFirmwareParam, XnFWVer nMinVer /* = XN_SENSOR_FW_VER_3_0 */, XnFWVer nMaxVer /* = XN_SENSOR_FW_VER_UNKNOWN */, XnUInt16 nValueIfNotSupported /* = 0 */)
{
4 changes: 2 additions & 2 deletions src/astra_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,8 +103,8 @@ AstraDriver::AstraDriver(rclcpp::Node::SharedPtr& n, rclcpp::Node::SharedPtr& pn
}
shm = (char *)shmat(shmid, 0, 0);
while( *shm!=bootOrder);
initDevice();
ROS_WARN("*********** device_id %s already open device************************ ", device_id_.c_str());
initDevice();
ROS_WARN("*********** device_id %s already open device************************ ", device_id_.c_str());
*shm = (bootOrder+1);
}
if( bootOrder==1 )
Expand Down
3 changes: 2 additions & 1 deletion src/astra_frame_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include "astra_camera/ros12_shim.h"
#include "openni2/OpenNI.h"

#include <cmath>
#include <rcl/time.h>
#include <sensor_msgs/image_encodings.hpp>

Expand Down Expand Up @@ -103,7 +104,7 @@ void AstraFrameListener::onNewFrame(openni::VideoStream& stream)
double corrected_timestamp = device_time_in_sec+filtered_time_diff;

//image->header.stamp.fromSec(corrected_timestamp);
image->header.stamp.sec = floor(corrected_timestamp);
image->header.stamp.sec = std::floor(corrected_timestamp);
image->header.stamp.nanosec = (corrected_timestamp - floor(corrected_timestamp)) * 1000000000;

ROS_DEBUG("Time interval between frames: %.4f ms", (float)((corrected_timestamp-prev_time_stamp_)*1000.0));
Expand Down