Public Member Functions | Protected Attributes | List of all members
stomp_moveit::noisy_filters::JointLimits Class Reference

Checks that the joint values are within the limits as defined in the urdf file. It modifies the values of those joints that exceed the limits. More...

#include <joint_limits.h>

Inheritance diagram for stomp_moveit::noisy_filters::JointLimits:
Inheritance graph
[legend]

Public Member Functions

virtual bool configure (const XmlRpc::XmlRpcValue &config) override
 see base class for documentation
 
virtual bool filter (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, int rollout_number, Eigen::MatrixXd &parameters, bool &filtered) override
 Sets the joint values to the closest joint limit whenever it's found outside the allowed range. More...
 
virtual std::string getGroupName () const override
 
virtual std::string getName () const override
 
virtual bool initialize (moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, const XmlRpc::XmlRpcValue &config) override
 see base class for documentation
 
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
 see base class for documentation
 
- Public Member Functions inherited from stomp_moveit::noisy_filters::StompNoisyFilter
virtual void done (bool success, int total_iterations, double final_cost, const Eigen::MatrixXd &parameters)
 Called by the Stomp at the end of the optimization process. More...
 
virtual void postIteration (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, double cost, const Eigen::MatrixXd &parameters)
 Called by STOMP at the end of each iteration. More...
 

Protected Attributes

moveit::core::RobotStatePtr goal_state_
 
std::string group_name_
 
bool has_goal_constraints_
 
bool lock_goal_
 
bool lock_start_
 
moveit::core::RobotModelConstPtr robot_model_
 
moveit::core::RobotStatePtr start_state_
 True if a joint constraint for the goal was provided.
 

Detailed Description

Checks that the joint values are within the limits as defined in the urdf file. It modifies the values of those joints that exceed the limits.

Examples:
All examples are located here STOMP MoveIt! examples

Definition at line 46 of file joint_limits.h.

Member Function Documentation

bool stomp_moveit::noisy_filters::JointLimits::filter ( std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
int  rollout_number,
Eigen::MatrixXd &  parameters,
bool &  filtered 
)
overridevirtual

Sets the joint values to the closest joint limit whenever it's found outside the allowed range.

Parameters
start_timestepStart index into the 'parameters' array, usually 0.
num_timestepsNumber of elements to use from 'parameters' starting from 'start_timestep'
iteration_numberThe current iteration count in the optimization loop.
rollout_numberIndex of the noisy trajectory whose cost is being evaluated.
parametersOutput argument containing the parameters to be filtered [num_dimensions x num_timesteps].
filteredOutput argument that's set to 'true' if the parameters were changed according to the filtering method.
Returns
false if there was an irrecoverable failure, true otherwise.

Implements stomp_moveit::noisy_filters::StompNoisyFilter.

Definition at line 152 of file joint_limits.cpp.


The documentation for this class was generated from the following files:


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Fri May 8 2020 03:35:47