Skip to content

Commit

Permalink
make 3 times to fully compile
Browse files Browse the repository at this point in the history
  • Loading branch information
root committed Dec 29, 2023
1 parent e564d96 commit 315f729
Show file tree
Hide file tree
Showing 5 changed files with 6 additions and 7 deletions.
2 changes: 1 addition & 1 deletion include/Grid3D/grid3d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
#include <nav_msgs/OccupancyGrid.h>
#include <std_msgs/Float32.h>
#include <std_msgs/Int32MultiArray.h>
#include <heuristic_planners/GetSemanticGrid.h>
#include <stdio.h>
// PCL
#include <pcl/point_cloud.h>
Expand All @@ -29,6 +28,7 @@
#include <iomanip> //for std::setw, std::hex, and std::setfill
#include <openssl/evp.h> //for all other OpenSSL function calls
#include <openssl/sha.h> //for SHA512_DIGEST_LENGTH
#include <heuristic_planners/GetSemanticGrid.h>
// #include "utils/ros/ROSInterfaces.hpp"

// #ifdef BUILD_VORONOI
Expand Down
2 changes: 1 addition & 1 deletion launch/grid3d.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,6 @@
<param name="world_size_x" value="212" />
<param name="world_size_y" value="170" />
<param name="world_size_z" value="9" />
<param name="resolution" value="0.2" />
<param name="resolution" value="0.1" />
</node>
</launch>
4 changes: 2 additions & 2 deletions launch/simulator_atlas.launch
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
<!-- <arg name="map_name" default="manufacturing"/> -->
<!-- ATLAS -->
<!-- <arg name="map_name" default="Atlas_8_300"/> -->
<arg name="map_name" default="Atlas_8_floor_1kk"/>
<arg name="map_name" default="Atlas_8_300"/>
<!-- <arg name="map_name" default="nube_de_puntos2"/> -->
<!-- <arg name="map_name" default="nube_de_puntos_con_etiquetas"/> -->
<arg name="map" default="$(find heuristic_planners)/resources/3dmaps/$(arg map_name).bt"/>
Expand All @@ -34,7 +34,7 @@
<!-- <arg name="world_size_z" default="5"/> -->
<!-- <arg name="world_size_z" default="2"/> manufacturing -->
<arg name="world_size_z" default="9"/> <!-- 6 -->
<arg name="resolution" default="0.1"/>
<arg name="resolution" default="0.2"/>

<arg name="inflate_map" default="true"/>
<arg name="inflation_size" default="$(arg resolution)"/>
Expand Down
1 change: 1 addition & 0 deletions src/ROS/planner_ros_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include <heuristic_planners/GetPath.h>
#include <heuristic_planners/SetAlgorithm.h>


/**
* @brief Demo Class that demonstrate how to use the algorithms classes and utils
* with ROS
Expand Down
4 changes: 1 addition & 3 deletions src/utils/ros/ROSInterfaces.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,9 +135,7 @@ namespace Planners
auto world_size = _algorithm.getWorldSize();
auto resolution = _algorithm.getWorldResolution();

std::cout << "Semantic Layer " << std::endl;

for (int i = 0; i < world_size.x; i++)
std::cout << "Semantic Layer " << std::endl;
for (int i = 0; i < world_size.x; i++)
{
for (int j = 0; j < world_size.y; j++)
Expand Down

0 comments on commit 315f729

Please sign in to comment.