-
Notifications
You must be signed in to change notification settings - Fork 91
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
[Windows][melodic-devel] Windows\MSVC port #239
base: melodic-devel
Are you sure you want to change the base?
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,16 @@ | ||
#ifndef DESCARTES_CORE_EXPORT_H_ | ||
#define DESCARTES_CORE_EXPORT_H_ | ||
|
||
#include <ros/macros.h> | ||
|
||
#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries | ||
#ifdef descartes_core_EXPORTS // we are building a shared lib/dll | ||
#define DESCARTES_CORE_DECL ROS_HELPER_EXPORT | ||
#else // we are using shared lib/dll | ||
#define DESCARTES_CORE_DECL ROS_HELPER_IMPORT | ||
#endif | ||
#else // ros is being built around static libraries | ||
#define DESCARTES_CORE_DECL | ||
#endif | ||
|
||
#endif |
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -64,7 +64,7 @@ bool PlanningGraph::insertGraph(const std::vector<TrajectoryPtPtr>& points) | |
|
||
// now we have a graph with data in the 'rungs' and we need to compute the edges | ||
#pragma omp parallel for | ||
for (std::size_t i = 0; i < graph_.size() - 1; ++i) | ||
for (int i = 0; i < graph_.size() - 1; ++i) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Why change the iterator type? |
||
{ | ||
computeAndAssignEdges(i, i + 1); | ||
} | ||
|
@@ -190,7 +190,7 @@ bool PlanningGraph::calculateJointSolutions(const TrajectoryPtPtr* points, const | |
bool success = true; | ||
|
||
#pragma omp parallel for shared(success) | ||
for (std::size_t i = 0; i < count; ++i) | ||
for (int i = 0; i < count; ++i) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Why change the iterator datatype here? |
||
{ | ||
if (success) | ||
{ | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,7 +1,11 @@ | ||
cmake_minimum_required(VERSION 2.8.11) | ||
project(descartes_trajectory) | ||
|
||
add_compile_options(-std=c++11 -Wall -Wextra) | ||
if(NOT MSVC) | ||
add_compile_options(-std=c++11 -Wall -Wextra) | ||
else() | ||
add_definitions(-D__PRETTY_FUNCTION__=__FUNCTION__) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. What does this definition do? |
||
endif() | ||
|
||
find_package(catkin REQUIRED COMPONENTS | ||
cmake_modules | ||
|
@@ -63,7 +67,9 @@ target_link_libraries(${PROJECT_NAME} | |
|
||
install( | ||
TARGETS ${PROJECT_NAME} | ||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) | ||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} | ||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} | ||
RUNTIME DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) | ||
|
||
install( | ||
DIRECTORY include/${PROJECT_NAME}/ | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I'm not too familiar with MSVC toolchains so could you explain why this is needed?