Skip to content

Commit

Permalink
feat(motion_utils, etc): add header argument in convertToTrajectory (#…
Browse files Browse the repository at this point in the history
…6021)

* feat(motion_utils, etc): add header argument in convertToTrajectory

Signed-off-by: Takayuki Murooka <[email protected]>

* fix include

Signed-off-by: Takayuki Murooka <[email protected]>

---------

Signed-off-by: Takayuki Murooka <[email protected]>
  • Loading branch information
takayuki5168 authored Jan 7, 2024
1 parent 4784c33 commit eb09f68
Show file tree
Hide file tree
Showing 15 changed files with 26 additions and 72 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include "autoware_auto_planning_msgs/msg/detail/trajectory__struct.hpp"
#include "autoware_auto_planning_msgs/msg/detail/trajectory_point__struct.hpp"
#include "std_msgs/msg/header.hpp"

#include <vector>

Expand All @@ -34,7 +35,8 @@ namespace motion_utils
* points larger than the capacity. (Tier IV)
*/
autoware_auto_planning_msgs::msg::Trajectory convertToTrajectory(
const std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> & trajectory);
const std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> & trajectory,
const std_msgs::msg::Header & header = std_msgs::msg::Header{});

/**
* @brief Convert autoware_auto_planning_msgs::msg::Trajectory to
Expand Down
4 changes: 3 additions & 1 deletion common/motion_utils/src/trajectory/conversion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,11 @@ namespace motion_utils
* points larger than the capacity. (Tier IV)
*/
autoware_auto_planning_msgs::msg::Trajectory convertToTrajectory(
const std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> & trajectory)
const std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> & trajectory,
const std_msgs::msg::Header & header)
{
autoware_auto_planning_msgs::msg::Trajectory output{};
output.header = header;
for (const auto & pt : trajectory) output.points.push_back(pt);
return output;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -154,9 +154,6 @@ size_t findEgoSegmentIndex(
points, ego_pose, ego_nearest_param.dist_threshold, ego_nearest_param.yaw_threshold);
}

Trajectory createTrajectory(
const std_msgs::msg::Header & header, const std::vector<TrajectoryPoint> & traj_points);

std::vector<TrajectoryPoint> resampleTrajectoryPoints(
const std::vector<TrajectoryPoint> traj_points, const double interval);

Expand Down
9 changes: 5 additions & 4 deletions planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include "obstacle_avoidance_planner/mpt_optimizer.hpp"

#include "interpolation/spline_interpolation_points_2d.hpp"
#include "motion_utils/trajectory/conversion.hpp"
#include "motion_utils/trajectory/trajectory.hpp"
#include "obstacle_avoidance_planner/utils/geometry_utils.hpp"
#include "obstacle_avoidance_planner/utils/trajectory_utils.hpp"
Expand Down Expand Up @@ -1708,17 +1709,17 @@ void MPTOptimizer::publishDebugTrajectories(
time_keeper_ptr_->tic(__func__);

// reference points
const auto ref_traj = trajectory_utils::createTrajectory(
header, trajectory_utils::convertToTrajectoryPoints(ref_points));
const auto ref_traj = motion_utils::convertToTrajectory(
trajectory_utils::convertToTrajectoryPoints(ref_points), header);
debug_ref_traj_pub_->publish(ref_traj);

// fixed reference points
const auto fixed_traj_points = extractFixedPoints(ref_points);
const auto fixed_traj = trajectory_utils::createTrajectory(header, fixed_traj_points);
const auto fixed_traj = motion_utils::convertToTrajectory(fixed_traj_points, header);
debug_fixed_traj_pub_->publish(fixed_traj);

// mpt points
const auto mpt_traj = trajectory_utils::createTrajectory(header, mpt_traj_points);
const auto mpt_traj = motion_utils::convertToTrajectory(mpt_traj_points, header);
debug_mpt_traj_pub_->publish(mpt_traj);

time_keeper_ptr_->toc(__func__, " ");
Expand Down
7 changes: 4 additions & 3 deletions planning/obstacle_avoidance_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include "interpolation/spline_interpolation_points_2d.hpp"
#include "motion_utils/marker/marker_helper.hpp"
#include "motion_utils/trajectory/conversion.hpp"
#include "obstacle_avoidance_planner/debug_marker.hpp"
#include "obstacle_avoidance_planner/utils/geometry_utils.hpp"
#include "obstacle_avoidance_planner/utils/trajectory_utils.hpp"
Expand Down Expand Up @@ -236,7 +237,7 @@ void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr)
"Backward path is NOT supported. Just converting path to trajectory");

const auto traj_points = trajectory_utils::convertToTrajectoryPoints(path_ptr->points);
const auto output_traj_msg = trajectory_utils::createTrajectory(path_ptr->header, traj_points);
const auto output_traj_msg = motion_utils::convertToTrajectory(traj_points, path_ptr->header);
traj_pub_->publish(output_traj_msg);
return;
}
Expand Down Expand Up @@ -268,7 +269,7 @@ void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr)
createFloat64Stamped(now(), time_keeper_ptr_->getAccumulatedTime()));

const auto output_traj_msg =
trajectory_utils::createTrajectory(path_ptr->header, full_traj_points);
motion_utils::convertToTrajectory(full_traj_points, path_ptr->header);
traj_pub_->publish(output_traj_msg);
}

Expand Down Expand Up @@ -656,7 +657,7 @@ void ObstacleAvoidancePlanner::publishDebugData(const Header & header) const

// publish trajectories
const auto debug_extended_traj =
trajectory_utils::createTrajectory(header, debug_data_ptr_->extended_traj_points);
motion_utils::convertToTrajectory(debug_data_ptr_->extended_traj_points, header);
debug_extended_traj_pub_->publish(debug_extended_traj);

time_keeper_ptr_->toc(__func__, " ");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -117,15 +117,6 @@ geometry_msgs::msg::Point getNearestPosition(
return points.back().pose.position;
}

Trajectory createTrajectory(
const std_msgs::msg::Header & header, const std::vector<TrajectoryPoint> & traj_points)
{
auto traj = motion_utils::convertToTrajectory(traj_points);
traj.header = header;

return traj;
}

std::vector<TrajectoryPoint> resampleTrajectoryPoints(
const std::vector<TrajectoryPoint> traj_points, const double interval)
{
Expand Down
11 changes: 1 addition & 10 deletions planning/obstacle_cruise_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,15 +171,6 @@ std::vector<TrajectoryPoint> extendTrajectoryPoints(
return output_points;
}

Trajectory createTrajectory(
const std::vector<TrajectoryPoint> & traj_points, const std_msgs::msg::Header & header)
{
auto traj = motion_utils::convertToTrajectory(traj_points);
traj.header = header;

return traj;
}

std::vector<int> getTargetObjectType(rclcpp::Node & node, const std::string & param_prefix)
{
std::unordered_map<std::string, int> types_map{
Expand Down Expand Up @@ -525,7 +516,7 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms
publishVelocityLimit(slow_down_vel_limit, "slow_down");

// 7. Publish trajectory
const auto output_traj = createTrajectory(slow_down_traj_points, msg->header);
const auto output_traj = motion_utils::convertToTrajectory(slow_down_traj_points, msg->header);
trajectory_pub_->publish(output_traj);

// 8. Publish debug data
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,9 +113,6 @@ size_t findEgoSegmentIndex(
points, ego_pose, ego_nearest_param.dist_threshold, ego_nearest_param.yaw_threshold);
}

Trajectory createTrajectory(
const std_msgs::msg::Header & header, const std::vector<TrajectoryPoint> & traj_points);

Path create_path(Path path_msg, const std::vector<TrajectoryPoint> & traj_points);

std::vector<TrajectoryPoint> resampleTrajectoryPoints(
Expand Down
5 changes: 3 additions & 2 deletions planning/path_smoother/src/elastic_band.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include "path_smoother/elastic_band.hpp"

#include "motion_utils/trajectory/conversion.hpp"
#include "motion_utils/trajectory/trajectory.hpp"
#include "path_smoother/type_alias.hpp"
#include "path_smoother/utils/geometry_utils.hpp"
Expand Down Expand Up @@ -262,7 +263,7 @@ std::vector<TrajectoryPoint> EBPathSmoother::smoothTrajectory(

// 8. publish eb trajectory
const auto eb_traj =
trajectory_utils::createTrajectory(createHeader(clock_.now()), *eb_traj_points);
motion_utils::convertToTrajectory(*eb_traj_points, createHeader(clock_.now()));
debug_eb_traj_pub_->publish(eb_traj);

time_keeper_ptr_->toc(__func__, " ");
Expand Down Expand Up @@ -389,7 +390,7 @@ void EBPathSmoother::updateConstraint(

// publish fixed trajectory
const auto eb_fixed_traj =
trajectory_utils::createTrajectory(createHeader(clock_.now()), debug_fixed_traj_points);
motion_utils::convertToTrajectory(debug_fixed_traj_points, createHeader(clock_.now()));
debug_eb_fixed_traj_pub_->publish(eb_fixed_traj);

time_keeper_ptr_->toc(__func__, " ");
Expand Down
5 changes: 3 additions & 2 deletions planning/path_smoother/src/elastic_band_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include "path_smoother/elastic_band_smoother.hpp"

#include "interpolation/spline_interpolation_points_2d.hpp"
#include "motion_utils/trajectory/conversion.hpp"
#include "path_smoother/utils/geometry_utils.hpp"
#include "path_smoother/utils/trajectory_utils.hpp"
#include "rclcpp/time.hpp"
Expand Down Expand Up @@ -167,7 +168,7 @@ void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr)
"Backward path is NOT supported. Just converting path to trajectory");

const auto traj_points = trajectory_utils::convertToTrajectoryPoints(path_ptr->points);
const auto output_traj_msg = trajectory_utils::createTrajectory(path_ptr->header, traj_points);
const auto output_traj_msg = motion_utils::convertToTrajectory(traj_points, path_ptr->header);
traj_pub_->publish(output_traj_msg);
path_pub_->publish(*path_ptr);
return;
Expand Down Expand Up @@ -220,7 +221,7 @@ void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr)
createFloat64Stamped(now(), time_keeper_ptr_->getAccumulatedTime()));

const auto output_traj_msg =
trajectory_utils::createTrajectory(path_ptr->header, full_traj_points);
motion_utils::convertToTrajectory(full_traj_points, path_ptr->header);
traj_pub_->publish(output_traj_msg);
const auto output_path_msg = trajectory_utils::create_path(*path_ptr, full_traj_points);
path_pub_->publish(output_path_msg);
Expand Down
9 changes: 0 additions & 9 deletions planning/path_smoother/src/utils/trajectory_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,15 +34,6 @@ namespace path_smoother
{
namespace trajectory_utils
{
Trajectory createTrajectory(
const std_msgs::msg::Header & header, const std::vector<TrajectoryPoint> & traj_points)
{
auto traj = motion_utils::convertToTrajectory(traj_points);
traj.header = header;

return traj;
}

Path create_path(Path path_msg, const std::vector<TrajectoryPoint> & traj_points)
{
path_msg.points.clear();
Expand Down
11 changes: 1 addition & 10 deletions planning/planning_topic_converter/src/path_to_trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,15 +40,6 @@ std::vector<TrajectoryPoint> convertToTrajectoryPoints(const std::vector<PathPoi
}
return traj_points;
}

Trajectory createTrajectory(
const std_msgs::msg::Header & header, const std::vector<TrajectoryPoint> & trajectory_points)
{
auto trajectory = motion_utils::convertToTrajectory(trajectory_points);
trajectory.header = header;

return trajectory;
}
} // namespace

PathToTrajectory::PathToTrajectory(const rclcpp::NodeOptions & options)
Expand All @@ -59,7 +50,7 @@ PathToTrajectory::PathToTrajectory(const rclcpp::NodeOptions & options)
void PathToTrajectory::process(const Path::ConstSharedPtr msg)
{
const auto trajectory_points = convertToTrajectoryPoints(msg->points);
const auto output = createTrajectory(msg->header, trajectory_points);
const auto output = motion_utils::convertToTrajectory(trajectory_points, msg->header);
pub_->publish(output);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -138,9 +138,6 @@ size_t findEgoSegmentIndex(
points, ego_pose, ego_nearest_param.dist_threshold, ego_nearest_param.yaw_threshold);
}

Trajectory createTrajectory(
const std_msgs::msg::Header & header, const std::vector<TrajectoryPoint> & traj_points);

std::vector<TrajectoryPoint> resampleTrajectoryPoints(
const std::vector<TrajectoryPoint> traj_points, const double interval);

Expand Down
6 changes: 3 additions & 3 deletions planning/sampling_based_planner/path_sampler/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include "interpolation/spline_interpolation_points_2d.hpp"
#include "motion_utils/marker/marker_helper.hpp"
#include "motion_utils/trajectory/conversion.hpp"
#include "path_sampler/path_generation.hpp"
#include "path_sampler/prepare_inputs.hpp"
#include "path_sampler/utils/geometry_utils.hpp"
Expand Down Expand Up @@ -244,13 +245,12 @@ void PathSampler::onPath(const Path::SharedPtr path_ptr)
if (!generated_traj_points.empty()) {
auto full_traj_points = extendTrajectory(planner_data.traj_points, generated_traj_points);
const auto output_traj_msg =
trajectory_utils::createTrajectory(path_ptr->header, full_traj_points);
motion_utils::convertToTrajectory(full_traj_points, path_ptr->header);
traj_pub_->publish(output_traj_msg);
} else {
auto stopping_traj = trajectory_utils::convertToTrajectoryPoints(planner_data.traj_points);
for (auto & p : stopping_traj) p.longitudinal_velocity_mps = 0.0;
const auto output_traj_msg =
trajectory_utils::createTrajectory(path_ptr->header, stopping_traj);
const auto output_traj_msg = motion_utils::convertToTrajectory(stopping_traj, path_ptr->header);
traj_pub_->publish(output_traj_msg);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,15 +58,6 @@ void compensateLastPose(
}
}

Trajectory createTrajectory(
const std_msgs::msg::Header & header, const std::vector<TrajectoryPoint> & traj_points)
{
auto traj = motion_utils::convertToTrajectory(traj_points);
traj.header = header;

return traj;
}

std::vector<TrajectoryPoint> resampleTrajectoryPoints(
const std::vector<TrajectoryPoint> traj_points, const double interval)
{
Expand Down

0 comments on commit eb09f68

Please sign in to comment.