@@ -90,7 +90,7 @@ class Optimizer
9090 geometry_msgs::msg::TwistStamped evalControl (
9191 const geometry_msgs::msg::PoseStamped & robot_pose,
9292 const geometry_msgs::msg::Twist & robot_speed, const nav_msgs::msg::Path & plan,
93- nav2_core::GoalChecker * goal_checker);
93+ const geometry_msgs::msg::Pose & goal, nav2_core::GoalChecker * goal_checker);
9494
9595 /* *
9696 * @brief Get the trajectories generated in a cycle for visualization
@@ -132,7 +132,8 @@ class Optimizer
132132 void prepare (
133133 const geometry_msgs::msg::PoseStamped & robot_pose,
134134 const geometry_msgs::msg::Twist & robot_speed,
135- const nav_msgs::msg::Path & plan, nav2_core::GoalChecker * goal_checker);
135+ const nav_msgs::msg::Path & plan,
136+ const geometry_msgs::msg::Pose & goal, nav2_core::GoalChecker * goal_checker);
136137
137138 /* *
138139 * @brief Obtain the main controller's parameters
@@ -250,10 +251,12 @@ class Optimizer
250251 std::array<mppi::models::Control, 4 > control_history_;
251252 models::Trajectories generated_trajectories_;
252253 models::Path path_;
254+ geometry_msgs::msg::Pose goal_;
253255 xt::xtensor<float , 1 > costs_;
254256
255- CriticData critics_data_ =
256- {state_, generated_trajectories_, path_, costs_, settings_.model_dt , false , nullptr , nullptr ,
257+ CriticData critics_data_ = {
258+ state_, generated_trajectories_, path_, goal_,
259+ costs_, settings_.model_dt , false , nullptr , nullptr ,
257260 std::nullopt , std::nullopt }; // / Caution, keep references
258261
259262 rclcpp::Logger logger_{rclcpp::get_logger (" MPPIController" )};
0 commit comments