Evaluates the cost of the goal pose by determining how far the Cartesian tool pose is from the desired under-constrained task manifold. More...
#include <tool_goal_pose.h>
Public Member Functions | |
virtual bool | computeCosts (const Eigen::MatrixXd ¶meters, 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 bool | configure (const XmlRpc::XmlRpcValue &config) override |
Sets internal members of the plugin from the configuration data. | |
virtual void | done (bool success, int total_iterations, double final_cost, const Eigen::MatrixXd ¶meters) override |
Called by the Stomp Task at the end of the optimization process. | |
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, XmlRpc::XmlRpcValue &config) override |
Initializes and configures the Cost Function. | |
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. | |
ToolGoalPose () | |
virtual | ~ToolGoalPose () |
Protected Attributes | |
Eigen::ArrayXi | dof_nullity_ |
Indicates which cartesian DOF's are unconstrained (0) and fully constrained (1) | |
std::string | group_name_ |
Eigen::VectorXd | last_joint_pose_ |
Eigen::Affine3d | last_tool_pose_ |
std::string | name_ |
double | orientation_cost_weight_ |
factor multiplied to the scaled orientation error | |
std::pair< double, double > | orientation_error_range_ |
The allowed orientation error range as euler angles, [2 x 1]. | |
moveit_msgs::MotionPlanRequest | plan_request_ |
planning_scene::PlanningSceneConstPtr | planning_scene_ |
double | position_cost_weight_ |
factor multiplied to the scaled position error | |
std::pair< double, double > | position_error_range_ |
The allowed position error range, [2 x 1]. | |
moveit::core::RobotModelConstPtr | robot_model_ |
moveit::core::RobotStatePtr | state_ |
Eigen::Affine3d | tool_goal_pose_ |
The desired goal pose for the active plan request. | |
std::string | tool_link_ |
Eigen::VectorXd | tool_twist_error_ |
Evaluates the cost of the goal pose by determining how far the Cartesian tool pose is from the desired under-constrained task manifold.
Definition at line 48 of file tool_goal_pose.h.
Definition at line 41 of file tool_goal_pose.cpp.
Definition at line 48 of file tool_goal_pose.cpp.
bool stomp_moveit::cost_functions::ToolGoalPose::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, virtual] |
computes the goal state costs as a function of the distance from the desired task manifold.
parameters | The parameter values to evaluate for state costs [num_dimensions x num_parameters] |
start_timestep | start index into the 'parameters' array, usually 0. |
num_timesteps | number of elements to use from 'parameters' starting from 'start_timestep' * |
iteration_number | The current iteration count in the optimization loop |
rollout_number | index of the noisy trajectory whose cost is being evaluated. * |
costs | vector containing the state costs per timestep. Only the array's last entry is set. [num_parameters x 1] |
validity | whether or not the trajectory is valid |
Implements stomp_moveit::cost_functions::StompCostFunction.
Definition at line 188 of file tool_goal_pose.cpp.
bool stomp_moveit::cost_functions::ToolGoalPose::configure | ( | const XmlRpc::XmlRpcValue & | config | ) | [override, virtual] |
Sets internal members of the plugin from the configuration data.
config | The configuration data . Usually loaded from the ros parameter server |
Implements stomp_moveit::cost_functions::StompCostFunction.
Definition at line 62 of file tool_goal_pose.cpp.
virtual void stomp_moveit::cost_functions::ToolGoalPose::done | ( | bool | success, |
int | total_iterations, | ||
double | final_cost, | ||
const Eigen::MatrixXd & | parameters | ||
) | [inline, override, virtual] |
Called by the Stomp Task at the end of the optimization process.
success | Whether the optimization succeeded |
total_iterations | Number of iterations used |
final_cost | The cost value after optimizing. |
parameters | The parameters generated at the end of current iteration[num_dimensions x num_timesteps] |
Reimplemented from stomp_moveit::cost_functions::StompCostFunction.
Definition at line 123 of file tool_goal_pose.h.
virtual std::string stomp_moveit::cost_functions::ToolGoalPose::getGroupName | ( | ) | const [inline, override, virtual] |
Reimplemented from stomp_moveit::cost_functions::StompCostFunction.
Definition at line 104 of file tool_goal_pose.h.
virtual std::string stomp_moveit::cost_functions::ToolGoalPose::getName | ( | ) | const [inline, override, virtual] |
Reimplemented from stomp_moveit::cost_functions::StompCostFunction.
Definition at line 110 of file tool_goal_pose.h.
bool stomp_moveit::cost_functions::ToolGoalPose::initialize | ( | moveit::core::RobotModelConstPtr | robot_model_ptr, |
const std::string & | group_name, | ||
XmlRpc::XmlRpcValue & | config | ||
) | [override, virtual] |
Initializes and configures the Cost Function.
robot_model_ptr | A pointer to the robot model. |
group_name | The designated planning group. |
config | The configuration data. Usually loaded from the ros parameter server |
Implements stomp_moveit::cost_functions::StompCostFunction.
Definition at line 53 of file tool_goal_pose.cpp.
bool stomp_moveit::cost_functions::ToolGoalPose::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 which will be used during the costs calculations.
planning_scene | A smart pointer to the planning scene |
req | The motion planning request |
config | The Stomp configuration. |
error_code | Moveit error code. |
Implements stomp_moveit::cost_functions::StompCostFunction.
Definition at line 111 of file tool_goal_pose.cpp.
Eigen::ArrayXi stomp_moveit::cost_functions::ToolGoalPose::dof_nullity_ [protected] |
Indicates which cartesian DOF's are unconstrained (0) and fully constrained (1)
Definition at line 143 of file tool_goal_pose.h.
std::string stomp_moveit::cost_functions::ToolGoalPose::group_name_ [protected] |
Definition at line 130 of file tool_goal_pose.h.
Eigen::VectorXd stomp_moveit::cost_functions::ToolGoalPose::last_joint_pose_ [protected] |
Definition at line 150 of file tool_goal_pose.h.
Eigen::Affine3d stomp_moveit::cost_functions::ToolGoalPose::last_tool_pose_ [protected] |
Definition at line 151 of file tool_goal_pose.h.
std::string stomp_moveit::cost_functions::ToolGoalPose::name_ [protected] |
Definition at line 127 of file tool_goal_pose.h.
double stomp_moveit::cost_functions::ToolGoalPose::orientation_cost_weight_ [protected] |
factor multiplied to the scaled orientation error
Definition at line 147 of file tool_goal_pose.h.
std::pair<double,double> stomp_moveit::cost_functions::ToolGoalPose::orientation_error_range_ [protected] |
The allowed orientation error range as euler angles, [2 x 1].
Definition at line 145 of file tool_goal_pose.h.
moveit_msgs::MotionPlanRequest stomp_moveit::cost_functions::ToolGoalPose::plan_request_ [protected] |
Definition at line 137 of file tool_goal_pose.h.
planning_scene::PlanningSceneConstPtr stomp_moveit::cost_functions::ToolGoalPose::planning_scene_ [protected] |
Definition at line 136 of file tool_goal_pose.h.
double stomp_moveit::cost_functions::ToolGoalPose::position_cost_weight_ [protected] |
factor multiplied to the scaled position error
Definition at line 146 of file tool_goal_pose.h.
std::pair<double,double> stomp_moveit::cost_functions::ToolGoalPose::position_error_range_ [protected] |
The allowed position error range, [2 x 1].
Definition at line 144 of file tool_goal_pose.h.
moveit::core::RobotModelConstPtr stomp_moveit::cost_functions::ToolGoalPose::robot_model_ [protected] |
Definition at line 132 of file tool_goal_pose.h.
moveit::core::RobotStatePtr stomp_moveit::cost_functions::ToolGoalPose::state_ [protected] |
Definition at line 133 of file tool_goal_pose.h.
Eigen::Affine3d stomp_moveit::cost_functions::ToolGoalPose::tool_goal_pose_ [protected] |
The desired goal pose for the active plan request.
Definition at line 140 of file tool_goal_pose.h.
std::string stomp_moveit::cost_functions::ToolGoalPose::tool_link_ [protected] |
Definition at line 131 of file tool_goal_pose.h.
Eigen::VectorXd stomp_moveit::cost_functions::ToolGoalPose::tool_twist_error_ [protected] |
Definition at line 152 of file tool_goal_pose.h.