Skip to content

Commit

Permalink
refactor(costmap_generator): add autoware prefix
Browse files Browse the repository at this point in the history
Signed-off-by: kosuke55 <[email protected]>
  • Loading branch information
kosuke55 committed Jun 7, 2024
1 parent 2b7c0db commit 59a204b
Show file tree
Hide file tree
Showing 20 changed files with 64 additions and 37 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -153,6 +153,7 @@ planning/autoware_behavior_velocity_run_out_module/** [email protected] m
planning/autoware_behavior_velocity_template_module/** [email protected]
planning/autoware_behavior_velocity_virtual_traffic_light_module/** [email protected] [email protected] [email protected]
planning/autoware_behavior_velocity_walkway_module/** [email protected] [email protected] [email protected] [email protected]
planning/autoware_costmap_generator/** [email protected] [email protected] [email protected]
planning/autoware_external_velocity_limit_selector/** [email protected] [email protected] [email protected] [email protected] [email protected]
planning/autoware_path_optimizer/** [email protected] [email protected] [email protected]
planning/autoware_planning_test_manager/** [email protected] [email protected]
Expand Down Expand Up @@ -183,7 +184,6 @@ planning/autoware_behavior_velocity_run_out_module/** [email protected] m
planning/behavior_velocity_speed_bump_module/** [email protected] [email protected] [email protected]
planning/behavior_velocity_stop_line_module/** [email protected] [email protected] [email protected] [email protected]
planning/behavior_velocity_traffic_light_module/** [email protected] [email protected] [email protected] [email protected]
planning/costmap_generator/** [email protected] [email protected] [email protected]
planning/freespace_planner/** [email protected] [email protected] [email protected]
planning/freespace_planning_algorithms/** [email protected] [email protected] [email protected]
planning/mission_planner/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<push-ros-namespace namespace="parking"/>

<node_container pkg="rclcpp_components" exec="$(var container_type)" name="parking_container" namespace="" output="screen">
<composable_node pkg="costmap_generator" plugin="CostmapGenerator" name="costmap_generator" namespace="">
<composable_node pkg="autoware_costmap_generator" plugin="autoware::costmap_generator::CostmapGenerator" name="costmap_generator" namespace="">
<!-- topic remap -->
<remap from="~/input/objects" to="/perception/object_recognition/objects"/>
<remap from="~/input/points_no_ground" to="/perception/obstacle_segmentation/pointcloud"/>
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_planning_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<exec_depend>autoware_behavior_velocity_planner</exec_depend>
<exec_depend>autoware_costmap_generator</exec_depend>
<exec_depend>autoware_external_velocity_limit_selector</exec_depend>
<exec_depend>autoware_path_optimizer</exec_depend>
<exec_depend>autoware_planning_topic_converter</exec_depend>
Expand All @@ -66,7 +67,6 @@
<exec_depend>autoware_surround_obstacle_checker</exec_depend>
<exec_depend>autoware_velocity_smoother</exec_depend>
<exec_depend>behavior_path_planner</exec_depend>
<exec_depend>costmap_generator</exec_depend>
<exec_depend>external_cmd_selector</exec_depend>
<exec_depend>freespace_planner</exec_depend>
<exec_depend>glog_component</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -526,7 +526,7 @@ If a safe path cannot be generated from the current position, search backwards f
### **freespace pull out**

If the vehicle gets stuck with pull out along lanes, execute freespace pull out.
To run this feature, you need to set `parking_lot` to the map, `activate_by_scenario` of [costmap_generator](../costmap_generator/README.md) to `false` and `enable_freespace_planner` to `true`
To run this feature, you need to set `parking_lot` to the map, `activate_by_scenario` of [costmap_generator](../autoware_costmap_generator/README.md) to `false` and `enable_freespace_planner` to `true`

<img src="https://user-images.githubusercontent.com/39142679/270964106-ae688bca-1709-4e06-98c4-90f671bb8246.png" width="600">

Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(costmap_generator)
project(autoware_costmap_generator)

find_package(autoware_cmake REQUIRED)
autoware_package()
Expand All @@ -16,9 +16,9 @@ include_directories(
)

ament_auto_add_library(costmap_generator_lib SHARED
nodes/costmap_generator/points_to_costmap.cpp
nodes/costmap_generator/objects_to_costmap.cpp
nodes/costmap_generator/object_map_utils.cpp
nodes/autoware_costmap_generator/points_to_costmap.cpp
nodes/autoware_costmap_generator/objects_to_costmap.cpp
nodes/autoware_costmap_generator/object_map_utils.cpp
)
target_link_libraries(costmap_generator_lib
${PCL_LIBRARIES}
Expand All @@ -33,15 +33,15 @@ if(${PCL_VERSION} GREATER_EQUAL 1.12.1)
endif()

ament_auto_add_library(costmap_generator_node SHARED
nodes/costmap_generator/costmap_generator_node.cpp
nodes/autoware_costmap_generator/costmap_generator_node.cpp
)
target_link_libraries(costmap_generator_node
${PCL_LIBRARIES}
costmap_generator_lib
)

rclcpp_components_register_node(costmap_generator_node
PLUGIN "CostmapGenerator"
PLUGIN "autoware::costmap_generator::CostmapGenerator"
EXECUTABLE costmap_generator
)

Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -42,11 +42,11 @@
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
********************/

#ifndef COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_
#define COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_
#ifndef AUTOWARE_COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_
#define AUTOWARE_COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_

#include "costmap_generator/objects_to_costmap.hpp"
#include "costmap_generator/points_to_costmap.hpp"
#include "autoware_costmap_generator/objects_to_costmap.hpp"
#include "autoware_costmap_generator/points_to_costmap.hpp"

#include <grid_map_ros/GridMapRosConverter.hpp>
#include <grid_map_ros/grid_map_ros.hpp>
Expand All @@ -72,6 +72,8 @@
#include <string>
#include <vector>

namespace autoware::costmap_generator
{
class CostmapGenerator : public rclcpp::Node
{
public:
Expand Down Expand Up @@ -197,5 +199,6 @@ class CostmapGenerator : public rclcpp::Node
/// \brief calculate cost for final output
grid_map::Matrix generateCombinedCostmap();
};
} // namespace autoware::costmap_generator

#endif // COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_
#endif // AUTOWARE_COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@
*
*/

#ifndef COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_
#define COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_
#ifndef AUTOWARE_COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_
#define AUTOWARE_COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_

#include <grid_map_cv/grid_map_cv.hpp>
#include <grid_map_ros/grid_map_ros.hpp>
Expand Down Expand Up @@ -98,4 +98,4 @@ void FillPolygonAreas(

} // namespace object_map

#endif // COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_
#endif // AUTOWARE_COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,8 @@
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
********************/

#ifndef COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_
#define COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_
#ifndef AUTOWARE_COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_
#define AUTOWARE_COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_

#include <grid_map_ros/grid_map_ros.hpp>

Expand All @@ -57,6 +57,8 @@

#include <string>

namespace autoware::costmap_generator
{
class ObjectsToCostmap
{
public:
Expand Down Expand Up @@ -123,5 +125,5 @@ class ObjectsToCostmap
const grid_map::Polygon & polygon, const std::string & gridmap_layer_name, const float score,
grid_map::GridMap & objects_costmap);
};

#endif // COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_
} // namespace autoware::costmap_generator
#endif // AUTOWARE_COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,8 @@
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
********************/

#ifndef COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_
#define COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_
#ifndef AUTOWARE_COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_
#define AUTOWARE_COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_

#include <grid_map_ros/grid_map_ros.hpp>

Expand All @@ -52,6 +52,9 @@
#include <string>
#include <vector>

namespace autoware::costmap_generator

{
class PointsToCostmap
{
public:
Expand Down Expand Up @@ -115,5 +118,6 @@ class PointsToCostmap
const std::string & gridmap_layer_name,
const std::vector<std::vector<std::vector<double>>> grid_vec);
};
} // namespace autoware::costmap_generator

#endif // COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_
#endif // AUTOWARE_COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,9 @@
<arg name="output_grid_map" default="~/output/grid_map"/>
<arg name="output_occupancy_grid" default="~/output/occupancy_grid"/>

<arg name="costmap_generator_param_file" default="$(find-pkg-share costmap_generator)/config/costmap_generator.param.yaml"/>
<arg name="costmap_generator_param_file" default="$(find-pkg-share autoware_costmap_generator)/config/costmap_generator.param.yaml"/>

<node pkg="costmap_generator" exec="costmap_generator" name="costmap_generator" output="screen">
<node pkg="autoware_costmap_generator" exec="costmap_generator" name="costmap_generator" output="screen">
<remap from="~/input/objects" to="$(var input_objects)"/>
<remap from="~/input/points_no_ground" to="$(var input_points_no_ground)"/>
<remap from="~/input/vector_map" to="$(var input_lanelet_map)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,8 @@
* OF private_node SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
********************/

#include "costmap_generator/costmap_generator.hpp"
#include "costmap_generator/object_map_utils.hpp"
#include "autoware_costmap_generator/costmap_generator.hpp"
#include "autoware_costmap_generator/object_map_utils.hpp"

#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/query.hpp>
Expand Down Expand Up @@ -157,6 +157,8 @@ pcl::PointCloud<pcl::PointXYZ> getTransformedPointCloud(

} // namespace

namespace autoware::costmap_generator
{
CostmapGenerator::CostmapGenerator(const rclcpp::NodeOptions & node_options)
: Node("costmap_generator", node_options), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_)
{
Expand Down Expand Up @@ -476,6 +478,7 @@ void CostmapGenerator::publishCostmap(const grid_map::GridMap & costmap)
out_gridmap_msg->header = header;
pub_costmap_->publish(*out_gridmap_msg);
}
} // namespace autoware::costmap_generator

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(CostmapGenerator)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::costmap_generator::CostmapGenerator)
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
*
*/

#include "costmap_generator/object_map_utils.hpp"
#include "autoware_costmap_generator/object_map_utils.hpp"

#include <string>
#include <vector>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,13 +42,15 @@
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
********************/

#include "costmap_generator/objects_to_costmap.hpp"
#include "autoware_costmap_generator/objects_to_costmap.hpp"

#include <tf2/utils.h>

#include <cmath>
#include <string>

namespace autoware::costmap_generator
{
// Constructor
ObjectsToCostmap::ObjectsToCostmap()
: NUMBER_OF_POINTS(4),
Expand Down Expand Up @@ -196,3 +198,4 @@ grid_map::Matrix ObjectsToCostmap::makeCostmapFromObjects(

return objects_costmap[OBJECTS_COSTMAP_LAYER_];
}
} // namespace autoware::costmap_generator
Original file line number Diff line number Diff line change
Expand Up @@ -42,11 +42,14 @@
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
********************/

#include "costmap_generator/points_to_costmap.hpp"
#include "autoware_costmap_generator/points_to_costmap.hpp"

#include <string>
#include <vector>

namespace autoware::costmap_generator
{

void PointsToCostmap::initGridmapParam(const grid_map::GridMap & gridmap)
{
grid_length_x_ = gridmap.getLength().x();
Expand Down Expand Up @@ -140,3 +143,5 @@ grid_map::Matrix PointsToCostmap::makeCostmapFromPoints(
gridmap_layer_name, grid_vec);
return costmap;
}

} // namespace autoware::costmap_generator
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>costmap_generator</name>
<name>autoware_costmap_generator</name>
<version>0.1.0</version>
<description>The costmap_generator package</description>
<description>The autoware_costmap_generator package</description>
<maintainer email="[email protected]">Kosuke Takeuchi</maintainer>
<maintainer email="[email protected]">Takamasa Horibe</maintainer>
<maintainer email="[email protected]">Takayuki Murooka</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <costmap_generator/objects_to_costmap.hpp>
#include <autoware_costmap_generator/objects_to_costmap.hpp>
#include <rclcpp/rclcpp.hpp>

#include <gtest/gtest.h>

namespace autoware::costmap_generator
{
using LABEL = autoware_perception_msgs::msg::ObjectClassification;

class ObjectsToCostMapTest : public ::testing::Test
Expand Down Expand Up @@ -134,3 +136,4 @@ TEST_F(ObjectsToCostMapTest, TestMakeCostmapFromObjects)
}
}
}
} // namespace autoware::costmap_generator
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <costmap_generator/points_to_costmap.hpp>
#include <autoware_costmap_generator/points_to_costmap.hpp>

#include <gtest/gtest.h>

namespace autoware::costmap_generator
{
using pointcloud = pcl::PointCloud<pcl::PointXYZ>;
class PointsToCostmapTest : public ::testing::Test
{
Expand Down Expand Up @@ -216,3 +219,4 @@ TEST_F(PointsToCostmapTest, TestMakeCostmapFromPoints_invalidPoints_outOfGrid)

EXPECT_EQ(nonempty_grid_cell_num, 0);
}
} // namespace autoware::costmap_generator

0 comments on commit 59a204b

Please sign in to comment.