constrained_cartesian_goal.h
Go to the documentation of this file.
1 
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_
29 
32 
33 namespace stomp_moveit
34 {
35 namespace update_filters
36 {
37 
46 class ConstrainedCartesianGoal : public StompUpdateFilter
47 {
48 public:
50  virtual ~ConstrainedCartesianGoal();
51 
59  virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
60  const std::string& group_name,const XmlRpc::XmlRpcValue& config) override;
61 
67  virtual bool configure(const XmlRpc::XmlRpcValue& config) override;
68 
77  virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
78  const moveit_msgs::MotionPlanRequest &req,
79  const stomp_core::StompConfiguration &config,
80  moveit_msgs::MoveItErrorCodes& error_code) override;
81 
93  virtual bool filter(std::size_t start_timestep,
94  std::size_t num_timesteps,
95  int iteration_number,
96  const Eigen::MatrixXd& parameters,
97  Eigen::MatrixXd& updates,
98  bool& filtered) override;
99 
100  virtual std::string getGroupName() const
101  {
102  return group_name_;
103  }
104 
105  virtual std::string getName() const
106  {
107  return name_ + "/" + group_name_;
108  }
109 
110 protected:
111 
112  std::string name_;
113  std::string group_name_;
114 
115  // kinematics
116  //utils::kinematics::KinematicConfig kc_;
117 
118  // goal config
119  Eigen::Affine3d tool_goal_pose_;
120  Eigen::VectorXd tool_goal_tolerance_;
121 
122  // robot
123  moveit::core::RobotModelConstPtr robot_model_;
124  moveit::core::RobotStatePtr state_;
125  stomp_moveit::utils::kinematics::IKSolverPtr ik_solver_;
126  std::string tool_link_;
127 };
128 
129 } /* namespace update_filters */
130 } /* namespace stomp_moveit */
131 
132 #endif /* INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_CONSTRAINED_CARTESIAN_GOAL_H_ */
virtual bool filter(std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, const Eigen::MatrixXd &parameters, Eigen::MatrixXd &updates, bool &filtered) override
Forces the goal to be within the tool's task manifold.
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.
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.
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.


stomp_plugins
Author(s): Jorge Nicho
autogenerated on Fri May 8 2020 03:35:53