Skip to content

Commit

Permalink
Merge pull request #1229 from fspindle/fix_various_changelog_warnings…
Browse files Browse the repository at this point in the history
…_spelling_pthread

Fix various changelog warnings spelling pthread
  • Loading branch information
fspindle authored Sep 7, 2023
2 parents 07da184 + 335d075 commit a32e92d
Show file tree
Hide file tree
Showing 20 changed files with 147 additions and 124 deletions.
4 changes: 3 additions & 1 deletion ChangeLog.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
ViSP 3.5.1 (under development)
- Contributors:
. Fabien Spindler, Souriya Trinh, Romain Lagneau, Antonio Marino, Samuel Felton,
Francois Chaumette, Olivier Roussel
Francois Chaumette, Olivier Roussel, Julien Dufour, Joudy Nader
- New classes
. vpMocapVicon an interface over Vicon motion capture system
. vpMocapQualisys an interface over Qualisys motion capture system
Expand Down Expand Up @@ -49,6 +49,7 @@ ViSP 3.5.1 (under development)
. In moving-edges ellipse tracker (vpMeEllipse and vpMbTracker and its derived classes),
change sample step parameter to consider the distance between moving-edges in pixels
rather than an angular value in deg as it was in the previous releases
. ViSP is available as a Conda package
- Tutorials
. New tutorial to list all the hardware (robot, camera, depth camera, lidar, mocap,
haptic devices, F/T sensor) supported by ViSP
Expand Down Expand Up @@ -99,6 +100,7 @@ ViSP 3.5.1 (under development)
. [#1160] MBT does not estimate dof set by the user using vpMbTracker::setEstimatedDoF()
. [#1176] ViSP cannot be built with a subset of OpenCV modules
. [#1198] Unable to save multiple cameras in a same xml file
. [#1228] Unable to use visp conda package to link visp as a 3rd party
----------------------------------------------
ViSP 3.5.0 (released February 15, 2022)
- Contributors:
Expand Down
16 changes: 16 additions & 0 deletions cmake/PCLTools.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -254,6 +254,7 @@ macro(vp_find_pcl pcl_libraries pcl_deps_include_dirs pcl_deps_libraries)

mark_as_advanced(ENSENSO_INCLUDE_DIR ENSENSO_LIBRARY)

mark_as_advanced(flann_DIR)
mark_as_advanced(FLANN_INCLUDE_DIR)
mark_as_advanced(FLANN_INCLUDE_DIRS)
mark_as_advanced(FLANN_LIBRARY)
Expand Down Expand Up @@ -295,6 +296,17 @@ macro(vp_find_pcl pcl_libraries pcl_deps_include_dirs pcl_deps_libraries)
mark_as_advanced(Qt5Quick_DIR) # Requested on macOS with pcl 1.12.1
mark_as_advanced(Qt5_DIR) # Requested on macOS with pcl 1.12.1

# Requested on macOS with pcl 1.13.1
mark_as_advanced(Qt6CoreTools_DIR Qt6Core_DIR Qt6BusTools_DIR Qt6GuiTools_DIR Qt6Gui_DIR Qt6OpenGLWidgets_DIR)
mark_as_advanced(Qt6OpenGL_DIR Qt6WidgetsTools_DIR Qt6Widgets_DIR)
mark_as_advanced(Qt6DBusTools_DIR Qt6DBus_DIR Qt6Network_DIR Qt6QmlCompilerPlusPrivate_DIR)
mark_as_advanced(Qt6QmlIntegration_DIR Qt6QmlModels_DIR Qt6QmlTools_DIR Qt6Qml_DIR Qt6Quick_DIR Qt6Sql_DIR)
mark_as_advanced(Qt6_DIR)
mark_as_advanced(QT_ADDITIONAL_HOST_PACKAGES_PREFIX_PATH)
mark_as_advanced(QT_ADDITIONAL_PACKAGES_PREFIX_PATH)
mark_as_advanced(MACDEPLOYQT_EXECUTABLE)
mark_as_advanced(WrapOpenGL_AGL)

mark_as_advanced(OPENNI2_INCLUDE_DIR)
mark_as_advanced(OPENNI2_INCLUDE_DIRS)
mark_as_advanced(OPENNI2_LIBRARY)
Expand All @@ -303,6 +315,9 @@ macro(vp_find_pcl pcl_libraries pcl_deps_include_dirs pcl_deps_libraries)
mark_as_advanced(OPENNI_INCLUDE_DIRS)
mark_as_advanced(OPENNI_LIBRARY)

mark_as_advanced(PCAP_INCLUDE_DIR) # Requested on macOS with pcl 1.13.1
mark_as_advanced(PCAP_LIBRARY) # Requested on macOS with pcl 1.13.1

mark_as_advanced(USB_10_INCLUDE_DIR)
mark_as_advanced(USB_10_LIBRARY)

Expand All @@ -325,6 +340,7 @@ macro(vp_find_pcl pcl_libraries pcl_deps_include_dirs pcl_deps_libraries)
mark_as_advanced(OPENGL_GLES3_INCLUDE_DIR)

mark_as_advanced(VTK_MPI_NUMPROCS)
mark_as_advanced(VTK_DIR) # Requested on macOS with pcl 1.12.1

mark_as_advanced(TBB_DIR)

Expand Down
8 changes: 4 additions & 4 deletions example/servo-universal-robots/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ if(VISP_HAVE_REALSENSE2)
list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unqualified-std-cast-call")
endif()

vp_set_source_file_compile_flag(servoUniversalRobotsIBVS.cpp ${CXX_FLAGS_MUTE_WARNINGS})
vp_set_source_file_compile_flag(servoUniversalRobotsPBVS.cpp ${CXX_FLAGS_MUTE_WARNINGS})
vp_set_source_file_compile_flag(UniversalRobotsMoveToPosition.cpp ${CXX_FLAGS_MUTE_WARNINGS})
vp_set_source_file_compile_flag(UniversalRobotsSavePosition.cpp ${CXX_FLAGS_MUTE_WARNINGS})
visp_set_source_file_compile_flag(servoUniversalRobotsIBVS.cpp ${CXX_FLAGS_MUTE_WARNINGS})
visp_set_source_file_compile_flag(servoUniversalRobotsPBVS.cpp ${CXX_FLAGS_MUTE_WARNINGS})
visp_set_source_file_compile_flag(UniversalRobotsMoveToPosition.cpp ${CXX_FLAGS_MUTE_WARNINGS})
visp_set_source_file_compile_flag(UniversalRobotsSavePosition.cpp ${CXX_FLAGS_MUTE_WARNINGS})
8 changes: 4 additions & 4 deletions modules/core/include/visp3/core/vpDisplay.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@
*
*****************************************************************************/

#ifndef vpDisplay_h
#define vpDisplay_h
#ifndef _vpDisplay_h_
#define _vpDisplay_h_

#include <list>
#include <sstream>
Expand Down Expand Up @@ -309,9 +309,9 @@ class VISP_EXPORT vpDisplay
when \e fill is set to false.
*/
inline virtual void displayCircle(const vpImageCircle &circle, const vpColor &color, bool fill = false,
unsigned int thickness = 1)
unsigned int thickness = 1)
{
this->displayCircle(circle.getCenter(), circle.getRadius(), color, fill, thickness);
this->displayCircle(circle.getCenter(), static_cast<unsigned int>(circle.getRadius()), color, fill, thickness);
}

/*!
Expand Down
35 changes: 20 additions & 15 deletions modules/core/include/visp3/core/vpImageFilter.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ class VISP_EXPORT vpImageFilter
{
public:
static void canny(const vpImage<unsigned char> &I, vpImage<unsigned char> &Ic, unsigned int gaussianFilterSize,
double thresholdCanny, unsigned int apertureSobel);
float thresholdCanny, unsigned int apertureSobel);

/*!
Apply a 1x3 derivative filter to an image pixel.
Expand Down Expand Up @@ -955,12 +955,14 @@ class VISP_EXPORT vpImageFilter
throw(vpImageException(vpImageException::incorrectInitializationError, "Bad Gaussian filter size"));

if (sigma <= 0)
sigma = (size - 1) / 6.0;
sigma = static_cast<FilterType>((size - 1) / 6.0);

int middle = (int)(size - 1) / 2;
FilterType sigma2 = vpMath::sqr(sigma);
FilterType sigma2 = static_cast<FilterType>(vpMath::sqr(sigma));
FilterType coef1 = static_cast<FilterType>(1. / (sigma * sqrt(2. * M_PI)));
FilterType _2_sigma2 = static_cast<FilterType>(2. * sigma2);
for (int i = 0; i <= middle; i++) {
filter[i] = (1. / (sigma * sqrt(2. * M_PI))) * exp(-(i * i) / (2. * sigma2));
filter[i] = coef1 * exp(-(i * i) / _2_sigma2);
}
if (normalize) {
// renormalization
Expand Down Expand Up @@ -997,22 +999,25 @@ class VISP_EXPORT vpImageFilter
throw(vpImageException(vpImageException::incorrectInitializationError, "Bad Gaussian filter size"));

if (sigma <= 0)
sigma = (size - 1) / 6.0;
sigma = static_cast<FilterType>((size - 1) / 6.0);

int middle = (int)(size - 1) / 2;
FilterType sigma2 = vpMath::sqr(sigma);
FilterType sigma2 = static_cast<FilterType>(vpMath::sqr(sigma));
FilterType coef_1 = static_cast<FilterType>(1. / (sigma * sqrt(2. * M_PI)));
FilterType coef_1_over_2 = coef_1 / static_cast<FilterType>(2.);
FilterType _2_coef_1 = static_cast<FilterType>(2.) * coef_1;
FilterType _2_sigma2 = static_cast<FilterType>(2. * sigma2);
filter[0] = 0.;
for (int i = 1; i <= middle; i++) {
filter[i] = -(1. / (sigma * sqrt(2. * M_PI))) *
(exp(-((i + 1) * (i + 1)) / (2. * sigma2)) - exp(-((i - 1) * (i - 1)) / (2. * sigma2))) / 2.;
filter[i] = -coef_1_over_2 * (static_cast<FilterType>(exp(-((i + 1) * (i + 1)) / _2_sigma2)) - static_cast<FilterType>(exp(-((i - 1) * (i - 1)) / _2_sigma2)));
}

if (normalize) {
FilterType sum = 0;
for (int i = 1; i <= middle; i++) {
sum += 2. * (1. / (sigma * sqrt(2. * M_PI))) * exp(-(i * i) / (2. * sigma2));
sum += _2_coef_1 * static_cast<FilterType>(exp(-(i * i) / _2_sigma2));
}
sum += (1. / (sigma * sqrt(2. * M_PI)));
sum += coef_1;

for (int i = 1; i <= middle; i++) {
filter[i] = filter[i] / sum;
Expand Down Expand Up @@ -1217,11 +1222,11 @@ class VISP_EXPORT vpImageFilter
}

#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC)
static double computeCannyThreshold(const cv::Mat &cv_I, const cv::Mat *p_cv_blur, double &lowerThresh);
static double computeCannyThreshold(const vpImage<unsigned char> &I, double &lowerThresh);
static double median(const cv::Mat &cv_I);
static double median(const vpImage<unsigned char> &Isrc);
static std::vector<double> median(const vpImage<vpRGBa> &Isrc);
static float computeCannyThreshold(const cv::Mat &cv_I, const cv::Mat *p_cv_blur, float &lowerThresh);
static float computeCannyThreshold(const vpImage<unsigned char> &I, float &lowerThresh);
static float median(const cv::Mat &cv_I);
static float median(const vpImage<unsigned char> &Isrc);
static std::vector<float> median(const vpImage<vpRGBa> &Isrc);
#endif
};

Expand Down
4 changes: 2 additions & 2 deletions modules/core/include/visp3/core/vpThread.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@
Windows.
There are two examples implemented in testMutex.cpp and testThread.cpp to
show how to use this class. The content of test-thread.cpp that hightlights
show how to use this class. The content of test-thread.cpp that highlights
the main functionalities of this class is given hereafter: \snippet
testThread.cpp Code
Expand All @@ -86,7 +86,7 @@ class vpThread
Default constructor that does nothing. To attach a function to this
thread of execution you need to call create().
*/
vpThread() : m_handle(), m_isCreated(false), m_isJoinable(false) {}
vpThread() : m_handle(), m_isCreated(false), m_isJoinable(false) { }

/*!
Construct a thread object that represents a new joinable thread of
Expand Down
2 changes: 1 addition & 1 deletion modules/core/src/display/vpDisplay_rgba.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ void vpDisplay::displayCharString(const vpImage<vpRGBa> &I, int i, int j, const
void vpDisplay::displayCircle(const vpImage<vpRGBa> &I, const vpImageCircle &circle,
const vpColor &color, bool fill, unsigned int thickness)
{
vp_display_display_circle(I, circle.getCenter(), circle.getRadius(), color, fill, thickness);
vp_display_display_circle(I, circle.getCenter(), static_cast<unsigned int>(circle.getRadius()), color, fill, thickness);
}

/*!
Expand Down
2 changes: 1 addition & 1 deletion modules/core/src/display/vpDisplay_uchar.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ void vpDisplay::displayCharString(const vpImage<unsigned char> &I, int i, int j,
void vpDisplay::displayCircle(const vpImage<unsigned char> &I, const vpImageCircle &circle,
const vpColor &color, bool fill, unsigned int thickness)
{
vp_display_display_circle(I, circle.getCenter(), circle.getRadius(), color, fill, thickness);
vp_display_display_circle(I, circle.getCenter(), static_cast<unsigned int>(circle.getRadius()), color, fill, thickness);
}

/*!
Expand Down
4 changes: 2 additions & 2 deletions modules/core/src/image/vpCannyEdgeDetection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ vpCannyEdgeDetection::detect(const vpImage<unsigned char> &I)
float lowerThreshold = m_lowerThreshold;
if (m_lowerThreshold < 0) {
// Applying Canny recommendation to have the upper threshold 3 times greater than the lower threshold.
lowerThreshold = m_upperThreshold / 3.;
lowerThreshold = m_upperThreshold / 3.f;
}

performHysteresisThresholding(lowerThreshold, upperThreshold);
Expand Down Expand Up @@ -269,7 +269,7 @@ getAbsoluteTheta(const vpImage<float> &dIx, const vpImage<float> &dIy, const int
absoluteTheta = 90.;
}
else {
absoluteTheta = vpMath::deg(std::abs(std::atan(dy / dx)));
absoluteTheta = static_cast<float>(vpMath::deg(std::abs(std::atan(dy / dx))));
}
return absoluteTheta;
}
Expand Down
39 changes: 20 additions & 19 deletions modules/core/src/image/vpImageFilter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,11 +148,11 @@ void vpImageFilter::sepFilter(const vpImage<unsigned char> &I, vpImage<double> &
* The algorithm is based on based on https://github.com/arnaudgelas/OpenCVExamples/blob/master/cvMat/Statistics/Median/Median.cpp
* \param[in] channel : Single channel image in OpenCV format.
*/
double vpImageFilter::median(const cv::Mat &channel)
float vpImageFilter::median(const cv::Mat &channel)
{
double m = (channel.rows * channel.cols) / 2;
float m = (channel.rows * channel.cols) / 2.f;
int bin = 0;
double med = -1.0;
float med = -1.0f;

int histSize = 256;
float range[] = { 0, 256 };
Expand All @@ -165,7 +165,7 @@ double vpImageFilter::median(const cv::Mat &channel)
for (int i = 0; i < histSize && med < 0.0; ++i) {
bin += cvRound(hist.at<float>(i));
if (bin > m && med < 0.0)
med = i;
med = static_cast<float>(i);
}

return med;
Expand All @@ -175,9 +175,10 @@ double vpImageFilter::median(const cv::Mat &channel)
* \brief Calculates the median value of a single channel.
* The algorithm is based on based on https://github.com/arnaudgelas/OpenCVExamples/blob/master/cvMat/Statistics/Median/Median.cpp
* \param[in] Isrc : Gray-level image in ViSP format.
* \return Gray level image median value.
* \sa \ref vpImageFilter::median() "vpImageFilter::median(const cv::Mat)"
*/
double vpImageFilter::median(const vpImage<unsigned char> &Isrc)
float vpImageFilter::median(const vpImage<unsigned char> &Isrc)
{
cv::Mat cv_I;
vpImageConvert::convert(Isrc, cv_I);
Expand All @@ -188,17 +189,17 @@ double vpImageFilter::median(const vpImage<unsigned char> &Isrc)
* \brief Calculates the median value of a vpRGBa image.
* The result is ordered in RGB format.
* \param[in] Isrc : RGB image in ViSP format. Alpha channel is ignored.
* \return std::vector<double> meds such as meds[0] = red-channel-median meds[1] = green-channel-median
* \return std::vector<float> meds such as meds[0] = red-channel-median, meds[1] = green-channel-median
* and meds[2] = blue-channel-median.
* \sa \ref vpImageFilter::median() "vpImageFilter::median(const cv::Mat)"
*/
std::vector<double> vpImageFilter::median(const vpImage<vpRGBa> &Isrc)
std::vector<float> vpImageFilter::median(const vpImage<vpRGBa> &Isrc)
{
cv::Mat cv_I_bgr;
vpImageConvert::convert(Isrc, cv_I_bgr);
std::vector<cv::Mat> channels;
cv::split(cv_I_bgr, channels);
std::vector<double> meds(3);
std::vector<float> meds(3);
const int orderMeds[] = { 2, 1, 0 }; // To keep the order R, G, B
const int orderCvChannels[] = { 0, 1, 2 }; // Because the order of the cv::Mat is B, G, R
for (unsigned int i = 0; i < 3; i++) {
Expand All @@ -213,9 +214,9 @@ std::vector<double> vpImageFilter::median(const vpImage<vpRGBa> &Isrc)
* \param[in] cv_I : The image, in cv format.
* \param[in] p_cv_blur : If different from nullptr, must contain a blurred version of cv_I.
* \param[out] lowerThresh : The lower threshold for the Canny edge filter.
* \return double The upper Canny edge filter threshold.
* \return The upper Canny edge filter threshold.
*/
double vpImageFilter::computeCannyThreshold(const cv::Mat &cv_I, const cv::Mat *p_cv_blur, double &lowerThresh)
float vpImageFilter::computeCannyThreshold(const cv::Mat &cv_I, const cv::Mat *p_cv_blur, float &lowerThresh)
{
cv::Mat cv_I_blur;
if (p_cv_blur != nullptr) {
Expand All @@ -232,10 +233,10 @@ double vpImageFilter::computeCannyThreshold(const cv::Mat &cv_I, const cv::Mat *
cv::Mat cv_I_scaled_down;
resize(cv_I_blur, cv_I_scaled_down, cv::Size(), scale_down, scale_down, cv::INTER_NEAREST);

double median_pix = vpImageFilter::median(cv_I_scaled_down);
double lower = std::max(0., 0.7 * median_pix);
double upper = std::min(255., 1.3 * median_pix);
upper = std::max(1., upper);
float median_pix = vpImageFilter::median(cv_I_scaled_down);
float lower = std::max(0.f, 0.7f * median_pix);
float upper = std::min(255.f, 1.3f * median_pix);
upper = std::max(1.f, upper);
lowerThresh = lower;
return upper;
}
Expand All @@ -245,9 +246,9 @@ double vpImageFilter::computeCannyThreshold(const cv::Mat &cv_I, const cv::Mat *
*
* \param[in] I : The gray-scale image, in ViSP format.
* \param[in] lowerThresh : Canny lower threshold.
* \return double The upper Canny edge filter threshold.
* \return The upper Canny edge filter threshold.
*/
double vpImageFilter::computeCannyThreshold(const vpImage<unsigned char> &I, double &lowerThresh)
float vpImageFilter::computeCannyThreshold(const vpImage<unsigned char> &I, float &lowerThresh)
{
cv::Mat cv_I;
vpImageConvert::convert(I, cv_I);
Expand Down Expand Up @@ -295,14 +296,14 @@ int main()
\param apertureSobel : Size of the mask for the Sobel operator (odd number).
*/
void vpImageFilter::canny(const vpImage<unsigned char> &Isrc, vpImage<unsigned char> &Ires,
unsigned int gaussianFilterSize, double thresholdCanny, unsigned int apertureSobel)
unsigned int gaussianFilterSize, float thresholdCanny, unsigned int apertureSobel)
{
#if defined(HAVE_OPENCV_IMGPROC)
cv::Mat img_cvmat, cv_I_blur, edges_cvmat;
vpImageConvert::convert(Isrc, img_cvmat);
cv::GaussianBlur(img_cvmat, cv_I_blur, cv::Size((int)gaussianFilterSize, (int)gaussianFilterSize), 0, 0);
double upperCannyThresh = thresholdCanny;
double lowerCannyThresh = thresholdCanny / 3.;
float upperCannyThresh = thresholdCanny;
float lowerCannyThresh = thresholdCanny / 3.f;
if (upperCannyThresh < 0) {
upperCannyThresh = computeCannyThreshold(img_cvmat, &cv_I_blur, lowerCannyThresh);
}
Expand Down
4 changes: 2 additions & 2 deletions modules/core/test/image-with-dataset/testImageFilter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -552,8 +552,8 @@ int main(int argc, const char *argv[])
I_median_rgba[r][c].B = 3 * (r * 3 + c);
}
}
std::vector<double> median_rgba = vpImageFilter::median(I_median_rgba);
std::vector<double> expected_median_rgba = { 4, 8, 12 };
std::vector<float> median_rgba = vpImageFilter::median(I_median_rgba);
std::vector<float> expected_median_rgba = { 4.f, 8.f, 12.f };
for (unsigned int i = 0; i < 3; i++) {
bool test_local = (median_rgba[i] == expected_median_rgba[i]);
test &= test_local;
Expand Down
1 change: 1 addition & 0 deletions modules/gui/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ if(USE_X11)
list(APPEND opt_libs ${X11_LIBRARIES})
mark_as_advanced(X11_xcb_icccm_INCLUDE_PATH)
mark_as_advanced(X11_xcb_icccm_LIB)
mark_as_advanced(X11_xcb_xkb_INCLUDE_PATH)
endif()
if(USE_GTK2)
list(APPEND opt_incs ${GTK2_INCLUDE_DIRS})
Expand Down
Loading

0 comments on commit a32e92d

Please sign in to comment.