Skip to content

Commit

Permalink
Added simplify_map feature, as well as benchmark. New simplify_map ca…
Browse files Browse the repository at this point in the history
…n speed up performance 10-20%, and is baseline faster at =0
  • Loading branch information
josephduchesne committed May 7, 2024
1 parent 238bc03 commit 6601c65
Show file tree
Hide file tree
Showing 19 changed files with 444 additions and 39 deletions.
6 changes: 4 additions & 2 deletions docs/core_functions/ros_launch.rst
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,14 @@ Here are the full list of parameters with the default values
step_size:=0.005 \
show_viz:=true \
viz_pub_rate:=30.0 \
use_rviz:=false
use_rviz:=false \
simplify_map:=2
* **world_path**: path to world.yaml
* **update_rate**: the real time rate to run the simulation loop in Hz
* **step_size**: amount of time to step each loop in seconds
* **show_viz**: show visualization, pops the flatland_viz window and publishes
visualization messages, either true or false
* **viz_pub_rate**: rate to publish visualization in Hz, works only when show_viz=true
* **use_rviz**: works only when show_viz=true, set this to disable flatland_viz popup
* **use_rviz**: works only when show_viz=true, set this to disable flatland_viz popup
* **simplify_map**: Simpify map during vector tracing: 0=None (default), 1=moderately, 2=significantly
2 changes: 1 addition & 1 deletion flatland_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.0.2)
project(flatland_plugins)

# Ensure we're using c++11
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -O3")
set(CMAKE_BUILD_TYPE RelWithDebInfo)

## Find catkin macros and libraries
Expand Down
20 changes: 19 additions & 1 deletion flatland_server/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.0.2)
project(flatland_server)

# Ensure we're using c++11
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17 -O3")

set(CMAKE_BUILD_TYPE RelWithDebInfo)

Expand Down Expand Up @@ -73,6 +73,7 @@ catkin_package(
include_directories(
thirdparty
include
thirdparty/Clipper2Lib/CPP/Clipper2Lib/include
${catkin_INCLUDE_DIRS}
${YAML_CPP_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
Expand Down Expand Up @@ -139,6 +140,23 @@ target_link_libraries(flatland_server
flatland_lib
)

## Add benchmark non-installed binary
add_executable(flatland_benchmark src/flatland_benchmark.cpp)
add_dependencies(flatland_benchmark ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Specify libraries to link a library or executable target against
target_link_libraries(flatland_benchmark
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
${Boost_LIBRARIES}
${LUA_LIBRARIES}
Threads::Threads
flatland_Box2D
yaml-cpp
flatland_lib
)


#############
## Install ##
#############
Expand Down
3 changes: 1 addition & 2 deletions flatland_server/include/flatland_server/layer.h
Original file line number Diff line number Diff line change
Expand Up @@ -151,10 +151,9 @@ class Layer : public Entity {
* @param[in] bitmap OpenCV Image
* @param[in] occupied_thresh Threshold indicating obstacle if above
* @param[in] resolution Resolution of the map image in meters per pixel
* @param[in] simplify Simplification factor: 0=None, 1=moderate, 2=significant
*/
void LoadFromBitmap(const cv::Mat &bitmap, double occupied_thresh,
double resolution, int simplify=0);
double resolution);

/**
* @brief Visualize layer for debugging purposes
Expand Down
5 changes: 4 additions & 1 deletion flatland_server/include/flatland_server/simulation_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,8 @@ class SimulationManager {
bool show_viz_; ///< flag to determine if to show visualization
double viz_pub_rate_; ///< rate to publish visualization
std::string world_yaml_file_; ///< path to the world file
Timekeeper timekeeper_; ///< Timekeeper manager
uint64_t iterations_ = 0; ///< Main loop iteration count (for debugging/profiling)

/**
* @name Simulation Manager constructor
Expand All @@ -79,8 +81,9 @@ class SimulationManager {

/**
* This method contains the loop that runs the simulation
* @param[in] benchmark optional, default false, ignore update timer (run as fast as possible)
*/
void Main();
void Main(bool benchmark=false);

/**
* Kill the world
Expand Down
33 changes: 33 additions & 0 deletions flatland_server/launch/benchmark.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
<launch>

<!--
You can override these default values:
roslaunch flatland_Server server.launch world_path:="/some/world.yaml" initial_rate:="30.0"
-->
<arg name="world_path" default="$(find flatland_server)/test/benchmark_world/world.yaml"/>
<arg name="update_rate" default="200.0"/>
<arg name="step_size" default="0.005"/>
<arg name="benchmark_duration" default="60.0"/>
<arg name="use_perf" default="false" />
<arg name="show_viz" default="true" />
<arg name="simplify_map" default="2" /> <!-- 0=None, 1=moderately, 2=significantly-->

<env name="ROSCONSOLE_FORMAT" value="[${severity} ${time} ${logger}]: ${message}" />

<param name="use_sim_time" value="true"/>

<!-- launch flatland benchmark -->
<!-- /usr/lib/linux-tools/5.4.0-173-generic/perf on my local container -->
<node name="flatland_benchmark" pkg="flatland_server" type="flatland_benchmark" output="screen" required="true"
launch-prefix="$(eval 'perf record --call-graph dwarf --output=perf.out.flatland_benchmark.data --' if arg('use_perf') else '')"
>
<!-- Use the arguments passed into the launchfile for this node -->
<param name="world_path" value="$(arg world_path)" />
<param name="update_rate" value="$(arg update_rate)" />
<param name="step_size" value="$(arg step_size)" />
<param name="show_viz" value="$(arg show_viz)" />
<param name="benchmark_duration" value="$(arg benchmark_duration)" />
<param name="simplify_map" value="$(arg simplify_map)" />
</node>

</launch>
2 changes: 1 addition & 1 deletion flatland_server/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>flatland_server</name>
<version>1.4.1</version>
<version>1.5.0</version>
<description>The flatland_server package</description>
<license>BSD</license>
<url type="website">https://bitbucket.org/avidbots/flatland</url>
Expand Down
136 changes: 136 additions & 0 deletions flatland_server/src/flatland_benchmark.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,136 @@
/*
* ______ __ __ __
* /\ _ \ __ /\ \/\ \ /\ \__
* \ \ \L\ \ __ __ /\_\ \_\ \ \ \____ ___\ \ ,_\ ____
* \ \ __ \/\ \/\ \\/\ \ /'_` \ \ '__`\ / __`\ \ \/ /',__\
* \ \ \/\ \ \ \_/ |\ \ \/\ \L\ \ \ \L\ \/\ \L\ \ \ \_/\__, `\
* \ \_\ \_\ \___/ \ \_\ \___,_\ \_,__/\ \____/\ \__\/\____/
* \/_/\/_/\/__/ \/_/\/__,_ /\/___/ \/___/ \/__/\/___/
* @copyright Copyright 2024 Avidbots Corp.
* @name flatland_benchmark.cpp
* @brief Benchmark version of flatland_server
* @author Joseph Duchesne
*
* Software License Agreement (BSD License)
*
* Copyright (c) 2024, Avidbots Corp.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Avidbots Corp. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#include <ros/ros.h>
#include <signal.h>
#include <string>

#include "flatland_server/simulation_manager.h"

/** Global variables */
flatland_server::SimulationManager *simulation_manager;
double benchmark_duration = 10.0; // overwritten by rosparam "benchmark_duration" if set
double benchmark_start = 0.0f;

/**
* @name SigintHandler
* @brief Interrupt handler - sends shutdown signal to simulation_manager
* @param[in] sig: signal itself
*/
void SigintHandler(int sig) {
ROS_WARN_NAMED("Benchmark", "*** Shutting down... ***");

if (simulation_manager != nullptr) {
simulation_manager->Shutdown();
delete simulation_manager;
simulation_manager = nullptr;
}
ROS_INFO_STREAM_NAMED("Benchmark", "Beginning ros shutdown");
ros::shutdown();
}

void CheckTimeout(const ros::WallTimerEvent& timer_event) {
double elapsed = simulation_manager->timekeeper_.GetSimTime().toSec();
if (elapsed >= benchmark_duration) {
double bench_time = ros::WallTime::now().toSec() - benchmark_start;
ROS_INFO_NAMED("Benchmark", "Benchmark complete. Ran %ld iterations in %.3f sec; %.3f iter/sec. Shutting down.",
simulation_manager->iterations_, bench_time, (double)(simulation_manager->iterations_)/bench_time);
ros::shutdown();
}
ROS_INFO_THROTTLE_NAMED(1.0, "Benchmark", "Elapsed: %.1f/%.1f.", elapsed, benchmark_duration);
}

/**
* @name main
* @brief Entrypoint for Flatland Server ros node
*/
int main(int argc, char **argv) {
ros::init(argc, argv, "flatland", ros::init_options::NoSigintHandler);
ros::NodeHandle node_handle("~");

// todo: Load default parameters, run on a specific (default incl.) map for N seconds, then report.

// Load parameters
std::string world_path; // The file path to the world.yaml file
if (!node_handle.getParam("world_path", world_path)) {
ROS_FATAL_NAMED("Benchmark", "No world_path parameter given!");
ros::shutdown();
return 1;
}

float update_rate = 200.0; // The physics update rate (Hz)
node_handle.getParam("update_rate", update_rate);

float step_size = 1 / 200.0;
node_handle.getParam("step_size", step_size);

bool show_viz = false;
node_handle.getParam("show_viz", show_viz);

float viz_pub_rate = 30.0;
node_handle.getParam("viz_pub_rate", viz_pub_rate);

node_handle.getParam("benchmark_duration", benchmark_duration);

// Create simulation manager object
simulation_manager = new flatland_server::SimulationManager(
world_path, update_rate, step_size, show_viz, viz_pub_rate);

// Register sigint shutdown handler
signal(SIGINT, SigintHandler);

// timeout
ros::WallTimer timeout_timer = node_handle.createWallTimer(ros::WallDuration(0.01), &CheckTimeout);

ROS_INFO_STREAM_NAMED("Benchmark", "Initialized");
benchmark_start = ros::WallTime::now().toSec();
simulation_manager->Main(/*benchmark=*/true);

ROS_INFO_STREAM_NAMED("Benchmark", "Returned from simulation manager main");
delete simulation_manager;
simulation_manager = nullptr;
return 0;
}
2 changes: 1 addition & 1 deletion flatland_server/src/flatland_server_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
* \ \_\ \_\ \___/ \ \_\ \___,_\ \_,__/\ \____/\ \__\/\____/
* \/_/\/_/\/__/ \/_/\/__,_ /\/___/ \/___/ \/__/\/___/
* @copyright Copyright 2017 Avidbots Corp.
* @name flatland_server_ndoe.cpp
* @name flatland_server_node.cpp
* @brief Load params and run the ros node for flatland_server
* @author Joseph Duchesne
*
Expand Down
10 changes: 6 additions & 4 deletions flatland_server/src/layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -218,7 +218,7 @@ void Layer::ReadLineSegmentsFile(const std::string &file_path,
}

void Layer::LoadFromBitmap(const cv::Mat &bitmap, double occupied_thresh,
double resolution, int simplify) {
double resolution) {
uint16_t category_bits = cfr_->GetCategoryBits(names_);

uint32_t edges_added = 0;
Expand Down Expand Up @@ -251,11 +251,13 @@ void Layer::LoadFromBitmap(const cv::Mat &bitmap, double occupied_thresh,
// considered to be occupied
cv::inRange(bitmap, occupied_thresh, 1.0, obstacle_map);

// TODO: Make simplification a parameter
// simplify_map rosparam: 0=None, 1=moderate, 2=maximum simplification of map polygon outlines
int simplify = 0;
ros::param::param<int>("simplify_map", simplify, 0);

std::vector<std::vector<cv::Point>> vectors_outline;
cv::Mat obstacle_map_open;
if (simplify >= 1) {
if (simplify >= 2) {
int open_kernel_size = 3; // 0.15m at 5cm pixel resolution
cv::Mat kernel = cv::getStructuringElement( cv::MORPH_ELLIPSE, {open_kernel_size*2+1, open_kernel_size*2+1});
cv::morphologyEx(obstacle_map, obstacle_map_open, cv::MORPH_OPEN, kernel);
Expand All @@ -271,7 +273,7 @@ void Layer::LoadFromBitmap(const cv::Mat &bitmap, double occupied_thresh,
std::vector<cv::Point2f>& poly_to_use = polygon2f;


if (simplify >= 2) {
if (simplify >= 1) {
std::vector<cv::Point2f> polygon_rdp;
cv::approxPolyDP(polygon2f, polygon_rdp, 1.0, true); // RDP reduction
if (polygon_rdp.size()>4) poly_to_use = polygon_rdp;
Expand Down
Loading

0 comments on commit 6601c65

Please sign in to comment.