Skip to content

Commit

Permalink
Rename project
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Jun 6, 2023
1 parent 7d0cc37 commit c13cd87
Show file tree
Hide file tree
Showing 85 changed files with 443 additions and 450 deletions.
10 changes: 5 additions & 5 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ endif()
# Set the possible values of build type for cmake-gui
set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug" "Release" "MinSizeRel" "RelWithDebInfo" "SanitizeAddress" "SanitizeThread")

project(SelfdrivingProject LANGUAGES CXX)
project(MRPTPathPlanningProject LANGUAGES CXX)

# Include std cmake scripts:
include(CheckCXXCompilerFlag) # for check_cxx_compiler_flag()
Expand Down Expand Up @@ -45,16 +45,16 @@ find_package(mrpt-gui REQUIRED)
find_package(mrpt-nav REQUIRED)

# Targets:
add_subdirectory(libselfdriving)
add_subdirectory(mrpt_path_planning)

option(SELFDRIVING_BUILD_APPS "Build selfdriving cli/gui tools" ON)
if (SELFDRIVING_BUILD_APPS)
option(MRPT_PATH_PLANNING_BUILD_APPS "Build mrpt_path_planning cli/gui tools" ON)
if (MRPT_PATH_PLANNING_BUILD_APPS)
add_subdirectory(apps)
endif()

# Summary:
message(STATUS "")
message(STATUS "${PROJECT_NAME} version ${SELFDRIVING_VERSION}")
message(STATUS "${PROJECT_NAME} version ${MRPT_PATH_PLANNING_VERSION}")
message(STATUS "----------------------------------------------------------")
message(STATUS " CMAKE_BUILD_TYPE : ${CMAKE_BUILD_TYPE}")
message(STATUS " MRPT : ${mrpt-nav_VERSION}")
Expand Down
13 changes: 8 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,7 +1,10 @@
[![CI Linux](https://github.com/jlblancoc/selfdriving/actions/workflows/build-linux.yml/badge.svg)](https://github.com/jlblancoc/selfdriving/actions/workflows/build-linux.yml) [![Documentation Status](https://readthedocs.org/projects/selfdriving/badge/?version=latest)](https://selfdriving.readthedocs.io/en/latest/?badge=latest)

# selfdriving
Self-driving (autonomous navigation) algorithms for robots/vehicles moving on planar environments. This builds upon mrpt-nav and the theory behind PTGs to generate libraries of "motion primitives" for vehicles with arbitrary shape and realistic kinematics and dynamics.
# mrpt_path_planning

Path planning and navigation algorithms for robots/vehicles moving on planar environments.
This library builds upon mrpt-nav and the theory behind PTGs to generate libraries of "motion primitives"
for vehicles with arbitrary shape and realistic kinematics and dynamics.

## Build requisites

Expand All @@ -28,8 +31,8 @@ sudo apt install libmrpt-dev
From your CMake script:

```
find_package(selfdriving REQUIRED)
target_link_libraries(YOUR_TARGET selfdriving::selfdriving)
find_package(mrpt_path_planning REQUIRED)
target_link_libraries(YOUR_TARGET mpp::mrpt_path_planning)
```

## Demo runs
Expand All @@ -42,7 +45,7 @@ Command-line app to test the A* planner:

```
build-Release/bin/path-planner-cli -g "[4 2.5 45]" -s "[0.5 0 0]" \
--planner "selfdriving::TPS_Astar" \
--planner "mpp::TPS_Astar" \
-c share/ptgs_holonomic_robot.ini \
--obstacles share/obstacles_01.txt \
--planner-parameters share/mvsim-demo-astar-planner-params.yaml \
Expand Down
2 changes: 1 addition & 1 deletion apps/path-planner-cli/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,6 @@ selfdriving_add_executable(
mrpt::gui
mrpt::nav
mrpt::tclap
selfdriving
mrpt_path_planning
)

83 changes: 38 additions & 45 deletions apps/path-planner-cli/path-planner-cli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,13 @@
* See LICENSE for license information.
* ------------------------------------------------------------------------- */

#include <mpp/algos/CostEvaluatorCostMap.h>
#include <mpp/algos/CostEvaluatorPreferredWaypoint.h>
#include <mpp/algos/TPS_Astar.h>
#include <mpp/algos/refine_trajectory.h>
#include <mpp/algos/trajectories.h>
#include <mpp/algos/viz.h>
#include <mpp/data/Waypoints.h>
#include <mrpt/3rdparty/tclap/CmdLine.h>
#include <mrpt/config/CConfigFile.h>
#include <mrpt/core/exceptions.h> // exception_to_str()
Expand All @@ -16,13 +23,6 @@
#include <mrpt/system/filesystem.h>
#include <mrpt/system/os.h> // plugins
#include <mrpt/version.h>
#include <selfdriving/algos/CostEvaluatorCostMap.h>
#include <selfdriving/algos/CostEvaluatorPreferredWaypoint.h>
#include <selfdriving/algos/TPS_Astar.h>
#include <selfdriving/algos/refine_trajectory.h>
#include <selfdriving/algos/trajectories.h>
#include <selfdriving/algos/viz.h>
#include <selfdriving/data/Waypoints.h>

#include <fstream>
#include <iostream>
Expand All @@ -37,8 +37,8 @@ TCLAP::ValueArg<std::string> arg_obs_file(
true, "", "obs.txt", cmd);

TCLAP::ValueArg<std::string> argPlanner(
"p", "planner", "Planner C++ class name to use", false,
"selfdriving::TPS_Astar", "selfdriving::TPS_Astar", cmd);
"p", "planner", "Planner C++ class name to use", false, "mpp::TPS_Astar",
"mpp::TPS_Astar", cmd);

TCLAP::ValueArg<std::string> argVerbosity(
"v", "verbose", "Verbosity level for path planner", false, "INFO",
Expand Down Expand Up @@ -192,17 +192,16 @@ static void do_plan_path()
{
// Load obstacles:
mrpt::maps::CPointsMap::Ptr obsPts = load_obstacles();
auto obs = selfdriving::ObstacleSource::FromStaticPointcloud(obsPts);
auto obs = mpp::ObstacleSource::FromStaticPointcloud(obsPts);

// Prepare planner input data:
selfdriving::PlannerInput pi;
mpp::PlannerInput pi;

pi.stateStart.pose.fromString(arg_start_pose.getValue());
if (arg_start_vel.isSet())
pi.stateStart.vel.fromString(arg_start_vel.getValue());

pi.stateGoal.state =
selfdriving::PoseOrPoint::FromString(arg_goal_pose.getValue());
pi.stateGoal.state = mpp::PoseOrPoint::FromString(arg_goal_pose.getValue());
if (arg_goal_vel.isSet())
pi.stateGoal.vel.fromString(arg_goal_vel.getValue());

Expand Down Expand Up @@ -235,9 +234,8 @@ static void do_plan_path()
<< pi.worldBboxMax.asString() << "\n";

// Do the path planning :
selfdriving::Planner::Ptr planner =
std::dynamic_pointer_cast<selfdriving::Planner>(
mrpt::rtti::classFactory(argPlanner.getValue()));
mpp::Planner::Ptr planner = std::dynamic_pointer_cast<mpp::Planner>(
mrpt::rtti::classFactory(argPlanner.getValue()));

if (!planner)
{
Expand All @@ -254,35 +252,32 @@ static void do_plan_path()
{
// cost map:
const auto costMapParams =
selfdriving::CostEvaluatorCostMap::Parameters::FromYAML(
mpp::CostEvaluatorCostMap::Parameters::FromYAML(
mrpt::containers::yaml::FromFile(arg_costMap.getValue()));

auto costmap =
selfdriving::CostEvaluatorCostMap::FromStaticPointObstacles(
*obsPts, costMapParams, pi.stateStart.pose);
auto costmap = mpp::CostEvaluatorCostMap::FromStaticPointObstacles(
*obsPts, costMapParams, pi.stateStart.pose);

planner->costEvaluators_.push_back(costmap);
}

// Preferred waypoints:
auto wpParams = selfdriving::CostEvaluatorPreferredWaypoint::Parameters();
auto wpParams = mpp::CostEvaluatorPreferredWaypoint::Parameters();
if (arg_waypointsParams.isSet())
{
wpParams =
selfdriving::CostEvaluatorPreferredWaypoint::Parameters::FromYAML(
mrpt::containers::yaml::FromFile(
arg_waypointsParams.getValue()));
wpParams = mpp::CostEvaluatorPreferredWaypoint::Parameters::FromYAML(
mrpt::containers::yaml::FromFile(arg_waypointsParams.getValue()));
}

if (arg_waypoints.isSet())
{
const auto wps = selfdriving::WaypointSequence::FromYAML(
const auto wps = mpp::WaypointSequence::FromYAML(
mrpt::containers::yaml::FromFile(arg_waypoints.getValue()));

std::vector<mrpt::math::TPoint2D> lstPts;
for (const auto& wp : wps.waypoints) lstPts.emplace_back(wp.target);

auto costEval = selfdriving::CostEvaluatorPreferredWaypoint::Create();
auto costEval = mpp::CostEvaluatorPreferredWaypoint::Create();
costEval->params_ = wpParams;
costEval->setPreferredWaypoints(lstPts);
planner->costEvaluators_.push_back(costEval);
Expand All @@ -305,14 +300,12 @@ static void do_plan_path()
}

// Insert custom progress callback:
planner->progressCallback_ =
[](const selfdriving::ProgressCallbackData& pcd) {
std::cout << "[progressCallback] bestCostFromStart: "
<< pcd.bestCostFromStart
<< " bestCostToGoal: " << pcd.bestCostToGoal
<< " bestPathLength: " << pcd.bestPath.size()
<< std::endl;
};
planner->progressCallback_ = [](const mpp::ProgressCallbackData& pcd) {
std::cout << "[progressCallback] bestCostFromStart: "
<< pcd.bestCostFromStart
<< " bestCostToGoal: " << pcd.bestCostToGoal
<< " bestPathLength: " << pcd.bestPath.size() << std::endl;
};

// PTGs config file:
mrpt::config::CConfigFile cfg(arg_ptgs_file.getValue());
Expand All @@ -321,7 +314,7 @@ static void do_plan_path()
// ==================================================
// ACTUAL PATH PLANNING
// ==================================================
const selfdriving::PlannerOutput plan = planner->plan(pi);
const mpp::PlannerOutput plan = planner->plan(pi);

std::cout << "\nDone.\n";
std::cout << "Success: " << (plan.success ? "YES" : "NO") << "\n";
Expand All @@ -342,11 +335,11 @@ static void do_plan_path()
if (!arg_noRefine.isSet())
{
// refine:
selfdriving::refine_trajectory(plannedPath, pathEdges, pi.ptgs);
mpp::refine_trajectory(plannedPath, pathEdges, pi.ptgs);
}

// Visualize:
selfdriving::VisualizationOptions vizOpts;
mpp::VisualizationOptions vizOpts;

vizOpts.renderOptions.highlight_path_to_node_id = plan.bestNodeId;
vizOpts.renderOptions.color_normal_edge = {0xb0b0b0, 0x20}; // RGBA
Expand All @@ -356,7 +349,7 @@ static void do_plan_path()
// Hide regular tree edges and only show best path?
if (!arg_showTree.isSet()) vizOpts.renderOptions.width_normal_edge = 0;

std::optional<selfdriving::trajectory_t> traj; // interpolated path
std::optional<mpp::trajectory_t> traj; // interpolated path

if (plan.success)
{
Expand All @@ -372,7 +365,7 @@ static void do_plan_path()
{
const auto t0 = mrpt::Clock::nowDouble();

traj = selfdriving::plan_to_trajectory(pathEdges, pi.ptgs);
traj = mpp::plan_to_trajectory(pathEdges, pi.ptgs);

const auto dt = mrpt::Clock::nowDouble() - t0;

Expand All @@ -383,7 +376,7 @@ static void do_plan_path()
{
std::cout << "Saving path to " << arg_InterpolatePath.getValue()
<< std::endl;
selfdriving::save_to_txt(*traj, arg_InterpolatePath.getValue());
mpp::save_to_txt(*traj, arg_InterpolatePath.getValue());
}
}
}
Expand All @@ -392,12 +385,12 @@ static void do_plan_path()
if (!arg_playAnimation.isSet() || !traj.has_value())
{
// regular UI:
selfdriving::viz_nav_plan(plan, vizOpts, planner->costEvaluators_);
mpp::viz_nav_plan(plan, vizOpts, planner->costEvaluators_);
}
else
{
// Animation UI:
selfdriving::viz_nav_plan_animation(
mpp::viz_nav_plan_animation(
plan, *traj, vizOpts.renderOptions, planner->costEvaluators_);
}
}
Expand All @@ -410,8 +403,8 @@ int main(int argc, char** argv)

if (argPlanner_yaml_output_file.isSet())
{
selfdriving::TPS_Astar_Parameters defaults;
const auto c = defaults.as_yaml();
mpp::TPS_Astar_Parameters defaults;
const auto c = defaults.as_yaml();
const auto sFile = argPlanner_yaml_output_file.getValue();
std::ofstream fileYaml(sFile);
ASSERT_(fileYaml.is_open());
Expand Down
2 changes: 1 addition & 1 deletion apps/selfdriving-simulator-gui/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,6 @@ selfdriving_add_executable(
SOURCES selfdriving-simulator-gui.cpp
LINK_LIBRARIES
mrpt::tclap
selfdriving
mrpt_path_planning
mvsim::mvsim-simulator
)

0 comments on commit c13cd87

Please sign in to comment.