27 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_CONSTRAINED_CARTESIAN_GOAL_H_ 28 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_CONSTRAINED_CARTESIAN_GOAL_H_ 59 virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
78 const moveit_msgs::MotionPlanRequest &req,
80 moveit_msgs::MoveItErrorCodes& error_code)
override;
93 virtual bool filter(std::size_t start_timestep,
94 std::size_t num_timesteps,
96 const Eigen::MatrixXd& parameters,
97 Eigen::MatrixXd& updates,
98 bool& filtered)
override;
virtual bool filter(std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, const Eigen::MatrixXd ¶meters, Eigen::MatrixXd &updates, bool &filtered) override
Forces the goal to be within the tool's task manifold.
virtual ~ConstrainedCartesianGoal()
virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::MotionPlanRequest &req, const stomp_core::StompConfiguration &config, moveit_msgs::MoveItErrorCodes &error_code) override
Stores the planning details.
moveit::core::RobotModelConstPtr robot_model_
Eigen::VectorXd tool_goal_tolerance_
Eigen::Affine3d tool_goal_pose_
The desired goal pose for the active plan request.
virtual bool configure(const XmlRpc::XmlRpcValue &config) override
Sets internal members of the plugin from the configuration data.
virtual std::string getGroupName() const
virtual std::string getName() const
Forces the goal cartesian tool pose into the task space.
stomp_moveit::utils::kinematics::IKSolverPtr ik_solver_
virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, const XmlRpc::XmlRpcValue &config) override
Initializes and configures.
ConstrainedCartesianGoal()
moveit::core::RobotStatePtr state_