Skip to content
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

Fixes for Windows #439

Open
wants to merge 4 commits into
base: foxy-devel
Choose a base branch
from
Open

Conversation

Ace314159
Copy link

Basic Info

Info Please fill out this column
Ticket(s) this addresses N/A
Primary OS tested on Windows
Robotic platform tested on I didn't test, just built the library

Description of contribution in a few bullet points

  • Builds on Windows now

Description of documentation updates required from your changes

N/A


Future work that may be required in bullet points

None, I think it all works on Windows

* Replace uint with unsigned int
* Export symbols by defining KARTO_DYNAMIC
* Don't set compiler flags that don't exist on MSVC
Undef NO_ERROR from windows headers
* Define _USE_MATH_DEFINES for M_PI
* Export all symbols for toolbox_common and other libraries
* Set stack size on compile time since there's no Windows equivalent
Use Sleep instead of sleep in Windows
rviz_plugin/slam_toolbox_rviz_plugin.hpp Show resolved Hide resolved
target_link_libraries(async_slam_toolbox toolbox_common kartoSlamToolbox ${Boost_LIBRARIES})
add_executable(async_slam_toolbox_node src/slam_toolbox_async_node.cpp)
if(MSVC)
target_compile_options(async_slam_toolbox_node PRIVATE "/F 40000000")
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm not familiar with this /F 40000000, can you explain me this?

@@ -29,6 +29,9 @@ int main(int argc, char ** argv)
auto temp_node = std::make_shared<rclcpp::Node>("slam_toolbox");
temp_node->declare_parameter("stack_size_to_use");
if (temp_node->get_parameter("stack_size_to_use", stack_size)) {
#ifdef _WIN32
RCLCPP_WARN(temp_node->get_logger(), "Can't dynamically change stack size on Windows. Node using stack size 40000000");
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is there another API to change the stack size then? This is kind of an important element for serialization / deserialization of large maps

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

From my research, I wasn't able to find a way to dynamically change the stack size of the program at runtime on Windows. However, I was able to find a way to change the stack size when a thread is created here.

Do you think it would be possible to utilize this functionality instead? Or, instead of serializing and deserializing maps on the stack, is it possible to use dynamic memory, just for Windows?

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It uses boost serialization, so that's totally out of our control where that memory is located for serialization.

So are you suggesting we serialize/deserialize in another thread that in instantiation we set the max size on? That would need some testing on your end to validate, but I could approve that.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Instead of putting only the serialization/deserialization on a separate thread, it might be easier to just put the entire node in a separate thread. Do you think that would be fine too?

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would not like to do that, that would add an extra thread for everyone for all of run-time, versus only an extra thread on serialization/deserialization processes

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I see, that makes sense! Would I just have to modify SlamToolbox::serializePoseGraphCallback and SlamToolbox::loadSerializedPoseGraph? Are there any other functions that do the serialization and deserialization?

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yup, that's right

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do you have any large serialized maps I can use for testing? In the README, I saw a mention about a map from Circuit Launch. Would it be possible to give me access to that or another map?

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

None that I can share publicly

@SteveMacenski
Copy link
Owner

Same with the Nav2 PR: needs a ros2 branch for main as well

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants