moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
MoveIt-based cost functions that can be passed to STOMP via a ComposableTask. More...
#include <Eigen/Geometry>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/kinematic_constraints/kinematic_constraint.h>
#include <stomp_moveit/stomp_moveit_task.hpp>
#include <stomp_moveit/conversion_functions.hpp>
Go to the source code of this file.
Namespaces | |
namespace | stomp_moveit |
namespace | stomp_moveit::costs |
Typedefs | |
using | stomp_moveit::StateValidatorFn = std::function< double(const Eigen::VectorXd &state_positions)> |
Functions | |
CostFn | stomp_moveit::costs::getCostFunctionFromStateValidator (const StateValidatorFn &state_validator_fn, double interpolation_step_size) |
CostFn | stomp_moveit::costs::getCollisionCostFunction (const std::shared_ptr< const planning_scene::PlanningScene > &planning_scene, const moveit::core::JointModelGroup *group, double collision_penalty) |
CostFn | stomp_moveit::costs::getConstraintsCostFunction (const std::shared_ptr< const planning_scene::PlanningScene > &planning_scene, const moveit::core::JointModelGroup *group, const moveit_msgs::msg::Constraints &constraints_msg, double cost_scale) |
CostFn | stomp_moveit::costs::sum (const std::vector< CostFn > &cost_functions) |
Variables | |
constexpr double | stomp_moveit::costs::COL_CHECK_DISTANCE = 0.05 |
constexpr double | stomp_moveit::costs::CONSTRAINT_CHECK_DISTANCE = 0.05 |
MoveIt-based cost functions that can be passed to STOMP via a ComposableTask.
Definition in file cost_functions.hpp.