diff --git a/frenet_trajectory_planner/include/frenet_trajectory_planner/conversion_adapters/circle_adapter.hpp b/frenet_trajectory_planner/include/frenet_trajectory_planner/conversion_adapters/circle_adapter.hpp
index 0bc54ba..93a36d4 100644
--- a/frenet_trajectory_planner/include/frenet_trajectory_planner/conversion_adapters/circle_adapter.hpp
+++ b/frenet_trajectory_planner/include/frenet_trajectory_planner/conversion_adapters/circle_adapter.hpp
@@ -86,6 +86,7 @@ CartesianState CircleAdapter::convertFrenet2Cartesian(const FrenetState & frenet
// cartesian_state[6] = std::atan2(t_frenet_[1], t_frenet_[0]) + std::atan2(
// frenet_state[4],
// frenet_state[1]); // implement in a correct way (yaw angle also should be added to frenet state)
+ cartesian_state[6] = std::atan2(cartesian_state[4], cartesian_state[1]);
return cartesian_state;
diff --git a/nav2_frenet_ilqr_controller/CMakeLists.txt b/nav2_frenet_ilqr_controller/CMakeLists.txt
index 8d6f691..7eeaec4 100644
--- a/nav2_frenet_ilqr_controller/CMakeLists.txt
+++ b/nav2_frenet_ilqr_controller/CMakeLists.txt
@@ -55,7 +55,8 @@ target_link_libraries(${library_name} PRIVATE
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)
+ src/costs/obstacle_cost.cpp
+ src/costs/angular_velocity_cost.cpp)
target_include_directories(nav2_frenet_ilqr_controller_costs
PUBLIC
diff --git a/nav2_frenet_ilqr_controller/costs.xml b/nav2_frenet_ilqr_controller/costs.xml
index 82c52c2..c85fee4 100644
--- a/nav2_frenet_ilqr_controller/costs.xml
+++ b/nav2_frenet_ilqr_controller/costs.xml
@@ -13,5 +13,9 @@
frenet trajectory planner cost checker for obstacle costs
+
+ frenet trajectory planner cost checker for angular velocity costs
+
+
\ No newline at end of file
diff --git a/nav2_frenet_ilqr_controller/include/nav2_frenet_ilqr_controller/costs/angular_velocity_cost.hpp b/nav2_frenet_ilqr_controller/include/nav2_frenet_ilqr_controller/costs/angular_velocity_cost.hpp
new file mode 100644
index 0000000..79e62ba
--- /dev/null
+++ b/nav2_frenet_ilqr_controller/include/nav2_frenet_ilqr_controller/costs/angular_velocity_cost.hpp
@@ -0,0 +1,42 @@
+#ifndef NAV2_FRENET_ILQR_CONTROLLER__COSTS__ANGULAR_VELOCITY_COST_HPP_
+#define NAV2_FRENET_ILQR_CONTROLLER__COSTS__ANGULAR_VELOCITY_COST_HPP_
+
+#include
+#include "nav2_util/node_utils.hpp"
+#include "nav2_frenet_ilqr_controller/costs/rclcpp_node_cost.hpp"
+
+using nav2_util::declare_parameter_if_not_declared;
+using rcl_interfaces::msg::ParameterType;
+
+namespace nav2_frenet_ilqr_controller
+{
+namespace costs
+{
+
+class AngularVelocityCost : public RclcppNodeCost
+{
+
+public:
+ AngularVelocityCost();
+ void initialize(
+ const std::string & cost_plugin_name,
+ const rclcpp_lifecycle::LifecycleNode::WeakPtr & node,
+ std::shared_ptr costmap_ros) override;
+ double cost(
+ const FrenetTrajectory & frenet_trajectory,
+ const CartesianTrajectory & cartesian_trajectory) override;
+
+protected:
+ double K_angular_velocity_;
+};
+
+}
+}
+
+#include
+
+PLUGINLIB_EXPORT_CLASS(
+ nav2_frenet_ilqr_controller::costs::AngularVelocityCost,
+ nav2_frenet_ilqr_controller::costs::RclcppNodeCost)
+
+#endif
diff --git a/nav2_frenet_ilqr_controller/src/costs/angular_velocity_cost.cpp b/nav2_frenet_ilqr_controller/src/costs/angular_velocity_cost.cpp
new file mode 100644
index 0000000..485ff9e
--- /dev/null
+++ b/nav2_frenet_ilqr_controller/src/costs/angular_velocity_cost.cpp
@@ -0,0 +1,63 @@
+#include "nav2_frenet_ilqr_controller/costs/angular_velocity_cost.hpp"
+
+namespace nav2_frenet_ilqr_controller
+{
+namespace costs
+{
+
+AngularVelocityCost::AngularVelocityCost()
+: RclcppNodeCost()
+{
+}
+
+void AngularVelocityCost::initialize(
+ const std::string & cost_plugin_name,
+ const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
+ std::shared_ptr costmap_ros)
+{
+ RclcppNodeCost::initialize(cost_plugin_name, parent, costmap_ros);
+
+ auto node = parent.lock();
+
+ declare_parameter_if_not_declared(
+ node, cost_plugin_name_ + ".K_angular_velocity", rclcpp::ParameterValue(2.0));
+
+ node->get_parameter(
+ cost_plugin_name_ + ".K_angular_velocity",
+ K_angular_velocity_);
+
+ RCLCPP_INFO(
+ node->get_logger(), "%s.K_angular_velocity : %f",
+ cost_plugin_name_.c_str(), K_angular_velocity_);
+}
+
+double AngularVelocityCost::cost(
+ const FrenetTrajectory & /*frenet_trajectory*/,
+ const CartesianTrajectory & cartesian_trajectory)
+{
+ double trajectory_cost = 0;
+
+ if (cartesian_trajectory.size() < 2) {
+ return 0.0;
+ }
+
+ for (auto cartesian_state_it = cartesian_trajectory.begin();
+ cartesian_state_it != std::prev(cartesian_trajectory.end()); ++cartesian_state_it)
+ {
+ const double & theta1 = (*cartesian_state_it)[6];
+ const double & theta2 = (*std::next(cartesian_state_it))[6];
+
+ trajectory_cost += std::abs(theta1 - theta2);
+ }
+
+ return K_angular_velocity_ * trajectory_cost / cartesian_trajectory.size();
+}
+
+}
+}
+
+#include
+
+PLUGINLIB_EXPORT_CLASS(
+ nav2_frenet_ilqr_controller::costs::AngularVelocityCost,
+ nav2_frenet_ilqr_controller::costs::RclcppNodeCost)
diff --git a/nav2_frenet_ilqr_controller/src/costs/obstacle_cost.cpp b/nav2_frenet_ilqr_controller/src/costs/obstacle_cost.cpp
index bbbc7bd..bb826eb 100644
--- a/nav2_frenet_ilqr_controller/src/costs/obstacle_cost.cpp
+++ b/nav2_frenet_ilqr_controller/src/costs/obstacle_cost.cpp
@@ -19,7 +19,7 @@ void ObstacleCost::initialize(
auto node = parent.lock();
declare_parameter_if_not_declared(
- node, cost_plugin_name_ + ".K_obstacle", rclcpp::ParameterValue(2));
+ node, cost_plugin_name_ + ".K_obstacle", rclcpp::ParameterValue(2.0));
node->get_parameter(
cost_plugin_name_ + ".K_obstacle",
diff --git a/nav2_frenet_ilqr_controller/src/frenet_ilqr_controller.cpp b/nav2_frenet_ilqr_controller/src/frenet_ilqr_controller.cpp
index 4325304..32b8b08 100644
--- a/nav2_frenet_ilqr_controller/src/frenet_ilqr_controller.cpp
+++ b/nav2_frenet_ilqr_controller/src/frenet_ilqr_controller.cpp
@@ -275,11 +275,6 @@ geometry_msgs::msg::TwistStamped FrenetILQRController::computeVelocityCommands(
robot_cartesian_state,
waypoint_list);
- // get yaw angles from velocities along x axis and y axis in cartesian coordinate system
- for (auto & cartesian_state : planned_cartesian_trajectory) {
- cartesian_state[6] = std::atan2(cartesian_state[4], cartesian_state[1]);
- }
-
nav_msgs::msg::Path frenet_plan = convertFromCartesianTrajectory(
transformed_plan.header.frame_id,
planned_cartesian_trajectory);