![]() |
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Classes | |
struct | Constraints |
Definition of kinematic constraints to take into account during planning. More... | |
struct | JointRangeConstraint |
struct | PlanarRotationConstraint |
struct | PlanningError |
Definition of planning error return type with a string and optional collision results. More... | |
class | PlanningTestFixture |
struct | RRTParams |
Configuration parameters for the RRT planner. More... | |
struct | TrajectoryParams |
Parameters for the trajectory generation. More... | |
Typedefs | |
using | ContactMap = collision_detection::CollisionResult::ContactMap |
Functions | |
Constraints | createPlanarOrientationConstraint (const moveit::core::LinkModel *link, double angle_tolerance) |
Create planar orientation constraints for a set of links. | |
std::vector< Constraints > | 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, PlanningError > | 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, PlanningError > | 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 > | 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 | 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. | |
Variables | |
constexpr char | kTestRobot [] = "panda" |
constexpr char | kTestGroup [] = "panda_arm" |
using pro_rrt::ContactMap = typedef collision_detection::CollisionResult::ContactMap |
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.
velocity_scale_factor | How much to scale the velocity of the trajectory, relative to the maximum robot velocity defined in configs. |
acceleration_scale_factor | How much to scale the acceleration of the trajectory, relative to the maximum robot acceleration defined in configs. |
trajectory_sampling_rate | The sampling rate of the output trajectory in Hz. |
link_padding | The padding to be used for collision checking, in meters. |
keep_orientation | Whether to keep the orientation of the robot's end effector fixed during planning. |
keep_orientation_tolerance | The angle tolerance to use for the orientation constraint. |
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.
This function sets the joint positions of the robot model in the input planning scene to the input goal_positions
and performs a collision check. The collision check is performed against the robot's self-collision and the environment. The link padding set in the planning scene is taken into account in both collision checks.
group | Joint model group associated with goal_positions . |
goal_positions | Joint-space configuration to validate. |
planning_scene | Planning scene to perform the collision check against. |
goal_positions
are collision-free in the input planning_scene
, false otherwise. Constraints pro_rrt::createPlanarOrientationConstraint | ( | const moveit::core::LinkModel * | link, |
double | angle_tolerance | ||
) |
Create planar orientation constraints for a set of links.
link | The link to constrain. |
angle_tolerance | The angle tolerance to use for the orientation constraint. |
std::vector< Constraints > pro_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.
joint_model_group | The joint model group to define constraints for. |
constrained_link_names | The names of the links to constrain. |
angle_tolerance | The angle tolerance to use for the orientation constraint. |
tl::expected< trajectory_msgs::msg::JointTrajectory, PlanningError > pro_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
.
group | Joint model group to plan motion for. |
initial_joint_positions | The initial joint positions of group . |
goal_joint_positions | The desired goal joint positions for group . |
rrt_params | Configuration parameters for the RRT planner. |
constraints | The kinematic constraints to take into account during planning. |
trajectory_params | Parameters for the trajectory generation. |
planning_scene | The planning scene to plan in, i.e. the obstacles around the robot. |
trajectory_msgs::msg::JointTrajectory
if one is found, or a PlanningError
if the planning fails. tl::expected< trajectory_msgs::msg::JointTrajectory, PlanningError > pro_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
.
group | Joint model group to plan motion for. |
start_state | The start state of the robot. |
goal_state | The goal state of the robot. |
rrt_params | Configuration parameters for the RRT planner. |
constraints | The kinematic constraints to take into account during planning. |
trajectory_params | Parameters for the trajectory generation. |
planning_scene | The planning scene to plan in, i.e. the obstacles around the robot. |
trajectory_msgs::msg::JointTrajectory
if one is found, or a PlanningError
if the planning fails.
|
constexpr |
|
constexpr |