collision_check.h
Go to the documentation of this file.
00001 
00026 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_COST_FUNCTIONS_COLLISION_CHECK_H_
00027 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_COST_FUNCTIONS_COLLISION_CHECK_H_
00028 
00029 #include <Eigen/Sparse>
00030 #include <moveit/robot_model/robot_model.h>
00031 #include "stomp_moveit/cost_functions/stomp_cost_function.h"
00032 
00033 namespace stomp_moveit
00034 {
00035 namespace cost_functions
00036 {
00037 
00045 class CollisionCheck : public StompCostFunction
00046 {
00047 public:
00048   CollisionCheck();
00049   virtual ~CollisionCheck();
00050 
00058   virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
00059                           const std::string& group_name,XmlRpc::XmlRpcValue& config) override;
00060 
00066   virtual bool configure(const XmlRpc::XmlRpcValue& config) override;
00067 
00076   virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
00077                    const moveit_msgs::MotionPlanRequest &req,
00078                    const stomp_core::StompConfiguration &config,
00079                    moveit_msgs::MoveItErrorCodes& error_code) override;
00080 
00081 
00093   virtual bool computeCosts(const Eigen::MatrixXd& parameters,
00094                             std::size_t start_timestep,
00095                             std::size_t num_timesteps,
00096                             int iteration_number,
00097                             int rollout_number,
00098                             Eigen::VectorXd& costs,
00099                             bool& validity) override;
00100 
00101   virtual std::string getGroupName() const override
00102   {
00103     return group_name_;
00104   }
00105 
00106 
00107   virtual std::string getName() const override
00108   {
00109     return "CollisionCheck/" + group_name_;
00110   }
00111 
00112   virtual void done(bool success,int total_iterations,double final_cost,const Eigen::MatrixXd& parameters) override;
00113 
00114 protected:
00115 
00124   bool checkIntermediateCollisions(const Eigen::VectorXd& start, const Eigen::VectorXd& end,double longest_valid_joint_move);
00125 
00126   std::string name_;
00127 
00128   // robot details
00129   std::string group_name_;
00130   moveit::core::RobotModelConstPtr robot_model_ptr_;
00131   moveit::core::RobotStatePtr robot_state_;
00132 
00133   // planning context information
00134   planning_scene::PlanningSceneConstPtr planning_scene_;
00135   moveit_msgs::MotionPlanRequest plan_request_;
00136 
00137   // parameters
00138   double collision_penalty_;            
00139   double kernel_window_percentage_;     
00140   double longest_valid_joint_move_;     
00142   // cost calculation
00143   Eigen::VectorXd raw_costs_;
00144   Eigen::ArrayXd intermediate_costs_slots_;
00145 
00146   // collision
00147   collision_detection::CollisionRequest collision_request_;
00148   collision_detection::CollisionRobotConstPtr collision_robot_;
00149   collision_detection::CollisionWorldConstPtr collision_world_;
00150 
00151   // intermediate collision check support
00152   std::array<moveit::core::RobotStatePtr,3 > intermediate_coll_states_;   
00154 };
00155 
00156 } /* namespace cost_functions */
00157 } /* namespace stomp_moveit */
00158 
00159 #endif /* INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_COST_FUNCTIONS_COLLISION_CHECK_H_ */


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Sat Jun 8 2019 19:24:01