Go to the documentation of this file.00001
00026 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_NOISY_FILTERS_JOINT_LIMITS_H_
00027 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_NOISY_FILTERS_JOINT_LIMITS_H_
00028
00029 #include <moveit/robot_model/robot_model.h>
00030 #include <moveit_msgs/GetMotionPlan.h>
00031 #include <stomp_moveit/noisy_filters/stomp_noisy_filter.h>
00032
00033 namespace stomp_moveit
00034 {
00035 namespace noisy_filters
00036 {
00046 class JointLimits : public StompNoisyFilter
00047 {
00048 public:
00049 JointLimits();
00050 virtual ~JointLimits();
00051
00053 virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
00054 const std::string& group_name,const XmlRpc::XmlRpcValue& config) override;
00055
00057 virtual bool configure(const XmlRpc::XmlRpcValue& config) override;
00058
00060 virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
00061 const moveit_msgs::MotionPlanRequest &req,
00062 const stomp_core::StompConfiguration &config,
00063 moveit_msgs::MoveItErrorCodes& error_code) override;
00064
00065
00066 virtual std::string getGroupName() const override
00067 {
00068 return group_name_;
00069 }
00070
00071 virtual std::string getName() const override
00072 {
00073 return "JointLimits/" + group_name_;
00074 }
00075
00087 virtual bool filter(std::size_t start_timestep,
00088 std::size_t num_timesteps,
00089 int iteration_number,
00090 int rollout_number,
00091 Eigen::MatrixXd& parameters,
00092 bool& filtered) override;
00093
00094 protected:
00095
00096 moveit::core::RobotModelConstPtr robot_model_;
00097 std::string group_name_;
00098
00099
00100 bool lock_start_;
00101 bool lock_goal_;
00102
00103
00104 moveit::core::RobotStatePtr start_state_;
00105 moveit::core::RobotStatePtr goal_state_;
00106
00107
00108 };
00109
00110 }
00111 }
00112
00113 #endif