MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
pro_rrt.cpp File Reference
#include "pro_rrt/pro_rrt.hpp"
#include <fmt/format.h>
#include <moveit/trajectory_processing/trajectory_tools.hpp>
#include "cartesian_planning/math.hpp"
#include "cartesian_planning/trajectory_utils.hpp"
#include "moveit_pro_macros/macros.hpp"
#include "rrtconnect/path_metric.hpp"
#include "rrtconnect/rrt_connect.hpp"
Include dependency graph for pro_rrt.cpp:

Namespaces

namespace  pro_rrt
 

Typedefs

using pro_rrt::ContactMap = collision_detection::CollisionResult::ContactMap
 

Functions

Constraints pro_rrt::createPlanarOrientationConstraint (const moveit::core::LinkModel *link, double angle_tolerance)
 Create planar orientation constraints for a set of links.
 
std::vector< Constraintspro_rrt::createPlanarOrientationConstraints (const moveit::core::JointModelGroup &joint_model_group, const std::vector< std::string > &constrained_link_names, double angle_tolerance)
 Create planar orientation constraints for a set of links.
 
tl::expected< trajectory_msgs::msg::JointTrajectory, PlanningErrorpro_rrt::planTrajectoryToJointGoal (const moveit::core::JointModelGroup &group, const moveit::core::RobotState &start_state, const moveit::core::RobotState &goal_state, const RRTParams &rrt_params, const std::vector< Constraints > &constraints, const TrajectoryParams &trajectory_params, planning_scene::PlanningScene &planning_scene)
 Plan a trajectory from a start state to a goal state, for the given planning group, in the given planning_scene.
 
tl::expected< trajectory_msgs::msg::JointTrajectory, PlanningErrorpro_rrt::planTrajectoryToJointGoal (const moveit::core::JointModelGroup &group, const Eigen::VectorXd &initial_joint_positions, const Eigen::VectorXd &goal_joint_positions, const RRTParams &rrt_params, const std::vector< Constraints > &constraints, const TrajectoryParams &trajectory_params, planning_scene::PlanningScene &planning_scene)
 Plan a trajectory from initial joint positions to goal joint positions, for the given planning group, in the given planning_scene.
 
std::optional< std::string > pro_rrt::checkInputsProRRT (double velocity_scale_factor, double acceleration_scale_factor, int trajectory_sampling_rate, double link_padding, bool keep_orientation, double keep_orientation_tolerance)
 Check if a given set of inputs for ProRRT are valid.
 
bool pro_rrt::collisionValidationFunction (const moveit::core::JointModelGroup &group, const Eigen::VectorXd &goal_positions, planning_scene::PlanningScene &planning_scene)
 Validate a joint-space configuration by checking for collisions in the given planning scene.