moveit2
The MoveIt Motion Planning Framework for ROS 2.
Namespaces | Classes | Typedefs | Functions
stomp_moveit Namespace Reference

Namespaces

 costs
 
 filters
 
 math
 
 noise
 
 visualization
 

Classes

class  StompPlanningContext
 
class  ComposableTask
 
class  StompPlannerManager
 

Typedefs

using Joints = std::vector< const moveit::core::JointModel * >
 
using StateValidatorFn = std::function< double(const Eigen::VectorXd &state_positions)>
 
using NoiseGeneratorFn = std::function< bool(const Eigen::MatrixXd &values, Eigen::MatrixXd &noisy_values, Eigen::MatrixXd &noise)>
 
using CostFn = std::function< bool(const Eigen::MatrixXd &values, Eigen::VectorXd &costs, bool &validity)>
 
using FilterFn = std::function< bool(const Eigen::MatrixXd &values, Eigen::MatrixXd &filtered_values)>
 
using PostIterationFn = std::function< void(int iteration_number, double cost, const Eigen::MatrixXd &values)>
 
using DoneFn = std::function< void(bool success, int total_iterations, double final_cost, const Eigen::MatrixXd &values)>
 

Functions

std::vector< double > getPositions (const moveit::core::RobotState &state, const Joints &joints)
 
void setJointPositions (const Eigen::VectorXd &values, const Joints &joints, moveit::core::RobotState &state)
 
void fillRobotTrajectory (const Eigen::MatrixXd &trajectory_values, const moveit::core::RobotState &reference_state, robot_trajectory::RobotTrajectory &trajectory)
 
robot_trajectory::RobotTrajectory matrixToRobotTrajectory (const Eigen::MatrixXd &trajectory_values, const moveit::core::RobotState &reference_state, const moveit::core::JointModelGroup *group=nullptr)
 
Eigen::MatrixXd robotTrajectoryToMatrix (const robot_trajectory::RobotTrajectory &trajectory)
 
bool solveWithStomp (const std::shared_ptr< stomp::Stomp > &stomp, const moveit::core::RobotState &start_state, const moveit::core::RobotState &goal_state, const moveit::core::JointModelGroup *group, const robot_trajectory::RobotTrajectoryPtr &input_trajectory, robot_trajectory::RobotTrajectoryPtr &output_trajectory)
 
bool extractSeedTrajectory (const planning_interface::MotionPlanRequest &req, const moveit::core::RobotModelConstPtr &robot_model, robot_trajectory::RobotTrajectoryPtr &seed)
 
stomp::TaskPtr createStompTask (const stomp::StompConfiguration &config, StompPlanningContext &context)
 
stomp::StompConfiguration getStompConfig (const stomp_moveit::Params &params, size_t num_dimensions)
 

Typedef Documentation

◆ CostFn

using stomp_moveit::CostFn = typedef std::function<bool(const Eigen::MatrixXd& values, Eigen::VectorXd& costs, bool& validity)>

Definition at line 65 of file stomp_moveit_task.hpp.

◆ DoneFn

using stomp_moveit::DoneFn = typedef std::function<void(bool success, int total_iterations, double final_cost, const Eigen::MatrixXd& values)>

Definition at line 71 of file stomp_moveit_task.hpp.

◆ FilterFn

using stomp_moveit::FilterFn = typedef std::function<bool(const Eigen::MatrixXd& values, Eigen::MatrixXd& filtered_values)>

Definition at line 67 of file stomp_moveit_task.hpp.

◆ Joints

using stomp_moveit::Joints = typedef std::vector<const moveit::core::JointModel*>

Definition at line 47 of file conversion_functions.hpp.

◆ NoiseGeneratorFn

using stomp_moveit::NoiseGeneratorFn = typedef std::function<bool(const Eigen::MatrixXd& values, Eigen::MatrixXd& noisy_values, Eigen::MatrixXd& noise)>

Definition at line 62 of file stomp_moveit_task.hpp.

◆ PostIterationFn

using stomp_moveit::PostIterationFn = typedef std::function<void(int iteration_number, double cost, const Eigen::MatrixXd& values)>

Definition at line 69 of file stomp_moveit_task.hpp.

◆ StateValidatorFn

using stomp_moveit::StateValidatorFn = typedef std::function<double(const Eigen::VectorXd& state_positions)>

Definition at line 53 of file cost_functions.hpp.

Function Documentation

◆ createStompTask()

stomp::TaskPtr stomp_moveit::createStompTask ( const stomp::StompConfiguration &  config,
StompPlanningContext context 
)

Definition at line 147 of file stomp_moveit_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ extractSeedTrajectory()

bool stomp_moveit::extractSeedTrajectory ( const planning_interface::MotionPlanRequest req,
const moveit::core::RobotModelConstPtr &  robot_model,
robot_trajectory::RobotTrajectoryPtr &  seed 
)

Definition at line 94 of file stomp_moveit_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ fillRobotTrajectory()

void stomp_moveit::fillRobotTrajectory ( const Eigen::MatrixXd &  trajectory_values,
const moveit::core::RobotState reference_state,
robot_trajectory::RobotTrajectory trajectory 
)

Writes the provided position value sequence into a robot trajectory.

Parameters
trajectory_valuesThe joint value sequence to copy the waypoints from
reference_stateA robot state providing default joint values and robot model
trajectoryThe robot trajectory containing waypoints with updated values

Definition at line 92 of file conversion_functions.hpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getPositions()

std::vector<double> stomp_moveit::getPositions ( const moveit::core::RobotState state,
const Joints joints 
)

Copies the position values of a robot state filtered by the provided joints.

Parameters
stateThe RobotState to copy the values from
jointsThe joints that should be considered
Returns
The vector containing the joint values

Definition at line 57 of file conversion_functions.hpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getStompConfig()

stomp::StompConfiguration stomp_moveit::getStompConfig ( const stomp_moveit::Params &  params,
size_t  num_dimensions 
)

Definition at line 191 of file stomp_moveit_planning_context.cpp.

Here is the caller graph for this function:

◆ matrixToRobotTrajectory()

robot_trajectory::RobotTrajectory stomp_moveit::matrixToRobotTrajectory ( const Eigen::MatrixXd &  trajectory_values,
const moveit::core::RobotState reference_state,
const moveit::core::JointModelGroup group = nullptr 
)

Constructs a new robot trajectory with the waypoints provided in the input matrix.

Parameters
trajectory_valuesThe waypoints and positions to copy
reference_stateThe RobotState with default joint values and robot model
groupAn optional JointModelGroup to filter for joints
Returns
The created RobotTrajectory containing updated waypoints

Definition at line 118 of file conversion_functions.hpp.

Here is the call graph for this function:

◆ robotTrajectoryToMatrix()

Eigen::MatrixXd stomp_moveit::robotTrajectoryToMatrix ( const robot_trajectory::RobotTrajectory trajectory)

Copies the waypoint positions of a RobotTrajectory into an Eigen matrix.

Parameters
trajectoryThe RobotTrajectory to read the waypoint positions fromi
Returns
The matrix representing a sequence of waypoint positions

Definition at line 134 of file conversion_functions.hpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setJointPositions()

void stomp_moveit::setJointPositions ( const Eigen::VectorXd &  values,
const Joints joints,
moveit::core::RobotState state 
)

Writes the provided position values into a robot state.

This function requires the dimension of values and joints to be equal!

Parameters
valuesThe joint position values to copy from
jointsThe joints that should be considered
stateThe robot state to update with the new joint values

Definition at line 77 of file conversion_functions.hpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ solveWithStomp()

bool stomp_moveit::solveWithStomp ( const std::shared_ptr< stomp::Stomp > &  stomp,
const moveit::core::RobotState start_state,
const moveit::core::RobotState goal_state,
const moveit::core::JointModelGroup group,
const robot_trajectory::RobotTrajectoryPtr &  input_trajectory,
robot_trajectory::RobotTrajectoryPtr &  output_trajectory 
)

Definition at line 67 of file stomp_moveit_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function: