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

refactor: modify class names #48

Merged
merged 2 commits into from
Jul 17, 2024
Merged
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
44 changes: 23 additions & 21 deletions src/autoware_practice_course/src/avoidance/trajectory_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
namespace autoware_practice_course
{

SampleNode::SampleNode()
TrajectoryPlannerNode::TrajectoryPlannerNode()
: Node("trajectory_planner"),
GRID_RESOLUTION_(1), // 1セルのサイズ(メートル)
GRID_WIDTH_(100.0), // コストマップの幅(メートル)
Expand Down Expand Up @@ -61,39 +61,40 @@ SampleNode::SampleNode()
pub_costmap_ =
create_publisher<autoware_practice_msgs::msg::FloatGrid>("/planning/scenario_planning/costmap", rclcpp::QoS(1));
sub_kinematic_state_ = create_subscription<Odometry>(
"/localization/kinematic_state", rclcpp::QoS(1), std::bind(&SampleNode::update_current_state, this, _1));
"/localization/kinematic_state", rclcpp::QoS(1), std::bind(&TrajectoryPlannerNode::update_current_state, this, _1));
sub_trajectory_ = create_subscription<Trajectory>(
"/planning/trajectory_loader/trajectory", rclcpp::QoS(1),
std::bind(&SampleNode::update_reference_trajectory, this, _1));
std::bind(&TrajectoryPlannerNode::update_reference_trajectory, this, _1));
sub_pointcloud_ = create_subscription<PointCloud2>(
"/perception/obstacle_segmentation/pointcloud", rclcpp::QoS(1),
std::bind(&SampleNode::update_pointcloud, this, _1));
std::bind(&TrajectoryPlannerNode::update_pointcloud, this, _1));

const auto period = rclcpp::Rate(10).period();
timer_ = rclcpp::create_timer(this, get_clock(), period, [this] { on_timer(); });
}

void SampleNode::update_current_state(const Odometry & msg) // called by sub_kinematic_state_
void TrajectoryPlannerNode::update_current_state(const Odometry & msg) // called by sub_kinematic_state_
{
current_velocity_ = msg.twist.twist.linear.x;
current_position_ = msg.pose.pose.position;
current_orientation_ = msg.pose.pose.orientation;
current_state_initialized_ = true;
};

void SampleNode::update_reference_trajectory(const Trajectory & msg) // called by sub_trajectory_
void TrajectoryPlannerNode::update_reference_trajectory(const Trajectory & msg) // called by sub_trajectory_

{
reference_trajectory_ = msg;
reference_trajectory_initialized_ = true;
};

void SampleNode::update_pointcloud(const PointCloud2 & msg) // called by sub_pointcloud_
void TrajectoryPlannerNode::update_pointcloud(const PointCloud2 & msg) // called by sub_pointcloud_
{
pointcloud_ = msg;
pointcloud_initialized_ = true;
};

void SampleNode::on_timer()
void TrajectoryPlannerNode::on_timer()
{
if (!current_state_initialized_ || !reference_trajectory_initialized_ || !pointcloud_initialized_) {
RCLCPP_WARN(this->get_logger(), "Waiting for all initial data to be received.");
Expand All @@ -114,7 +115,7 @@ void SampleNode::on_timer()
}
}

void SampleNode::create_trajectory() // called by on_timer()
void TrajectoryPlannerNode::create_trajectory() // called by on_timer()
{
// state lattice planner
// create trajectory library
Expand All @@ -127,7 +128,7 @@ void SampleNode::create_trajectory() // called by on_timer()
best_trajectory_ = evaluate_trajectory(trajectory_set, costmap_);
}

std::vector<SampleNode::Trajectory> SampleNode::create_trajectory_set()
std::vector<TrajectoryPlannerNode::Trajectory> TrajectoryPlannerNode::create_trajectory_set()
{
// 目標状態集合を計算
std::vector<TrajectoryPoint> target_trajectory_point_set = create_target_state_set();
Expand Down Expand Up @@ -178,7 +179,7 @@ std::vector<SampleNode::Trajectory> SampleNode::create_trajectory_set()
return trajectory_set;
}

std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> SampleNode::create_target_state_set()
std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> TrajectoryPlannerNode::create_target_state_set()
{
if (reference_trajectory_.points.empty()) {
RCLCPP_ERROR(this->get_logger(), "Reference trajectory is empty.");
Expand Down Expand Up @@ -244,12 +245,12 @@ geometry_msgs::msg::Point operator+(const geometry_msgs::msg::Point & p1, const
return result;
}

Eigen::Vector3d SampleNode::pointToVector3d(const geometry_msgs::msg::Point & point)
Eigen::Vector3d TrajectoryPlannerNode::pointToVector3d(const geometry_msgs::msg::Point & point)
{
return Eigen::Vector3d(point.x, point.y, point.z);
}

geometry_msgs::msg::Point SampleNode::vector3dToPoint(const Eigen::Vector3d & vector)
geometry_msgs::msg::Point TrajectoryPlannerNode::vector3dToPoint(const Eigen::Vector3d & vector)
{
geometry_msgs::msg::Point point;
point.x = vector.x();
Expand All @@ -258,7 +259,7 @@ geometry_msgs::msg::Point SampleNode::vector3dToPoint(const Eigen::Vector3d & ve
return point;
}

Eigen::Quaterniond SampleNode::vectorToQuaternion(const Eigen::Vector3d & start, const Eigen::Vector3d & end)
Eigen::Quaterniond TrajectoryPlannerNode::vectorToQuaternion(const Eigen::Vector3d & start, const Eigen::Vector3d & end)
{
Eigen::Vector3d direction = (end - start).normalized();
Eigen::Vector3d referenceVector(1.0, 0.0, 0.0);
Expand All @@ -269,7 +270,7 @@ Eigen::Quaterniond SampleNode::vectorToQuaternion(const Eigen::Vector3d & start,
return q;
}

std::vector<std::vector<float>> SampleNode::create_costmap()
std::vector<std::vector<float>> TrajectoryPlannerNode::create_costmap()
{
pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud_pcl(new pcl::PointCloud<pcl::PointXYZ>());
// 変換関数を呼び出し
Expand Down Expand Up @@ -309,8 +310,9 @@ std::vector<std::vector<float>> SampleNode::create_costmap()
return costmap;
}

SampleNode::Trajectory SampleNode::evaluate_trajectory(
const std::vector<SampleNode::Trajectory> & trajectory_set, const std::vector<std::vector<float>> & costmap)
TrajectoryPlannerNode::Trajectory TrajectoryPlannerNode::evaluate_trajectory(
const std::vector<TrajectoryPlannerNode::Trajectory> & trajectory_set,
const std::vector<std::vector<float>> & costmap)
{
Trajectory best_trajectory;
std::vector<float> trajectory_cost(trajectory_set.size(), 0.0f);
Expand Down Expand Up @@ -342,20 +344,20 @@ SampleNode::Trajectory SampleNode::evaluate_trajectory(
return best_trajectory;
}

double SampleNode::quaternionToInclination(Eigen::Quaterniond q)
double TrajectoryPlannerNode::quaternionToInclination(Eigen::Quaterniond q)
{
double inclination = 2.0 * q.z() / q.w();
return inclination;
}

Eigen::Vector3d SampleNode::quaternionToVector(Eigen::Quaterniond q)
Eigen::Vector3d TrajectoryPlannerNode::quaternionToVector(Eigen::Quaterniond q)
{
Eigen::Vector3d unitVector(1, 0, 0);
Eigen::Vector3d directionVector = q * unitVector;
return directionVector;
}
// ベジエ曲線で補間する関数
std::vector<geometry_msgs::msg::Point> SampleNode::bezierInterpolate(
std::vector<geometry_msgs::msg::Point> TrajectoryPlannerNode::bezierInterpolate(
const geometry_msgs::msg::Point & p0, const geometry_msgs::msg::Point & p1, Eigen::Vector3d m0, Eigen::Vector3d m1)
{
std::vector<geometry_msgs::msg::Point> interpolatedPoints;
Expand Down Expand Up @@ -390,7 +392,7 @@ std::vector<geometry_msgs::msg::Point> SampleNode::bezierInterpolate(
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<autoware_practice_course::SampleNode>();
auto node = std::make_shared<autoware_practice_course::TrajectoryPlannerNode>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,10 @@ namespace autoware_practice_course
{
geometry_msgs::msg::Point operator+(const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2);

class SampleNode : public rclcpp::Node
class TrajectoryPlannerNode : public rclcpp::Node
{
public:
SampleNode();
TrajectoryPlannerNode();

private:
using Trajectory = autoware_auto_planning_msgs::msg::Trajectory;
Expand Down
4 changes: 2 additions & 2 deletions src/autoware_practice_course/src/vehicle/forward.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@ void SampleNode::on_timer()

AckermannControlCommand command;
command.stamp = stamp;
command.longitudinal.speed = 0.0;
command.longitudinal.acceleration = -2.5;
command.longitudinal.speed = 3.0;
command.longitudinal.acceleration = 1.0;
command.lateral.steering_tire_angle = 0.0;
pub_command_->publish(command);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,23 +20,25 @@
namespace autoware_practice_course
{

SampleNode::SampleNode() : Node("longitudinal_controller"), kp_(0.0)
LongitudinalControllerNode::LongitudinalControllerNode() : Node("longitudinal_controller"), kp_(0.0)
{
using std::placeholders::_1;
declare_parameter<double>("kp", kp_);
get_parameter("kp", kp_);

pub_command_ = create_publisher<AckermannControlCommand>("/control/command/control_cmd", rclcpp::QoS(1));
sub_trajectory_ = create_subscription<Trajectory>(
"/planning/scenario_planning/trajectory", rclcpp::QoS(1), std::bind(&SampleNode::update_target_velocity, this, _1));
"/planning/scenario_planning/trajectory", rclcpp::QoS(1),
std::bind(&LongitudinalControllerNode::update_target_velocity, this, _1));
sub_kinematic_state_ = create_subscription<Odometry>(
"/localization/kinematic_state", rclcpp::QoS(1), std::bind(&SampleNode::update_current_state, this, _1));
"/localization/kinematic_state", rclcpp::QoS(1),
std::bind(&LongitudinalControllerNode::update_current_state, this, _1));

const auto period = rclcpp::Rate(10).period();
timer_ = rclcpp::create_timer(this, get_clock(), period, [this] { on_timer(); });
}

void SampleNode::update_target_velocity(const Trajectory & msg)
void LongitudinalControllerNode::update_target_velocity(const Trajectory & msg)
{
double min_distance = std::numeric_limits<double>::max();
size_t closest_waypoint_index = 0;
Expand All @@ -56,13 +58,13 @@ void SampleNode::update_target_velocity(const Trajectory & msg)
target_velocity_ = msg.points[closest_waypoint_index].longitudinal_velocity_mps;
};

void SampleNode::update_current_state(const Odometry & msg)
void LongitudinalControllerNode::update_current_state(const Odometry & msg)
{
current_velocity_ = msg.twist.twist.linear.x;
current_pose_ = msg.pose.pose.position; // 現在の車両の位置を更新する
};

void SampleNode::on_timer()
void LongitudinalControllerNode::on_timer()
{
const auto stamp = now();

Expand All @@ -84,7 +86,7 @@ void SampleNode::on_timer()
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<autoware_practice_course::SampleNode>();
auto node = std::make_shared<autoware_practice_course::LongitudinalControllerNode>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,10 +23,10 @@
namespace autoware_practice_course
{

class SampleNode : public rclcpp::Node
class LongitudinalControllerNode : public rclcpp::Node
{
public:
SampleNode();
LongitudinalControllerNode();

private:
using Trajectory = autoware_auto_planning_msgs::msg::Trajectory;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
namespace autoware_practice_course
{

SampleNode::SampleNode() : Node("p_controller")
PControllerNode::PControllerNode() : Node("p_controller")
{
declare_parameter<double>("kp", 0.0);
declare_parameter<double>("target_velocity", 1.0);
Expand All @@ -37,7 +37,7 @@ SampleNode::SampleNode() : Node("p_controller")
timer_ = rclcpp::create_timer(this, get_clock(), period, [this] { on_timer(); });
}

void SampleNode::on_timer()
void PControllerNode::on_timer()
{
const auto stamp = now();

Expand All @@ -58,7 +58,7 @@ void SampleNode::on_timer()
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<autoware_practice_course::SampleNode>();
auto node = std::make_shared<autoware_practice_course::PControllerNode>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,10 @@
namespace autoware_practice_course
{

class SampleNode : public rclcpp::Node
class PControllerNode : public rclcpp::Node
{
public:
SampleNode();
PControllerNode();

private:
using AckermannControlCommand = autoware_auto_control_msgs::msg::AckermannControlCommand;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
namespace autoware_practice_course
{

SampleNode::SampleNode() : Node("trajectory_follower"), kp_(0.0), lookahead_distance_(5.0)
TrajectoryFollowerNode::TrajectoryFollowerNode() : Node("trajectory_follower"), kp_(0.0), lookahead_distance_(5.0)
{
using std::placeholders::_1;
declare_parameter<double>("kp", kp_);
Expand All @@ -34,15 +34,17 @@ SampleNode::SampleNode() : Node("trajectory_follower"), kp_(0.0), lookahead_dist

pub_command_ = create_publisher<AckermannControlCommand>("/control/command/control_cmd", rclcpp::QoS(1));
sub_trajectory_ = create_subscription<Trajectory>(
"/planning/scenario_planning/trajectory", rclcpp::QoS(1), std::bind(&SampleNode::update_target_velocity, this, _1));
"/planning/scenario_planning/trajectory", rclcpp::QoS(1),
std::bind(&TrajectoryFollowerNode::update_target_velocity, this, _1));
sub_kinematic_state_ = create_subscription<Odometry>(
"/localization/kinematic_state", rclcpp::QoS(1), std::bind(&SampleNode::update_current_state, this, _1));
"/localization/kinematic_state", rclcpp::QoS(1),
std::bind(&TrajectoryFollowerNode::update_current_state, this, _1));

const auto period = rclcpp::Rate(10).period();
timer_ = rclcpp::create_timer(this, get_clock(), period, [this] { on_timer(); });
}

void SampleNode::update_target_velocity(const Trajectory & msg)
void TrajectoryFollowerNode::update_target_velocity(const Trajectory & msg)
{
double min_distance = std::numeric_limits<double>::max();

Expand All @@ -62,7 +64,7 @@ void SampleNode::update_target_velocity(const Trajectory & msg)
target_velocity_ = msg.points[closest_point_index_].longitudinal_velocity_mps;
};

double SampleNode::load_parameters(const std::string & param_file, const std::string & param_tag)
double TrajectoryFollowerNode::load_parameters(const std::string & param_file, const std::string & param_tag)
{
std::ifstream file(param_file);
if (!file.is_open()) {
Expand All @@ -85,14 +87,14 @@ double SampleNode::load_parameters(const std::string & param_file, const std::st
return -1.0;
}

void SampleNode::update_current_state(const Odometry & msg)
void TrajectoryFollowerNode::update_current_state(const Odometry & msg)
{
current_velocity_ = msg.twist.twist.linear.x;
current_position_ = msg.pose.pose.position;
current_orientation_ = msg.pose.pose.orientation;
};

void SampleNode::on_timer()
void TrajectoryFollowerNode::on_timer()
{
const auto stamp = now();

Expand All @@ -108,12 +110,12 @@ void SampleNode::on_timer()
pub_command_->publish(command);
}

double SampleNode::longitudinal_controller(double velocity_error)
double TrajectoryFollowerNode::longitudinal_controller(double velocity_error)
{
return kp_ * velocity_error;
}

double SampleNode::lateral_controller()
double TrajectoryFollowerNode::lateral_controller()
{
double min_distance = std::numeric_limits<double>::max();
size_t lookahead_point_index = closest_point_index_;
Expand Down Expand Up @@ -141,7 +143,7 @@ double SampleNode::lateral_controller()
return steering_angle;
}

double SampleNode::calculate_yaw_from_quaternion(const geometry_msgs::msg::Quaternion & q)
double TrajectoryFollowerNode::calculate_yaw_from_quaternion(const geometry_msgs::msg::Quaternion & q)
{
// Convert quaternion to Euler angles
double siny_cosp = 2 * (q.w * q.z + q.x * q.y);
Expand All @@ -156,7 +158,7 @@ double SampleNode::calculate_yaw_from_quaternion(const geometry_msgs::msg::Quate
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<autoware_practice_course::SampleNode>();
auto node = std::make_shared<autoware_practice_course::TrajectoryFollowerNode>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,10 +28,10 @@
namespace autoware_practice_course
{

class SampleNode : public rclcpp::Node
class TrajectoryFollowerNode : public rclcpp::Node
{
public:
SampleNode();
TrajectoryFollowerNode();

private:
using Trajectory = autoware_auto_planning_msgs::msg::Trajectory;
Expand Down
Loading
Loading