Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

94 crptg1 code quality increase #96

Merged
merged 18 commits into from
Feb 6, 2025
Merged
Show file tree
Hide file tree
Changes from 5 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
3 changes: 0 additions & 3 deletions .gitmodules
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,6 @@
[submodule "crp_VIL/nissan_bringup"]
path = crp_VIL/nissan_bringup
url = https://github.com/szenergy/nissan_bringup
[submodule "crp_VIL/pacmod_interface"]
path = crp_VIL/pacmod_interface
url = https://github.com/tier4/pacmod_interface
[submodule "crp_VIL/kvaser_interface"]
path = crp_VIL/kvaser_interface
url = https://github.com/astuff/kvaser_interface.git
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,8 @@ endif()
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(autoware_control_msgs REQUIRED)
find_package(autoware_planning_msgs REQUIRED)
find_package(autoware_vehicle_msgs REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(crp_msgs REQUIRED)


Expand All @@ -24,13 +20,15 @@ add_executable(ctrl_vehicle_control_lat_compensatory src/ctrl_vehicle_control_la
src/compensatory_model/compensatory_model.cpp
src/lib/polynomialCalculator.cpp )

ament_target_dependencies(ctrl_vehicle_control_lat_compensatory rclcpp geometry_msgs std_msgs autoware_control_msgs autoware_planning_msgs autoware_vehicle_msgs nav_msgs crp_msgs)
ament_target_dependencies(ctrl_vehicle_control_lat_compensatory rclcpp autoware_control_msgs autoware_planning_msgs crp_msgs)

install(DIRECTORY launch
DESTINATION share/${PROJECT_NAME})
DESTINATION share/${PROJECT_NAME}
)

install(TARGETS
ctrl_vehicle_control_lat_compensatory
DESTINATION lib/${PROJECT_NAME})
ctrl_vehicle_control_lat_compensatory
DESTINATION lib/${PROJECT_NAME}
)

ament_package()
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ namespace crp
std::vector<double> path_x;
std::vector<double> path_y;
std::vector<double> path_theta;
double target_speed{0.0f};
double targetSpeed{0.0f};
double egoPoseGlobal [3]{0.0f};
double vxEgo{0.0f};
double egoSteeringAngle{0.0f};
Expand Down
Original file line number Diff line number Diff line change
@@ -1,20 +1,12 @@
#ifndef CRP_APL_CTRL_VEHICLE_LAT_COMPENSATORY_HPP
#define CRP_APL_CTRL_VEHICLE_LAT_COMPENSATORY_HPP

#include <chrono>
#include <functional>
#include <memory>
#include <string>
#include <math.h>
#ifndef CRP_APL_CTRL_VEHICLE_LAT_COMPENSATORY_CTRLVEHILECONTROLLATCOMPENSATORY_HPP
#define CRP_APL_CTRL_VEHICLE_LAT_COMPENSATORY_CTRLVEHILECONTROLLATCOMPENSATORY_HPP


#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/pose.hpp"
#include "std_msgs/msg/float32_multi_array.hpp"
#include "std_msgs/msg/float32.hpp"
#include "crp_msgs/msg/ego.hpp"

#include "autoware_control_msgs/msg/control.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"
#include "autoware_vehicle_msgs/msg/steering_report.hpp"

#include "ctrl_vehicle_control/controller_inputs.hpp"
#include "ctrl_vehicle_control/controller_outputs.hpp"
Expand All @@ -25,10 +17,10 @@ namespace crp
{
namespace apl
{
class CtrlVehicleControlLat : public rclcpp::Node
class CtrlVehicleControlLatCompensatory : public rclcpp::Node
{
public:
CtrlVehicleControlLat();
CtrlVehicleControlLatCompensatory();

private:
// VARIABLES
Expand All @@ -43,13 +35,13 @@ namespace crp

void loop();

rclcpp::TimerBase::SharedPtr timer_;
rclcpp::TimerBase::SharedPtr m_timer_;
rclcpp::Publisher<autoware_control_msgs::msg::Lateral>::SharedPtr m_pub_cmd;

rclcpp::Subscription<autoware_planning_msgs::msg::Trajectory>::SharedPtr m_traj_sub_;
rclcpp::Subscription<crp_msgs::msg::Ego>::SharedPtr m_egoVehicle_sub_;
rclcpp::Subscription<autoware_planning_msgs::msg::Trajectory>::SharedPtr m_sub_traj_;
rclcpp::Subscription<crp_msgs::msg::Ego>::SharedPtr m_sub_egoVehicle_;
autoware_control_msgs::msg::Lateral m_ctrlCmdMsg;
};
} // namespace apl
}
#endif // CRP_APL_CTRL_VEHICLE_LAT_COMPENSATORY_HPP
#endif // CRP_APL_CTRL_VEHICLE_LAT_COMPENSATORY_CTRLVEHILECONTROLLATCOMPENSATORY_HPP
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,6 @@
from launch_ros.actions import Node

def generate_launch_description():
ld = LaunchDescription()

ctrl_vehicle_control_lat_compensatory = Node(
package="ctrl_vehicle_control_lat_compensatory",
executable="ctrl_vehicle_control_lat_compensatory",
Expand All @@ -21,6 +19,6 @@ def generate_launch_description():
]
)

ld.add_action(ctrl_vehicle_control_lat_compensatory)

return ld
return LaunchDescription([
ctrl_vehicle_control_lat_compensatory
])
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,8 @@
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<depend>rclcpp</depend>
<depend>geometry_msgs</depend>
<depend>std_msgs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>nav_msgs</depend>
<depend>crp_msgs</depend>

<export>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,43 +1,39 @@
#include <ctrl_vehicle_control_lat_compensatory/ctrl_vehicle_control_lat_compensatory.hpp>

using namespace std::chrono_literals;
using std::placeholders::_1;


crp::apl::CtrlVehicleControlLat::CtrlVehicleControlLat() : Node("CtrlVehicleControlLat")
crp::apl::CtrlVehicleControlLatCompensatory::CtrlVehicleControlLatCompensatory() : Node("CtrlVehicleControlLatCompensatory")
{
timer_ = this->create_wall_timer(std::chrono::milliseconds(33), std::bind(&CtrlVehicleControlLat::loop, this));
m_timer_ = this->create_wall_timer(std::chrono::milliseconds(33), std::bind(&CtrlVehicleControlLatCompensatory::loop, this));
m_pub_cmd = this->create_publisher<autoware_control_msgs::msg::Lateral>("/control/command/control_cmdLat", 30);

m_traj_sub_ = this->create_subscription<autoware_planning_msgs::msg::Trajectory>("/plan/trajectory", 10, std::bind(&CtrlVehicleControlLat::trajCallback, this, std::placeholders::_1));
m_egoVehicle_sub_ = this->create_subscription<crp_msgs::msg::Ego>("/ego", 10, std::bind(&CtrlVehicleControlLat::egoVehicleCallback, this, std::placeholders::_1));

this->declare_parameter("/ctrl/ffGainOffsetGround", 0.0f);
this->declare_parameter("/ctrl/ffGainSlope", 0.0f);
this->declare_parameter("/ctrl/ffLookAheadTime", 0.1f);
this->declare_parameter("/ctrl/ffMinLookAheadDistance", 0.0f);
this->declare_parameter("/ctrl/steeringAngleLPFilter", 0.5f);
this->declare_parameter("/ctrl/fbLookAheadTime", 0.1f);
this->declare_parameter("/ctrl/fbPGain", 0.1f);
this->declare_parameter("/ctrl/fbDGain", 0.0f);
this->declare_parameter("/ctrl/fbIGain", 0.0f);
this->declare_parameter("/ctrl/fbThetaGain", 0.0f);
this->declare_parameter("/ctrl/fbMinLookAheadDistance", 0.5f);
this->declare_parameter("/ctrl/fbIntegralLimit", 3.0f);
this->declare_parameter("/ctrl/trajectory_distance", 50.0f);
this->declare_parameter("/ctrl/debugKPIs", true);

RCLCPP_INFO(this->get_logger(), "ctrl_vehicle_control has been started");
m_sub_traj_ = this->create_subscription<autoware_planning_msgs::msg::Trajectory>("/plan/trajectory", 10, std::bind(&CtrlVehicleControlLatCompensatory::trajCallback, this, std::placeholders::_1));
m_sub_egoVehicle_ = this->create_subscription<crp_msgs::msg::Ego>("/ego", 10, std::bind(&CtrlVehicleControlLatCompensatory::egoVehicleCallback, this, std::placeholders::_1));

this->declare_parameter("/ctrl/ffGainOffsetGround", 0.0f);
this->declare_parameter("/ctrl/ffGainSlope", 0.0f);
this->declare_parameter("/ctrl/ffLookAheadTime", 0.1f);
this->declare_parameter("/ctrl/ffMinLookAheadDistance", 0.0f);
this->declare_parameter("/ctrl/steeringAngleLPFilter", 0.5f);
this->declare_parameter("/ctrl/fbLookAheadTime", 0.1f);
this->declare_parameter("/ctrl/fbPGain", 0.1f);
this->declare_parameter("/ctrl/fbDGain", 0.0f);
this->declare_parameter("/ctrl/fbIGain", 0.0f);
this->declare_parameter("/ctrl/fbThetaGain", 0.0f);
this->declare_parameter("/ctrl/fbMinLookAheadDistance", 0.5f);
this->declare_parameter("/ctrl/fbIntegralLimit", 3.0f);
this->declare_parameter("/ctrl/trajectory_distance", 50.0f);
this->declare_parameter("/ctrl/debugKPIs", true);

RCLCPP_INFO(this->get_logger(), "CtrlVehicleControlLatCompensatory has been started");
}

void crp::apl::CtrlVehicleControlLat::trajCallback(const autoware_planning_msgs::msg::Trajectory input_msg)
void crp::apl::CtrlVehicleControlLatCompensatory::trajCallback(const autoware_planning_msgs::msg::Trajectory input_msg)
{
m_input.path_x.clear();
m_input.path_y.clear();
m_input.path_theta.clear();
double quaternion[4];


// this callback maps the input trajectory to the internal interface
for (long unsigned int i=0; i<input_msg.points.size(); i++)
{
Expand All @@ -51,12 +47,12 @@ void crp::apl::CtrlVehicleControlLat::trajCallback(const autoware_planning_msgs:
}

if (input_msg.points.size() > 0)
m_input.target_speed = input_msg.points.at(0).longitudinal_velocity_mps;
m_input.targetSpeed = input_msg.points.at(0).longitudinal_velocity_mps;
else
m_input.target_speed = 0.0f;
m_input.targetSpeed = 0.0f;
}

void crp::apl::CtrlVehicleControlLat::egoVehicleCallback(const crp_msgs::msg::Ego input_msg)
void crp::apl::CtrlVehicleControlLatCompensatory::egoVehicleCallback(const crp_msgs::msg::Ego input_msg)
{
m_input.vxEgo = input_msg.twist.twist.linear.x;
m_input.egoSteeringAngle = input_msg.tire_angle_front;
Expand All @@ -72,7 +68,7 @@ void crp::apl::CtrlVehicleControlLat::egoVehicleCallback(const crp_msgs::msg::Eg
m_input.egoPoseGlobal[2] = theta;
}

void crp::apl::CtrlVehicleControlLat::loop()
void crp::apl::CtrlVehicleControlLatCompensatory::loop()
{
// parameter assignments
m_params.ffGainOffsetGround = this->get_parameter("/ctrl/ffGainOffsetGround").as_double();
Expand Down Expand Up @@ -103,7 +99,7 @@ void crp::apl::CtrlVehicleControlLat::loop()
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<crp::apl::CtrlVehicleControlLat>());
rclcpp::spin(std::make_shared<crp::apl::CtrlVehicleControlLatCompensatory>());
rclcpp::shutdown();
return 0;
}
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,8 @@ endif()
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(autoware_control_msgs REQUIRED)
find_package(autoware_planning_msgs REQUIRED)
find_package(autoware_vehicle_msgs REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(crp_msgs REQUIRED)


Expand All @@ -22,7 +18,7 @@ include_directories(include)

add_executable(ctrl_vehicle_control_lat_pure_p src/ctrl_vehicle_control_lat_pure_p.cpp)

ament_target_dependencies(ctrl_vehicle_control_lat_pure_p rclcpp geometry_msgs std_msgs autoware_control_msgs autoware_planning_msgs autoware_vehicle_msgs nav_msgs crp_msgs)
ament_target_dependencies(ctrl_vehicle_control_lat_pure_p rclcpp autoware_control_msgs autoware_planning_msgs crp_msgs)

install(DIRECTORY launch
DESTINATION share/${PROJECT_NAME})
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,14 @@ namespace crp
std::vector<double> m_path_x;
std::vector<double> m_path_y;
std::vector<double> m_path_theta;
double target_speed{0.0f};
double targetSpeed{0.0f};
double egoPoseGlobal [3]{0.0f};
double vxEgo{0.0f};
double egoSteeringAngle{0.0f};
};

struct ControlParams{
double lookahead_time{1.0f};
double lookaheadTime{1.0f};
double wheelbase{2.9f};
};
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@ namespace crp
namespace apl
{
struct ControlOutput{
double m_accelerationTarget{0.0f};
double m_steeringAngleTarget{0.0f};
double accelerationTarget{0.0f};
double steeringAngleTarget{0.0f};
};
}
}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,20 +1,12 @@
#ifndef CRP_APL_CTRL_VEHICLE_LAT_PURE_P_HPP
#define CRP_APL_CTRL_VEHICLE_LAT_PURE_P_HPP

#include <chrono>
#include <functional>
#include <memory>
#include <string>
#include <math.h>
#ifndef CRP_APL_CTRL_VEHICLE_CONTROL_LAT_PURE_P_CTRLVEHICLECONTROLLATPUREP_HPP
#define CRP_APL_CTRL_VEHICLE_CONTROL_LAT_PURE_P_CTRLVEHICLECONTROLLATPUREP_HPP


#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/pose.hpp"
#include "std_msgs/msg/float32_multi_array.hpp"
#include "std_msgs/msg/float32.hpp"
#include "crp_msgs/msg/ego.hpp"

#include "crp_msgs/msg/ego.hpp"
#include "autoware_control_msgs/msg/control.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"
#include "autoware_vehicle_msgs/msg/steering_report.hpp"

#include "ctrl_vehicle_control_lat_pure_p/controller_inputs.hpp"
#include "ctrl_vehicle_control_lat_pure_p/controller_outputs.hpp"
Expand All @@ -23,10 +15,10 @@ namespace crp
{
namespace apl
{
class CtrlVehicleControlLat : public rclcpp::Node
class CtrlVehicleControlLatPureP : public rclcpp::Node
{
public:
CtrlVehicleControlLat();
CtrlVehicleControlLatPureP();

private:
// VARIABLES
Expand All @@ -40,13 +32,13 @@ namespace crp
void pure_p_control();
void loop();

rclcpp::TimerBase::SharedPtr timer_;
rclcpp::TimerBase::SharedPtr m_timer_;
rclcpp::Publisher<autoware_control_msgs::msg::Lateral>::SharedPtr m_pub_cmd;

rclcpp::Subscription<autoware_planning_msgs::msg::Trajectory>::SharedPtr m_traj_sub_;
rclcpp::Subscription<crp_msgs::msg::Ego>::SharedPtr m_egoVehicle_sub_;
rclcpp::Subscription<autoware_planning_msgs::msg::Trajectory>::SharedPtr m_sub_traj_;
rclcpp::Subscription<crp_msgs::msg::Ego>::SharedPtr m_sub_egoVehicle_;
autoware_control_msgs::msg::Lateral m_ctrlCmdMsg;
};
} // namespace apl
}
#endif // CRP_APL_CTRL_VEHICLE_LAT_PURE_P_HPP
#endif // CRP_APL_CTRL_VEHICLE_CONTROL_LAT_PURE_P_CTRLVEHICLECONTROLLATPUREP_HPP
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,6 @@
from launch_ros.actions import Node

def generate_launch_description():
ld = LaunchDescription()

ctrl_vehicle_control_lat_pure_p = Node(
package="ctrl_vehicle_control_lat_pure_p",
executable="ctrl_vehicle_control_lat_pure_p",
Expand All @@ -13,6 +11,6 @@ def generate_launch_description():
]
)

ld.add_action(ctrl_vehicle_control_lat_pure_p)

return ld
return LaunchDescription([
ctrl_vehicle_control_lat_pure_p
])
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,8 @@
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<depend>rclcpp</depend>
<depend>geometry_msgs</depend>
<depend>std_msgs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>nav_msgs</depend>
<depend>crp_msgs</depend>

<export>
Expand Down
Loading