Skip to content

Commit

Permalink
Fixes for Windows into main (#2603) (#2606)
Browse files Browse the repository at this point in the history
* Fix nav2_util

* Don't include libgen.h on Windows
* Replace sleep with Sleep on Windows

* Fix rviz plugin

Undef NO_ERROR from windows headers

* Fix smac_planner

* Define _USE_MATH_DEFINES for M_PI
* Replace uint with unsigned int
* Don't add compiler flags that aren't supported on MSVC
* Use vector instead of VLA when building with MSVC

* Fix dirname for \ paths

* Fix typo

* Fix linter

(cherry picked from commit 82ce6ca)

Co-authored-by: Akash <[email protected]>
  • Loading branch information
mergify[bot] and Ace314159 authored Oct 14, 2021
1 parent 5d23326 commit f88c467
Show file tree
Hide file tree
Showing 8 changed files with 40 additions and 9 deletions.
7 changes: 7 additions & 0 deletions nav2_map_server/src/map_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,13 @@ char * dirname(char * path)
return path;
}

/* Replace all "\" with "/" */
char * c = path;
while (*c != '\0') {
if (*c == '\\') {*c = '/';}
++c;
}

/* Find last '/'. */
last_slash = path != NULL ? strrchr(path, '/') : NULL;

Expand Down
1 change: 1 addition & 0 deletions nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include <QtWidgets>
#include <QBasicTimer>
#undef NO_ERROR

#include <memory>
#include <string>
Expand Down
6 changes: 5 additions & 1 deletion nav2_smac_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,11 @@ endif()

set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")

add_compile_options(-O3 -Wextra -Wdeprecated -fPIC)
if(MSVC)
add_compile_definitions(_USE_MATH_DEFINES)
else()
add_compile_options(-O3 -Wextra -Wdeprecated -fPIC)
endif()

include_directories(
include
Expand Down
8 changes: 4 additions & 4 deletions nav2_smac_planner/src/costmap_downsampler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,8 +90,8 @@ nav2_costmap_2d::Costmap2D * CostmapDownsampler::downsample(
}

// Assign costs
for (uint i = 0; i < _downsampled_size_x; ++i) {
for (uint j = 0; j < _downsampled_size_y; ++j) {
for (unsigned int i = 0; i < _downsampled_size_x; ++i) {
for (unsigned int j = 0; j < _downsampled_size_y; ++j) {
setCostOfCell(i, j);
}
}
Expand Down Expand Up @@ -130,12 +130,12 @@ void CostmapDownsampler::setCostOfCell(
unsigned int x_offset = new_mx * _downsampling_factor;
unsigned int y_offset = new_my * _downsampling_factor;

for (uint i = 0; i < _downsampling_factor; ++i) {
for (unsigned int i = 0; i < _downsampling_factor; ++i) {
mx = x_offset + i;
if (mx >= _size_x) {
continue;
}
for (uint j = 0; j < _downsampling_factor; ++j) {
for (unsigned int j = 0; j < _downsampling_factor; ++j) {
my = y_offset + j;
if (my >= _size_y) {
continue;
Expand Down
11 changes: 8 additions & 3 deletions nav2_smac_planner/test/deprecated/smoother.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,8 +105,13 @@ class Smoother
{
_options.max_solver_time_in_seconds = params.max_time;

double parameters[path.size() * 2]; // NOLINT
for (uint i = 0; i != path.size(); i++) {
#ifdef _MSC_VER
std::vector<double> parameters_vec(path.size() * 2);
double * parameters = parameters_vec.data();
#else
double parameters[path.size() * 2]; // NOLINT
#endif
for (unsigned int i = 0; i != path.size(); i++) {
parameters[2 * i] = path[i][0];
parameters[2 * i + 1] = path[i][1];
}
Expand All @@ -123,7 +128,7 @@ class Smoother
return false;
}

for (uint i = 0; i != path.size(); i++) {
for (unsigned int i = 0; i != path.size(); i++) {
path[i][0] = parameters[2 * i];
path[i][1] = parameters[2 * i + 1];
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ class UnconstrainedSmootherCostFunction : public ceres::FirstOrderFunction
Eigen::Vector2d xi;
Eigen::Vector2d xi_p1;
Eigen::Vector2d xi_m1;
uint x_index, y_index;
unsigned int x_index, y_index;
cost[0] = 0.0;
double cost_raw = 0.0;
double grad_x_raw = 0.0;
Expand Down
2 changes: 2 additions & 0 deletions nav2_util/src/dump_params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,9 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef _WIN32
#include <libgen.h>
#endif

#include <iomanip>
#include <iostream>
Expand Down
12 changes: 12 additions & 0 deletions nav2_util/test/test_lifecycle_cli_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,10 @@
#include "nav2_util/node_thread.hpp"
#include "rclcpp/rclcpp.hpp"

#ifdef _WIN32
#include <windows.h>
#endif

class DummyNode : public nav2_util::LifecycleNode
{
public:
Expand Down Expand Up @@ -80,7 +84,11 @@ TEST(LifeycleCLI, fails_no_node_name)
Handle handle;
auto rc = system("ros2 run nav2_util lifecycle_bringup");
(void)rc;
#ifdef _WIN32
Sleep(1000);
#else
sleep(1);
#endif
// check node didn't mode
EXPECT_EQ(handle.node->activated, false);
SUCCEED();
Expand All @@ -90,7 +98,11 @@ TEST(LifeycleCLI, succeeds_node_name)
{
Handle handle;
auto rc = system("ros2 run nav2_util lifecycle_bringup nav2_test_cli");
#ifdef _WIN32
Sleep(3000);
#else
sleep(3);
#endif
// check node moved
(void)rc;
EXPECT_EQ(handle.node->activated, true);
Expand Down

0 comments on commit f88c467

Please sign in to comment.