Skip to content

Commit

Permalink
[master] Windows bring-up (#1704)
Browse files Browse the repository at this point in the history
* Windows bringup.

* nullity check.

* nullity check.
  • Loading branch information
seanyen committed May 13, 2020
1 parent 433c6ac commit 879a937
Show file tree
Hide file tree
Showing 40 changed files with 206 additions and 43 deletions.
14 changes: 13 additions & 1 deletion nav2_amcl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,9 @@ include_directories(
include
)

include(CheckSymbolExists)
check_symbol_exists(drand48 stdlib.h HAVE_DRAND48)

add_subdirectory(src/pf)
add_subdirectory(src/map)
add_subdirectory(src/motion_model)
Expand All @@ -39,6 +42,11 @@ add_library(${library_name} SHARED
src/amcl_node.cpp
)

target_include_directories(${library_name} PRIVATE src/include)
if(HAVE_DRAND48)
target_compile_definitions(${library_name} PRIVATE "HAVE_DRAND48")
endif()

set(dependencies
rclcpp
rclcpp_lifecycle
Expand Down Expand Up @@ -70,9 +78,13 @@ target_link_libraries(${library_name}
map_lib motions_lib sensors_lib
)

install(TARGETS ${executable_name} ${library_name}
install(TARGETS ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

install(TARGETS ${executable_name}
RUNTIME DESTINATION lib/${PROJECT_NAME}
)

Expand Down
2 changes: 2 additions & 0 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,8 @@
#include "tf2/utils.h"
#pragma GCC diagnostic pop

#include "portable_utils.h"

using namespace std::placeholders;
using namespace std::chrono_literals;

Expand Down
28 changes: 28 additions & 0 deletions nav2_amcl/src/include/portable_utils.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
#ifndef PORTABLE_UTILS_H
#define PORTABLE_UTILS_H

#include <stdlib.h>

#ifdef __cplusplus
extern "C" {
#endif

#ifndef HAVE_DRAND48
// Some system (e.g., Windows) doesn't come with drand48(), srand48().
// Use rand, and srand for such system.
static double drand48(void)
{
return ((double)rand()) / RAND_MAX;
}

static void srand48(long int seedval)
{
srand(seedval);
}
#endif

#ifdef __cplusplus
}
#endif

#endif
2 changes: 1 addition & 1 deletion nav2_amcl/src/map/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,5 +10,5 @@ install(TARGETS
map_lib
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
RUNTIME DESTINATION bin
)
2 changes: 1 addition & 1 deletion nav2_amcl/src/motion_model/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,5 +12,5 @@ install(TARGETS
motions_lib
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
RUNTIME DESTINATION bin
)
7 changes: 6 additions & 1 deletion nav2_amcl/src/pf/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,9 +11,14 @@ add_library(pf_lib SHARED
pf_draw.c
)

target_include_directories(pf_lib PRIVATE ../include)
if(HAVE_DRAND48)
target_compile_definitions(pf_lib PRIVATE "HAVE_DRAND48")
endif()

install(TARGETS
pf_lib
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
RUNTIME DESTINATION bin
)
7 changes: 5 additions & 2 deletions nav2_amcl/src/pf/eig3.c
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,11 @@
#define MAX(a, b) ((a) > (b) ? (a) : (b))
#endif

// #define n 3
static const int n = 3;
#ifdef _MSC_VER
#define n 3
#else
static int n = 3;
#endif

static double hypot2(double x, double y)
{
Expand Down
2 changes: 2 additions & 0 deletions nav2_amcl/src/pf/pf.c
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,8 @@
#include "nav2_amcl/pf/pf_pdf.hpp"
#include "nav2_amcl/pf/pf_kdtree.hpp"

#include "portable_utils.h"


// Compute the required number of samples, given that there are k bins
// with samples in them.
Expand Down
2 changes: 2 additions & 0 deletions nav2_amcl/src/pf/pf_pdf.c
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,8 @@

#include "nav2_amcl/pf/pf_pdf.hpp"

#include "portable_utils.h"

// Random number generator seed value
static unsigned int pf_pdf_seed;

Expand Down
4 changes: 2 additions & 2 deletions nav2_amcl/src/pf/pf_vector.c
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ int pf_vector_finite(pf_vector_t a)
int i;

for (i = 0; i < 3; i++) {
if (!finite(a.v[i])) {
if (!isfinite(a.v[i])) {
return 0;
}
}
Expand Down Expand Up @@ -152,7 +152,7 @@ int pf_matrix_finite(pf_matrix_t a)

for (i = 0; i < 3; i++) {
for (j = 0; j < 3; j++) {
if (!finite(a.m[i][j])) {
if (!isfinite(a.m[i][j])) {
return 0;
}
}
Expand Down
5 changes: 3 additions & 2 deletions nav2_amcl/src/sensors/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,12 @@ add_library(sensors_lib SHARED
laser/likelihood_field_model.cpp
laser/likelihood_field_model_prob.cpp
)
target_link_libraries(sensors_lib pf_lib)
# map_update_cspace
target_link_libraries(sensors_lib pf_lib map_lib)

install(TARGETS
sensors_lib
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
RUNTIME DESTINATION bin
)
1 change: 0 additions & 1 deletion nav2_amcl/src/sensors/laser/laser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
#include <math.h>
#include <stdlib.h>
#include <assert.h>
#include <unistd.h>

#include "nav2_amcl/sensors/laser/laser.hpp"

Expand Down
2 changes: 1 addition & 1 deletion nav2_behavior_tree/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ install(TARGETS ${library_name}
${plugin_libs}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
RUNTIME DESTINATION bin
)

install(DIRECTORY include/
Expand Down
6 changes: 5 additions & 1 deletion nav2_bt_navigator/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -60,9 +60,13 @@ ament_target_dependencies(${library_name}
${dependencies}
)

install(TARGETS ${executable_name} ${library_name}
install(TARGETS ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

install(TARGETS ${executable_name}
RUNTIME DESTINATION lib/${PROJECT_NAME}
)

Expand Down
4 changes: 4 additions & 0 deletions nav2_bt_navigator/src/ros_topic_logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,12 @@ void RosTopicLogger::callback(

// BT timestamps are a duration since the epoch. Need to convert to a time_point
// before converting to a msg.
#ifndef _WIN32
event.timestamp =
tf2_ros::toMsg(std::chrono::time_point<std::chrono::high_resolution_clock>(timestamp));
#else
event.timestamp = tf2_ros::toMsg(timestamp);
#endif
event.node_name = node.name();
event.previous_status = toStr(prev_status, false);
event.current_status = toStr(status, false);
Expand Down
12 changes: 12 additions & 0 deletions nav2_common/cmake/nav2_package.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -42,4 +42,16 @@ macro(nav2_package)
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} --coverage")
set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} --coverage")
endif()

# Defaults for Microsoft C++ compiler
if(MSVC)
# https://blog.kitware.com/create-dlls-on-windows-without-declspec-using-new-cmake-export-all-feature/
set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)

# Enable Math Constants
# https://docs.microsoft.com/en-us/cpp/c-runtime-library/math-constants?view=vs-2019
add_compile_definitions(
_USE_MATH_DEFINES
)
endif()
endmacro()
6 changes: 5 additions & 1 deletion nav2_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -59,9 +59,13 @@ ament_target_dependencies(${executable_name}

target_link_libraries(${executable_name} ${library_name})

install(TARGETS ${executable_name} ${library_name}
install(TARGETS ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

install(TARGETS ${executable_name}
RUNTIME DESTINATION lib/${PROJECT_NAME}
)

Expand Down
4 changes: 2 additions & 2 deletions nav2_controller/src/nav2_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
exit(-1);
}

for (uint i = 0; i != controller_types_.size(); i++) {
for (size_t i = 0; i != controller_types_.size(); i++) {
try {
nav2_core::Controller::Ptr controller =
lp_loader_.createUniqueInstance(controller_types_[i]);
Expand All @@ -105,7 +105,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
}
}

for (uint i = 0; i != controller_ids_.size(); i++) {
for (size_t i = 0; i != controller_ids_.size(); i++) {
controller_ids_concat_ += controller_ids_[i] + std::string(" ");
}

Expand Down
10 changes: 7 additions & 3 deletions nav2_costmap_2d/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -131,13 +131,17 @@ target_link_libraries(nav2_costmap_2d

install(TARGETS
nav2_costmap_2d_core
nav2_costmap_2d
layers
nav2_costmap_2d_client
nav2_costmap_2d_markers
nav2_costmap_2d_cloud
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

install(TARGETS
nav2_costmap_2d
nav2_costmap_2d_markers
nav2_costmap_2d_cloud
RUNTIME DESTINATION lib/${PROJECT_NAME}
)

Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/costmap_queue/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ endif()
install(TARGETS ${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
RUNTIME DESTINATION bin
)
install(DIRECTORY include/
DESTINATION include/
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/dwb_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ ament_target_dependencies(dwb_core
install(TARGETS dwb_core
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
RUNTIME DESTINATION bin
)

install(DIRECTORY include/
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/dwb_critics/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ ament_target_dependencies(${PROJECT_NAME}
install(TARGETS ${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
RUNTIME DESTINATION bin
)
install(DIRECTORY include/
DESTINATION include/
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/dwb_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ endif()
install(TARGETS simple_goal_checker stopped_goal_checker standard_traj_generator
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
RUNTIME DESTINATION bin
)
install(DIRECTORY include/
DESTINATION include/
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/nav_2d_utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ ament_target_dependencies(path_ops
install(TARGETS conversions path_ops
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
RUNTIME DESTINATION bin
)
install(DIRECTORY include/
DESTINATION include/
Expand Down
6 changes: 5 additions & 1 deletion nav2_lifecycle_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -57,10 +57,14 @@ ament_target_dependencies(lifecycle_manager
)

install(TARGETS
lifecycle_manager
${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

install(TARGETS
lifecycle_manager
RUNTIME DESTINATION lib/${PROJECT_NAME}
)

Expand Down
18 changes: 16 additions & 2 deletions nav2_map_server/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,11 @@ target_link_libraries(${library_name}
target_link_libraries(${map_server_executable}
${library_name})

if(WIN32)
target_compile_definitions(${map_server_executable} PRIVATE
YAML_CPP_DLL)
endif()

target_link_libraries(${map_saver_cli_executable}
${library_name})

Expand All @@ -100,10 +105,19 @@ target_include_directories(${map_io_library_name} SYSTEM PRIVATE
target_link_libraries(${map_io_library_name}
${GRAPHICSMAGICKCPP_LIBRARIES})

install(TARGETS ${map_server_executable} ${library_name} ${map_io_library_name}
${map_saver_cli_executable} ${map_saver_server_executable}
if(WIN32)
target_compile_definitions(${map_io_library_name} PRIVATE
YAML_CPP_DLL)
endif()

install(TARGETS
${library_name} ${map_io_library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)

install(TARGETS
${map_server_executable} ${map_saver_cli_executable} ${map_saver_server_executable}
RUNTIME DESTINATION lib/${PROJECT_NAME})

install(DIRECTORY include/
Expand Down
4 changes: 2 additions & 2 deletions nav2_map_server/cmake_modules/FindGRAPHICSMAGICKCPP.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -26,9 +26,9 @@ find_path(GRAPHICSMAGICKCPP_INCLUDE_DIRS
PATH_SUFFIXES GraphicsMagick)

find_library(GRAPHICSMAGICKCPP_LIBRARIES
NAMES "GraphicsMagick++")
NAMES "GraphicsMagick++" "graphicsmagick")

find_package_handle_standard_args(
GRAPHICSMAGICKCPP
GRAPHICSMAGICKCPP__LIBRARIES
GRAPHICSMAGICKCPP_LIBRARIES
GRAPHICSMAGICKCPP_INCLUDE_DIRS)
Loading

0 comments on commit 879a937

Please sign in to comment.