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

fix(planning): fix -Werror=deprecated-declaration #4414

Merged
merged 1 commit into from
Jul 27, 2023
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
Original file line number Diff line number Diff line change
Expand Up @@ -62,11 +62,12 @@ MotionVelocitySmootherNode::MotionVelocitySmootherNode(const rclcpp::NodeOptions
"~/input/external_velocity_limit_mps", 1,
std::bind(&MotionVelocitySmootherNode::onExternalVelocityLimit, this, _1));
sub_current_acceleration_ = create_subscription<AccelWithCovarianceStamped>(
"~/input/acceleration", 1,
[this](const AccelWithCovarianceStamped::SharedPtr msg) { current_acceleration_ptr_ = msg; });
"~/input/acceleration", 1, [this](const AccelWithCovarianceStamped::ConstSharedPtr msg) {
current_acceleration_ptr_ = msg;
});
sub_operation_mode_ = create_subscription<OperationModeState>(
"~/input/operation_mode_state", 1,
[this](const OperationModeState::SharedPtr msg) { operation_mode_ = *msg; });
[this](const OperationModeState::ConstSharedPtr msg) { operation_mode_ = *msg; });

// parameter update
set_param_res_ = this->add_on_set_parameters_callback(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ class ObstacleAvoidancePlanner : public rclcpp::Node
EgoNearestParam ego_nearest_param_{};

// variables for subscribers
Odometry::SharedPtr ego_state_ptr_;
Odometry::ConstSharedPtr ego_state_ptr_;

// interface publisher
rclcpp::Publisher<Trajectory>::SharedPtr traj_pub_;
Expand All @@ -97,7 +97,7 @@ class ObstacleAvoidancePlanner : public rclcpp::Node
OnSetParametersCallbackHandle::SharedPtr set_param_res_;

// subscriber callback function
void onPath(const Path::SharedPtr);
void onPath(const Path::ConstSharedPtr path_ptr);

// reset functions
void initializePlanning();
Expand Down
4 changes: 2 additions & 2 deletions planning/obstacle_avoidance_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ ObstacleAvoidancePlanner::ObstacleAvoidancePlanner(const rclcpp::NodeOptions & n
path_sub_ = create_subscription<Path>(
"~/input/path", 1, std::bind(&ObstacleAvoidancePlanner::onPath, this, std::placeholders::_1));
odom_sub_ = create_subscription<Odometry>(
"~/input/odometry", 1, [this](const Odometry::SharedPtr msg) { ego_state_ptr_ = msg; });
"~/input/odometry", 1, [this](const Odometry::ConstSharedPtr msg) { ego_state_ptr_ = msg; });

// debug publisher
debug_extended_traj_pub_ = create_publisher<Trajectory>("~/debug/extended_traj", 1);
Expand Down Expand Up @@ -189,7 +189,7 @@ void ObstacleAvoidancePlanner::resetPreviousData()
mpt_optimizer_ptr_->resetPreviousData();
}

void ObstacleAvoidancePlanner::onPath(const Path::SharedPtr path_ptr)
void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr)
{
time_keeper_ptr_->init();
time_keeper_ptr_->tic(__func__);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ class ElasticBandSmoother : public rclcpp::Node
EgoNearestParam ego_nearest_param_{};

// variables for subscribers
Odometry::SharedPtr ego_state_ptr_;
Odometry::ConstSharedPtr ego_state_ptr_;

// variables for previous information
std::shared_ptr<std::vector<TrajectoryPoint>> prev_optimized_traj_points_ptr_;
Expand All @@ -88,7 +88,7 @@ class ElasticBandSmoother : public rclcpp::Node
OnSetParametersCallbackHandle::SharedPtr set_param_res_;

// subscriber callback function
void onPath(const Path::SharedPtr);
void onPath(const Path::ConstSharedPtr path_ptr);

// reset functions
void initializePlanning();
Expand Down
4 changes: 2 additions & 2 deletions planning/path_smoother/src/elastic_band_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ ElasticBandSmoother::ElasticBandSmoother(const rclcpp::NodeOptions & node_option
path_sub_ = create_subscription<Path>(
"~/input/path", 1, std::bind(&ElasticBandSmoother::onPath, this, std::placeholders::_1));
odom_sub_ = create_subscription<Odometry>(
"~/input/odometry", 1, [this](const Odometry::SharedPtr msg) { ego_state_ptr_ = msg; });
"~/input/odometry", 1, [this](const Odometry::ConstSharedPtr msg) { ego_state_ptr_ = msg; });

// debug publisher
debug_extended_traj_pub_ = create_publisher<Trajectory>("~/debug/extended_traj", 1);
Expand Down Expand Up @@ -134,7 +134,7 @@ void ElasticBandSmoother::resetPreviousData()
prev_optimized_traj_points_ptr_ = nullptr;
}

void ElasticBandSmoother::onPath(const Path::SharedPtr path_ptr)
void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr)
{
time_keeper_ptr_->init();
time_keeper_ptr_->tic(__func__);
Expand Down