tool_goal_pose.h
Go to the documentation of this file.
1 
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_
28 
29 #include <Eigen/Sparse>
33 
34 namespace stomp_moveit
35 {
36 namespace cost_functions
37 {
38 
48 {
49 public:
50  ToolGoalPose();
51  virtual ~ToolGoalPose();
52 
60  virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
61  const std::string& group_name,XmlRpc::XmlRpcValue& config) override;
62 
68  virtual bool configure(const XmlRpc::XmlRpcValue& config) override;
69 
78  virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
79  const moveit_msgs::MotionPlanRequest &req,
80  const stomp_core::StompConfiguration &config,
81  moveit_msgs::MoveItErrorCodes& error_code) override;
82 
83 
95  virtual bool computeCosts(const Eigen::MatrixXd& parameters,
96  std::size_t start_timestep,
97  std::size_t num_timesteps,
98  int iteration_number,
99  int rollout_number,
100  Eigen::VectorXd& costs,
101  bool& validity) override;
102 
103  virtual std::string getGroupName() const override
104  {
105  return group_name_;
106  }
107 
108 
109  virtual std::string getName() const override
110  {
111  return name_ + "/" + group_name_;
112  }
113 
122  virtual void done(bool success,int total_iterations,double final_cost,const Eigen::MatrixXd& parameters) override;
123 
124 protected:
125 
126  std::string name_;
127 
128  // robot details
129  std::string group_name_;
130  std::string tool_link_;
131  moveit::core::RobotModelConstPtr robot_model_;
132  moveit::core::RobotStatePtr state_;
133 
134  // planning context information
135  planning_scene::PlanningSceneConstPtr planning_scene_;
136  moveit_msgs::MotionPlanRequest plan_request_;
137 
138  // goal pose
139  Eigen::Affine3d tool_goal_pose_;
140  Eigen::VectorXd tool_goal_tolerance_;
141  Eigen::VectorXd min_twist_error_;
142  Eigen::VectorXd max_twist_error_;
143 
144  // ros parameters
148  // partial results variables
149  Eigen::VectorXd last_joint_pose_;
150  Eigen::Affine3d last_tool_pose_;
151  Eigen::VectorXd tool_twist_error_;
152 
153 
154 
155 };
156 
157 } /* namespace cost_functions */
158 } /* namespace stomp_moveit */
159 
160 #endif /* INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_COST_FUNCTIONS_TOOL_GOAL_POSE_H_ */
moveit::core::RobotModelConstPtr robot_model_
Evaluates the cost of the goal pose by determining how far the Cartesian tool pose is from the desire...
virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, XmlRpc::XmlRpcValue &config) override
Initializes and configures the Cost Function.
virtual bool configure(const XmlRpc::XmlRpcValue &config) override
Sets internal members of the plugin from the configuration data.
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 which will be used during the costs calculations.
virtual std::string getGroupName() const override
moveit_msgs::MotionPlanRequest plan_request_
virtual void done(bool success, int total_iterations, double final_cost, const Eigen::MatrixXd &parameters) override
Called by the Stomp Task at the end of the optimization process.
double orientation_cost_weight_
factor multiplied to the scaled orientation error
virtual bool computeCosts(const Eigen::MatrixXd &parameters, std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, int rollout_number, Eigen::VectorXd &costs, bool &validity) override
computes the goal state costs as a function of the distance from the desired task manifold...
virtual std::string getName() const override
Eigen::Affine3d tool_goal_pose_
The desired goal pose for the active plan request.
planning_scene::PlanningSceneConstPtr planning_scene_
double position_cost_weight_
factor multiplied to the scaled position error


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