Skip to content

Commit e03ba40

Browse files
committed
2.5.0
1 parent 9ef3f2e commit e03ba40

File tree

16 files changed

+229
-179
lines changed

16 files changed

+229
-179
lines changed

.gitignore

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,6 @@
1+
log
2+
.vscode
3+
14
**/gas_simulations
25
*_U
36
*_V

Changelog.md

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,10 @@
1+
## 2.5.0
2+
### Major changes
3+
- Added support for [BasicSim](https://github.com/PepeOjeda/BasicSim). The preprocessing node now automatically generates a valid BasicSim scene yaml, and the main_simbot launchfile has an argument to let you select BasicSim as the robotic simulator.
4+
5+
### Minor changes
6+
- Improved CMakelists build mode configuration and changed some of the fatal errors in `gaden_player` to raise `SIGTRAP` instead of calling `exit()` for easier debugging
7+
18
## 2.4.0
29
### Major changes
310
- Simulation YAML files in the `test_env` directory are now more powerful than ever! You can define any ROS argument per-simulation, so a configuration does not need to be shared between all simulations in a given scenario. However, if you want to add a new parameter to the simulation YAML, you will also need to modify the shared YAML (under the `params` directory) to tell it to use the value that was read from the simulation file -- like this:

gaden_common/include/gaden_common/Logging.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,9 @@
1212
#define GADEN_INFO(...) RCLCPP_INFO(rclcpp::get_logger(GADEN_LOGGER_ID), fmt::format(__VA_ARGS__).c_str())
1313
#define GADEN_INFO_COLOR(color,...) RCLCPP_INFO(rclcpp::get_logger(GADEN_LOGGER_ID), fmt::format(fmt::fg(color),__VA_ARGS__).c_str())
1414

15-
#define GADEN_WARN(...) RCLCPP_WARN(rclcpp::get_logger(GADEN_LOGGER_ID), fmt::format(fmt::fg(fmt::terminal_color::yellow), __VA_ARGS__).c_str())
15+
#define GADEN_WARN(...) RCLCPP_WARN(rclcpp::get_logger(GADEN_LOGGER_ID), fmt::format(__VA_ARGS__).c_str())
1616

17-
#define GADEN_ERROR(...) RCLCPP_ERROR(rclcpp::get_logger(GADEN_LOGGER_ID), fmt::format(fmt::fg(fmt::terminal_color::red), __VA_ARGS__).c_str())
17+
#define GADEN_ERROR(...) RCLCPP_ERROR(rclcpp::get_logger(GADEN_LOGGER_ID), fmt::format(__VA_ARGS__).c_str())
1818

1919
#if GADEN_TRACING
2020
#define GADEN_TRACE(...) RCLCPP_INFO(rclcpp::get_logger(GADEN_LOGGER_ID"-Trace"), fmt::format(fmt::fg(fmt::terminal_color::green), __VA_ARGS__).c_str())

gaden_environment/CMakeLists.txt

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,13 @@ cmake_minimum_required(VERSION 3.5)
22
project(gaden_environment)
33

44
##################
5-
set(CMAKE_BUILD_TYPE "None")
6-
set(CMAKE_CXX_FLAGS "-std=c++17 -g -O2 ${CMAKE_CXX_FLAGS}")
5+
set(CMAKE_BUILD_TYPE "Release")
6+
set(CMAKE_CXX_FLAGS_RELEASE "-O3 ${CMAKE_CXX_FLAGS}")
7+
set(CMAKE_CXX_FLAGS_DEBUG "-g -O0 ${CMAKE_CXX_FLAGS}")
8+
9+
10+
set(CMAKE_CXX_STANDARD 17)
11+
712

813

914
find_package(ament_cmake REQUIRED)

gaden_filament_simulator/CMakeLists.txt

Lines changed: 5 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,13 @@
11
cmake_minimum_required(VERSION 3.5)
22
project(gaden_filament_simulator)
33

4-
set(CMAKE_BUILD_TYPE "None")
4+
set(CMAKE_BUILD_TYPE "Release")
5+
set(CMAKE_CXX_FLAGS_RELEASE "-O3 ${CMAKE_CXX_FLAGS}")
6+
set(CMAKE_CXX_FLAGS_DEBUG "-g -O0 ${CMAKE_CXX_FLAGS}")
57

6-
set(CMAKE_CXX_FLAGS "-std=c++17 -fopenmp ${CMAKE_CXX_FLAGS}")
7-
set(DEBUG OFF)
88

9-
if(DEBUG)
10-
add_definitions(-DDEBUG)
11-
set(CMAKE_CXX_FLAGS "-g -O0 ${CMAKE_CXX_FLAGS}")
12-
else()
13-
set(CMAKE_CXX_FLAGS "-O3 ${CMAKE_CXX_FLAGS}")
14-
endif(DEBUG)
9+
set(CMAKE_CXX_STANDARD 17)
10+
1511

1612

1713

gaden_player/CMakeLists.txt

Lines changed: 4 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,18 +1,12 @@
11
cmake_minimum_required(VERSION 3.5)
22
project(gaden_player)
33

4-
set(CMAKE_BUILD_TYPE "None")
5-
set(CMAKE_CXX_FLAGS "-std=c++17 ${CMAKE_CXX_FLAGS}")
4+
set(CMAKE_BUILD_TYPE "Release")
5+
set(CMAKE_CXX_FLAGS_RELEASE "-O3 ${CMAKE_CXX_FLAGS}")
6+
set(CMAKE_CXX_FLAGS_DEBUG "-g -O0 ${CMAKE_CXX_FLAGS}")
67

7-
set(DEBUG ON)
8-
9-
if(DEBUG)
10-
add_definitions(-DDEBUG)
11-
set(CMAKE_CXX_FLAGS "-g -O0 ${CMAKE_CXX_FLAGS}")
12-
else()
13-
set(CMAKE_CXX_FLAGS "-O3 ${CMAKE_CXX_FLAGS}")
14-
endif(DEBUG)
158

9+
set(CMAKE_CXX_STANDARD 17)
1610

1711

1812
find_package(ament_cmake REQUIRED)

gaden_player/src/simulation_player.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -247,7 +247,7 @@ sim_obj::sim_obj(std::string filepath, bool load_wind_info, std::string occupanc
247247
if (!std::filesystem::exists(simulation_filename))
248248
{
249249
GADEN_ERROR("Simulation folder does not exist: {}", simulation_filename.c_str());
250-
exit(-1);
250+
raise(SIGTRAP);
251251
}
252252
}
253253

@@ -582,12 +582,12 @@ void sim_obj::configure_environment()
582582
if (result == Gaden::ReadResult::NO_FILE)
583583
{
584584
GADEN_ERROR("No occupancy file provided to Gaden-player node!");
585-
exit(-1);
585+
raise(SIGTRAP);
586586
}
587587
else if (result == Gaden::ReadResult::READING_FAILED)
588588
{
589589
GADEN_ERROR("Something went wrong while parsing the file!");
590-
exit(-1);
590+
raise(SIGTRAP);
591591
}
592592
}
593593

gaden_preprocessing/CMakeLists.txt

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -7,18 +7,18 @@ set(CMAKE_CXX_FLAGS "-std=c++17 -fopenmp ${CMAKE_CXX_FLAGS}")
77
# OPTIONS!
88
#==============================================
99
set(GENERATE_COPPELIA_SCENE OFF)
10-
set(DEBUG OFF)
1110
#==============================================
1211

1312

1413

1514

16-
if(DEBUG)
17-
add_definitions(-DDEBUG)
18-
set(CMAKE_CXX_FLAGS "-g -O0 ${CMAKE_CXX_FLAGS}")
19-
else()
20-
set(CMAKE_CXX_FLAGS "-O3 ${CMAKE_CXX_FLAGS}")
21-
endif()
15+
set(CMAKE_BUILD_TYPE "Release")
16+
set(CMAKE_CXX_FLAGS_RELEASE "-O3 ${CMAKE_CXX_FLAGS}")
17+
set(CMAKE_CXX_FLAGS_DEBUG "-g -O0 ${CMAKE_CXX_FLAGS}")
18+
19+
20+
set(CMAKE_CXX_STANDARD 17)
21+
2222

2323

2424

@@ -30,6 +30,7 @@ set(AMENT_DEPS
3030
tf2_geometry_msgs
3131
std_msgs
3232
gaden_common
33+
yaml_cpp_vendor
3334
)
3435

3536
if(GENERATE_COPPELIA_SCENE)

gaden_preprocessing/include/gaden_preprocessing/Gaden_preprocessing.h

Lines changed: 8 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -79,12 +79,13 @@ class Gaden_preprocessing : public rclcpp::Node
7979
bool isASCII(const std::string& filename);
8080

8181
bool compare_cell(int x, int y, int z, cell_state value);
82-
void changeWorldFile(const std::string& filename);
83-
void printMap(std::string filename, int scale, bool block_outlets);
84-
void printEnv(std::string filename, int scale);
85-
void printWind(const std::vector<double>& U, const std::vector<double>& V, const std::vector<double>& W, std::string filename);
82+
void changeStageWorldFile(const std::string& filename);
83+
void printOccupancyMap(std::string filename, int scale, bool block_outlets);
84+
void printOccupancyYaml(std::string outputFolder);
85+
void printBasicSimYaml(std::string outputFolder);
86+
void printGadenEnvFile(std::string filename, int scale);
87+
void printWindFiles(const std::vector<double>& U, const std::vector<double>& V, const std::vector<double>& W, std::string filename);
8688

87-
void printYaml(std::string output);
8889
std::array<tf2::Vector3, 9> cubePoints(const tf2::Vector3& query_point);
8990
bool pointInTriangle(const tf2::Vector3& query_point, const tf2::Vector3& triangle_vertex_0, const tf2::Vector3& triangle_vertex_1,
9091
const tf2::Vector3& triangle_vertex_2);
@@ -103,34 +104,12 @@ class Gaden_preprocessing : public rclcpp::Node
103104

104105
namespace Utils
105106
{
106-
float min_val(float x, float y, float z)
107-
{
108-
109-
float min = x;
110-
if (y < min)
111-
min = y;
112-
if (z < min)
113-
min = z;
114-
115-
return min;
116-
}
117-
float max_val(float x, float y, float z)
118-
{
119-
120-
float max = x;
121-
if (y > max)
122-
max = y;
123-
if (z > max)
124-
max = z;
125-
126-
return max;
127-
}
128-
bool eq(float x, float y)
107+
inline bool eq(float x, float y)
129108
{
130109
return std::abs(x - y) < 0.01;
131110
}
132111

133-
bool isParallel(const tf2::Vector3& vec)
112+
inline bool isParallel(const tf2::Vector3& vec)
134113
{
135114
return (eq(vec.y(), 0) && eq(vec.z(), 0)) || (eq(vec.x(), 0) && eq(vec.z(), 0)) || (eq(vec.x(), 0) && eq(vec.y(), 0));
136115
}

0 commit comments

Comments
 (0)