#include <obstacle_distance_gradient.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 state costs by calculating the minimum distance between the robot and an obstacle. | |
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. Calls the configure method and passes the 'config' value. | |
ObstacleDistanceGradient () | |
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. | |
virtual | ~ObstacleDistanceGradient () |
Protected Member Functions | |
bool | checkIntermediateCollisions (const Eigen::VectorXd &start, const Eigen::VectorXd &end, double longest_valid_joint_move) |
Checks for collision between consecutive points by dividing the joint move into sub-moves where the maximum joint motion can not exceed the longest_valid_joint_move value. | |
Protected Attributes | |
collision_detection::CollisionRequest | collision_request_ |
collision_detection::CollisionResult | collision_result_ |
std::string | group_name_ |
std::array < moveit::core::RobotStatePtr, 3 > | intermediate_coll_states_ |
Used in checking collisions between to consecutive poses. | |
double | longest_valid_joint_move_ |
how far can a joint move in between consecutive trajectory points | |
double | max_distance_ |
maximum distance from at which the trajectory will be penalized | |
std::string | name_ |
moveit_msgs::MotionPlanRequest | plan_request_ |
planning_scene::PlanningSceneConstPtr | planning_scene_ |
moveit::core::RobotModelConstPtr | robot_model_ptr_ |
moveit::core::RobotStatePtr | robot_state_ |
Definition at line 44 of file obstacle_distance_gradient.h.
Definition at line 40 of file obstacle_distance_gradient.cpp.
Definition at line 47 of file obstacle_distance_gradient.cpp.
bool stomp_moveit::cost_functions::ObstacleDistanceGradient::checkIntermediateCollisions | ( | const Eigen::VectorXd & | start, |
const Eigen::VectorXd & | end, | ||
double | longest_valid_joint_move | ||
) | [protected] |
Checks for collision between consecutive points by dividing the joint move into sub-moves where the maximum joint motion can not exceed the longest_valid_joint_move value.
start | The start joint pose |
end | The end joint pose |
longest_valid_joint_move | The maximum distance that the joints are allowed to move before checking for collisions. |
Definition at line 209 of file obstacle_distance_gradient.cpp.
bool stomp_moveit::cost_functions::ObstacleDistanceGradient::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 state costs by calculating the minimum distance between the robot and an obstacle.
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. |
validity | whether or not the trajectory is valid |
Implements stomp_moveit::cost_functions::StompCostFunction.
Definition at line 131 of file obstacle_distance_gradient.cpp.
bool stomp_moveit::cost_functions::ObstacleDistanceGradient::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 67 of file obstacle_distance_gradient.cpp.
void stomp_moveit::cost_functions::ObstacleDistanceGradient::done | ( | bool | success, |
int | total_iterations, | ||
double | final_cost, | ||
const Eigen::MatrixXd & | parameters | ||
) | [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 255 of file obstacle_distance_gradient.cpp.
virtual std::string stomp_moveit::cost_functions::ObstacleDistanceGradient::getGroupName | ( | ) | const [inline, override, virtual] |
Reimplemented from stomp_moveit::cost_functions::StompCostFunction.
Definition at line 95 of file obstacle_distance_gradient.h.
virtual std::string stomp_moveit::cost_functions::ObstacleDistanceGradient::getName | ( | ) | const [inline, override, virtual] |
Reimplemented from stomp_moveit::cost_functions::StompCostFunction.
Definition at line 100 of file obstacle_distance_gradient.h.
bool stomp_moveit::cost_functions::ObstacleDistanceGradient::initialize | ( | moveit::core::RobotModelConstPtr | robot_model_ptr, |
const std::string & | group_name, | ||
XmlRpc::XmlRpcValue & | config | ||
) | [override, virtual] |
Initializes and configures the Cost Function. Calls the configure method and passes the 'config' value.
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 52 of file obstacle_distance_gradient.cpp.
bool stomp_moveit::cost_functions::ObstacleDistanceGradient::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 102 of file obstacle_distance_gradient.cpp.
collision_detection::CollisionRequest stomp_moveit::cost_functions::ObstacleDistanceGradient::collision_request_ [protected] |
Definition at line 137 of file obstacle_distance_gradient.h.
collision_detection::CollisionResult stomp_moveit::cost_functions::ObstacleDistanceGradient::collision_result_ [protected] |
Definition at line 138 of file obstacle_distance_gradient.h.
std::string stomp_moveit::cost_functions::ObstacleDistanceGradient::group_name_ [protected] |
Definition at line 124 of file obstacle_distance_gradient.h.
std::array<moveit::core::RobotStatePtr,3 > stomp_moveit::cost_functions::ObstacleDistanceGradient::intermediate_coll_states_ [protected] |
Used in checking collisions between to consecutive poses.
Definition at line 129 of file obstacle_distance_gradient.h.
double stomp_moveit::cost_functions::ObstacleDistanceGradient::longest_valid_joint_move_ [protected] |
how far can a joint move in between consecutive trajectory points
Definition at line 142 of file obstacle_distance_gradient.h.
double stomp_moveit::cost_functions::ObstacleDistanceGradient::max_distance_ [protected] |
maximum distance from at which the trajectory will be penalized
Definition at line 141 of file obstacle_distance_gradient.h.
std::string stomp_moveit::cost_functions::ObstacleDistanceGradient::name_ [protected] |
Definition at line 121 of file obstacle_distance_gradient.h.
moveit_msgs::MotionPlanRequest stomp_moveit::cost_functions::ObstacleDistanceGradient::plan_request_ [protected] |
Definition at line 134 of file obstacle_distance_gradient.h.
planning_scene::PlanningSceneConstPtr stomp_moveit::cost_functions::ObstacleDistanceGradient::planning_scene_ [protected] |
Definition at line 133 of file obstacle_distance_gradient.h.
moveit::core::RobotModelConstPtr stomp_moveit::cost_functions::ObstacleDistanceGradient::robot_model_ptr_ [protected] |
Definition at line 125 of file obstacle_distance_gradient.h.
moveit::core::RobotStatePtr stomp_moveit::cost_functions::ObstacleDistanceGradient::robot_state_ [protected] |
Definition at line 126 of file obstacle_distance_gradient.h.