Public Member Functions | Protected Attributes
stomp_moveit::update_filters::ConstrainedCartesianGoal Class Reference

Forces the goal cartesian tool pose into the task space. More...

#include <constrained_cartesian_goal.h>

Inheritance diagram for stomp_moveit::update_filters::ConstrainedCartesianGoal:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool configure (const XmlRpc::XmlRpcValue &config) override
 Sets internal members of the plugin from the configuration data.
 ConstrainedCartesianGoal ()
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 std::string getGroupName () const
virtual std::string getName () const
virtual bool initialize (moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, const XmlRpc::XmlRpcValue &config) override
 Initializes and configures.
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.
virtual ~ConstrainedCartesianGoal ()

Protected Attributes

std::string group_name_
utils::kinematics::KinematicConfig kc_
std::string name_
moveit::core::RobotModelConstPtr robot_model_
moveit::core::RobotStatePtr state_
std::string tool_link_

Detailed Description

Forces the goal cartesian tool pose into the task space.

Examples:
All examples are located here stomp_core examples

Definition at line 46 of file constrained_cartesian_goal.h.


Constructor & Destructor Documentation

Definition at line 48 of file constrained_cartesian_goal.cpp.

Definition at line 55 of file constrained_cartesian_goal.cpp.


Member Function Documentation

Sets internal members of the plugin from the configuration data.

Parameters:
configThe configuration data. Usually loaded from the ros parameter server
Returns:
true if succeeded, false otherwise.

Implements stomp_moveit::update_filters::StompUpdateFilter.

Definition at line 69 of file constrained_cartesian_goal.cpp.

bool stomp_moveit::update_filters::ConstrainedCartesianGoal::filter ( std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
const Eigen::MatrixXd &  parameters,
Eigen::MatrixXd &  updates,
bool &  filtered 
) [override, virtual]

Forces the goal to be within the tool's task manifold.

Parameters:
start_timestepThe start index into the 'parameters' array, usually 0.
num_timestepsThe number of elements to use from 'parameters' starting from 'start_timestep'.
iteration_numberThe current iteration count in the optimization loop.
parametersThe current parameter values [num_dimensions x num_timesteps]
updatesThe output updates to be applied to the parameters [num_dimensions x num_timesteps]
filteredSet to 'true' if the updates were modified, false otherwise
Returns:
false if there was an irrecoverable failure, true otherwise.

Implements stomp_moveit::update_filters::StompUpdateFilter.

Definition at line 210 of file constrained_cartesian_goal.cpp.

virtual std::string stomp_moveit::update_filters::ConstrainedCartesianGoal::getGroupName ( ) const [inline, virtual]

Reimplemented from stomp_moveit::update_filters::StompUpdateFilter.

Definition at line 100 of file constrained_cartesian_goal.h.

virtual std::string stomp_moveit::update_filters::ConstrainedCartesianGoal::getName ( ) const [inline, virtual]

Reimplemented from stomp_moveit::update_filters::StompUpdateFilter.

Definition at line 105 of file constrained_cartesian_goal.h.

bool stomp_moveit::update_filters::ConstrainedCartesianGoal::initialize ( moveit::core::RobotModelConstPtr  robot_model_ptr,
const std::string &  group_name,
const XmlRpc::XmlRpcValue config 
) [override, virtual]

Initializes and configures.

Parameters:
robot_model_ptrA pointer to the robot model.
group_nameThe designated planning group.
configThe configuration data. Usually loaded from the ros parameter server
Returns:
true if succeeded, false otherwise.

Implements stomp_moveit::update_filters::StompUpdateFilter.

Definition at line 60 of file constrained_cartesian_goal.cpp.

bool stomp_moveit::update_filters::ConstrainedCartesianGoal::setMotionPlanRequest ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const moveit_msgs::MotionPlanRequest req,
const stomp_core::StompConfiguration config,
moveit_msgs::MoveItErrorCodes &  error_code 
) [override, virtual]

Stores the planning details.

Parameters:
planning_sceneA smart pointer to the planning scene
reqThe motion planning request
configThe Stomp configuration.
error_codeMoveit error code.
Returns:
true if succeeded, false otherwise.

Implements stomp_moveit::update_filters::StompUpdateFilter.

Definition at line 118 of file constrained_cartesian_goal.cpp.


Member Data Documentation

Definition at line 113 of file constrained_cartesian_goal.h.

Definition at line 116 of file constrained_cartesian_goal.h.

Definition at line 112 of file constrained_cartesian_goal.h.

moveit::core::RobotModelConstPtr stomp_moveit::update_filters::ConstrainedCartesianGoal::robot_model_ [protected]

Definition at line 119 of file constrained_cartesian_goal.h.

moveit::core::RobotStatePtr stomp_moveit::update_filters::ConstrainedCartesianGoal::state_ [protected]

Definition at line 120 of file constrained_cartesian_goal.h.

Definition at line 121 of file constrained_cartesian_goal.h.


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


stomp_plugins
Author(s): Jorge Nicho
autogenerated on Sat Jun 8 2019 19:24:15