Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
73 changes: 73 additions & 0 deletions nav2_frenet_ilqr_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(frenet_trajectory_planner REQUIRED)
find_package(ilqr_trajectory_tracker REQUIRED)
find_package(nav2_ros_common REQUIRED)

include_directories(
include
Expand All @@ -31,6 +32,7 @@ add_library(${library_name} SHARED
src/frenet_ilqr_controller.cpp
src/path_handler.cpp
src/parameter_handler.cpp)
<<<<<<< HEAD

ament_target_dependencies(${library_name}
rclcpp
Expand All @@ -46,13 +48,40 @@ ament_target_dependencies(${library_name}
frenet_trajectory_planner
ilqr_trajectory_tracker
rcl_interfaces
=======
target_include_directories(${library_name}
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
"$<BUILD_INTERFACE:${nav2_ros_common_INCLUDE_DIRS}>"
)
target_link_libraries(${library_name} PUBLIC
${geometry_msgs_TARGETS}
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_core
nav2_util::nav2_util_core
${nav_msgs_TARGETS}
pluginlib::pluginlib
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rcl_interfaces_TARGETS}
${std_msgs_TARGETS}
tf2::tf2
tf2_ros::tf2_ros
frenet_trajectory_planner::frenet_trajectory_planner_lib
ilqr_trajectory_tracker::ilqr_trajectory_tracker_lib
)
target_link_libraries(${library_name} PRIVATE
angles::angles
>>>>>>> 443563f (Migrate nav2_utils's ros relavant dependencies to nav2_ros_common (#44))
)

add_library(nav2_frenet_ilqr_controller_costs SHARED
src/costs/lateral_distance_cost.cpp
src/costs/longtitutal_velocity_cost.cpp
src/costs/obstacle_cost.cpp)

<<<<<<< HEAD
ament_target_dependencies(nav2_frenet_ilqr_controller_costs
rclcpp
geometry_msgs
Expand All @@ -67,11 +96,33 @@ ament_target_dependencies(nav2_frenet_ilqr_controller_costs
frenet_trajectory_planner
ilqr_trajectory_tracker
rcl_interfaces
=======
target_include_directories(nav2_frenet_ilqr_controller_costs
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
"$<BUILD_INTERFACE:${nav2_ros_common_INCLUDE_DIRS}>"
)

target_link_libraries(nav2_frenet_ilqr_controller_costs PUBLIC
nav2_costmap_2d::nav2_costmap_2d_core
nav2_util::nav2_util_core
${nav_msgs_TARGETS}
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rcl_interfaces_TARGETS}
frenet_trajectory_planner::frenet_trajectory_planner_lib
)

target_link_libraries(nav2_frenet_ilqr_controller_costs PRIVATE
pluginlib::pluginlib
>>>>>>> 443563f (Migrate nav2_utils's ros relavant dependencies to nav2_ros_common (#44))
)

add_library(nav2_frenet_ilqr_controller_policies SHARED
src/policies/obstacle_policy.cpp)

<<<<<<< HEAD
ament_target_dependencies(nav2_frenet_ilqr_controller_policies
rclcpp
geometry_msgs
Expand All @@ -86,6 +137,27 @@ ament_target_dependencies(nav2_frenet_ilqr_controller_policies
frenet_trajectory_planner
ilqr_trajectory_tracker
rcl_interfaces
=======
target_include_directories(nav2_frenet_ilqr_controller_policies
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
"$<BUILD_INTERFACE:${nav2_ros_common_INCLUDE_DIRS}>"
)

target_link_libraries(nav2_frenet_ilqr_controller_policies PUBLIC
nav2_costmap_2d::nav2_costmap_2d_core
nav2_util::nav2_util_core
${nav_msgs_TARGETS}
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rcl_interfaces_TARGETS}
frenet_trajectory_planner::frenet_trajectory_planner_lib
)

target_link_libraries(nav2_frenet_ilqr_controller_policies PRIVATE
pluginlib::pluginlib
>>>>>>> 443563f (Migrate nav2_utils's ros relavant dependencies to nav2_ros_common (#44))
)

install(TARGETS ${library_name} nav2_frenet_ilqr_controller_costs nav2_frenet_ilqr_controller_policies
Expand Down Expand Up @@ -126,6 +198,7 @@ ament_export_dependencies(
std_msgs
tf2
tf2_ros
nav2_ros_common
)
ament_export_targets(${library_name})

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,10 @@
#define NAV2_FRENET_ILQR_CONTROLLER__COSTS__LATERAL_DISTANCE_COST_HPP_

#include <memory>
#include "nav2_util/node_utils.hpp"
#include "nav2_ros_common/node_utils.hpp"
#include "nav2_frenet_ilqr_controller/costs/rclcpp_node_cost.hpp"

using nav2_util::declare_parameter_if_not_declared;
using nav2::declare_parameter_if_not_declared;
using rcl_interfaces::msg::ParameterType;

namespace nav2_frenet_ilqr_controller
Expand All @@ -20,7 +20,7 @@ class LateralDistanceCost : public RclcppNodeCost
LateralDistanceCost();
void initialize(
const std::string & cost_plugin_name,
const rclcpp_lifecycle::LifecycleNode::WeakPtr & node,
const nav2::LifecycleNode::WeakPtr & node,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
double cost(
const FrenetTrajectory & frenet_trajectory,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,10 @@
#define NAV2_FRENET_ILQR_CONTROLLER__COSTS__LONGTITUTAL_VELOCITY_COST_HPP_

#include <memory>
#include "nav2_util/node_utils.hpp"
#include "nav2_ros_common/node_utils.hpp"
#include "nav2_frenet_ilqr_controller/costs/rclcpp_node_cost.hpp"

using nav2_util::declare_parameter_if_not_declared;
using nav2::declare_parameter_if_not_declared;
using rcl_interfaces::msg::ParameterType;

namespace nav2_frenet_ilqr_controller
Expand All @@ -20,7 +20,7 @@ class LongtitutalVelocityCost : public RclcppNodeCost
LongtitutalVelocityCost();
void initialize(
const std::string & cost_plugin_name,
const rclcpp_lifecycle::LifecycleNode::WeakPtr & node,
const nav2::LifecycleNode::WeakPtr & node,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
double cost(
const FrenetTrajectory & frenet_trajectory,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,10 @@
#define NAV2_FRENET_ILQR_CONTROLLER__COSTS__OBSTACLE_COST_HPP_

#include <memory>
#include "nav2_util/node_utils.hpp"
#include "nav2_ros_common/node_utils.hpp"
#include "nav2_frenet_ilqr_controller/costs/rclcpp_node_cost.hpp"

using nav2_util::declare_parameter_if_not_declared;
using nav2::declare_parameter_if_not_declared;
using rcl_interfaces::msg::ParameterType;

namespace nav2_frenet_ilqr_controller
Expand All @@ -20,7 +20,7 @@ class ObstacleCost : public RclcppNodeCost
ObstacleCost();
void initialize(
const std::string & cost_plugin_name,
const rclcpp_lifecycle::LifecycleNode::WeakPtr & node,
const nav2::LifecycleNode::WeakPtr & node,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
double cost(
const FrenetTrajectory & frenet_trajectory,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#define NAV2_FRENET_ILQR_CONTROLLER__COSTS__RCLCPP_NODE_COST_HPP_

#include "frenet_trajectory_planner/costs/base_cost.hpp"
#include "rclcpp/rclcpp.hpp"
#include "nav2_ros_common/node_utils.hpp"
#include "nav2_costmap_2d/costmap_2d_ros.hpp"

using namespace frenet_trajectory_planner::costs;
Expand All @@ -20,7 +20,7 @@ class RclcppNodeCost : public Cost
: Cost() {}
virtual void initialize(
const std::string & cost_plugin_name,
const rclcpp_lifecycle::LifecycleNode::WeakPtr & node,
const nav2::LifecycleNode::WeakPtr & node,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
{
cost_plugin_name_ = cost_plugin_name;
Expand All @@ -31,7 +31,7 @@ class RclcppNodeCost : public Cost

protected:
std::string cost_plugin_name_;
rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
nav2::LifecycleNode::WeakPtr node_;
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
nav2_costmap_2d::Costmap2D * costmap_{nullptr};
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class FrenetILQRController : public nav2_core::Controller
* @param costmap_ros Costmap2DROS object of environment
*/
void configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
const nav2::LifecycleNode::WeakPtr & parent,
std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;

Expand Down Expand Up @@ -124,7 +124,7 @@ class FrenetILQRController : public nav2_core::Controller
const nav_msgs::msg::Path & path_msg);

protected:
rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
nav2::LifecycleNode::WeakPtr node_;
std::shared_ptr<tf2_ros::Buffer> tf_;
std::string plugin_name_;
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
Expand All @@ -137,9 +137,9 @@ class FrenetILQRController : public nav2_core::Controller
bool finished_cancelling_ = false;
bool is_rotating_to_heading_ = false;

std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> global_path_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> truncated_path_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PoseStamped>>
std::shared_ptr<nav2::Publisher<nav_msgs::msg::Path>> global_path_pub_;
std::shared_ptr<nav2::Publisher<nav_msgs::msg::Path>> truncated_path_pub_;
std::shared_ptr<nav2::Publisher<geometry_msgs::msg::PoseStamped>>
robot_pose_pub_;
std::unique_ptr<nav2_frenet_ilqr_controller::PathHandler> path_handler_;
std::unique_ptr<nav2_frenet_ilqr_controller::ParameterHandler> parameter_handler_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,11 +21,10 @@
#include <algorithm>
#include <mutex>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "nav2_util/odometry_utils.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_ros_common/lifecycle_node.hpp"
#include "nav2_ros_common/node_utils.hpp"

#include "frenet_trajectory_planner/type_definitions.hpp"
#include <iostream>
Expand Down Expand Up @@ -57,7 +56,7 @@ class ParameterHandler
* @brief Constructor for nav2_frenet_ilqr_controller::ParameterHandler
*/
ParameterHandler(
rclcpp_lifecycle::LifecycleNode::WeakPtr node, const std::string & plugin_name,
nav2::LifecycleNode::WeakPtr node, const std::string & plugin_name,
const double costmap_size_x_in_meters);

/**
Expand All @@ -70,7 +69,7 @@ class ParameterHandler
Parameters * getParams() {return &params_;}

protected:
rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
nav2::LifecycleNode::WeakPtr node_;
std::string plugin_name_;
Parameters params_;
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ class ObstaclePolicy : public RclcppNodePolicy
ObstaclePolicy();
void initialize(
const std::string & policy_plugin_name,
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
const nav2::LifecycleNode::WeakPtr & parent,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
bool checkIfFeasible(
const FrenetTrajectory & frenet_trajectory,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ class RclcppNodePolicy : public Policy
RclcppNodePolicy();
virtual void initialize(
const std::string & policy_plugin_name,
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
const nav2::LifecycleNode::WeakPtr & parent,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
{
policy_plugin_name_ = policy_plugin_name;
Expand All @@ -32,7 +32,7 @@ class RclcppNodePolicy : public Policy
const CartesianTrajectory & cartesian_trajectory) = 0;

protected:
rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
nav2::LifecycleNode::WeakPtr node_;
std::string policy_plugin_name_;
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
nav2_costmap_2d::Costmap2D * costmap_{nullptr};
Expand Down
1 change: 1 addition & 0 deletions nav2_frenet_ilqr_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
<depend>tf2_ros</depend>
<depend>frenet_trajectory_planner</depend>
<depend>ilqr_trajectory_tracker</depend>
<depend>nav2_ros_common</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ LateralDistanceCost::LateralDistanceCost()

void LateralDistanceCost::initialize(
const std::string & cost_plugin_name,
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
const nav2::LifecycleNode::WeakPtr & parent,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
{
RclcppNodeCost::initialize(cost_plugin_name, parent, costmap_ros);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ LongtitutalVelocityCost::LongtitutalVelocityCost()

void LongtitutalVelocityCost::initialize(
const std::string & cost_plugin_name,
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
const nav2::LifecycleNode::WeakPtr & parent,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
{
RclcppNodeCost::initialize(cost_plugin_name, parent, costmap_ros);
Expand Down
2 changes: 1 addition & 1 deletion nav2_frenet_ilqr_controller/src/costs/obstacle_cost.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ ObstacleCost::ObstacleCost()

void ObstacleCost::initialize(
const std::string & cost_plugin_name,
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
const nav2::LifecycleNode::WeakPtr & parent,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
{
RclcppNodeCost::initialize(cost_plugin_name, parent, costmap_ros);
Expand Down
Loading