26 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_COST_FUNCTIONS_TOOL_GOAL_POSE_H_ 27 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_COST_FUNCTIONS_TOOL_GOAL_POSE_H_ 29 #include <Eigen/Sparse> 36 namespace cost_functions
60 virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
79 const moveit_msgs::MotionPlanRequest &req,
81 moveit_msgs::MoveItErrorCodes& error_code)
override;
95 virtual bool computeCosts(
const Eigen::MatrixXd& parameters,
96 std::size_t start_timestep,
97 std::size_t num_timesteps,
100 Eigen::VectorXd& costs,
101 bool& validity)
override;
122 virtual void done(
bool success,
int total_iterations,
double final_cost,
const Eigen::MatrixXd& parameters)
override;