Robowflex  v0.1
Making MoveIt Easy
robowflex Namespace Reference

Main namespace. Contains all library classes and functions. More...

Namespaces

 color
 
 constants
 
 darts
 DART-based robot modeling and planning.
 
 hypercube
 
 IO
 File and ROS Input / Output operations.
 
 log
 Logging functions.
 
 movegroup
 Move group interaction related classes and features.
 
 OMPL
 OMPL specific planners and features.
 
 openrave
 
 opt
 
 RNG
 Collection of methods relating to random sampling.
 
 TF
 Collection of methods relating to transforms and transform math.
 

Classes

struct  PlanningQuery
 A container structure for all elements needed in a planning query, plus an identifying name. More...
 
class  PlanData
 Detailed statistics and metrics computed from profiling a planner's motion planning. More...
 
class  PlanDataSet
 Detailed statistics about a benchmark of multiple queries. More...
 
class  Profiler
 
class  Experiment
 A helper class for benchmarking that controls running multiple queries. More...
 
class  PlanDataSetOutputter
 An abstract class for outputting benchmark results. More...
 
class  JSONPlanDataSetOutputter
 A benchmark outputter for storing data in a single JSON file. More...
 
class  TrajectoryPlanDataSetOutputter
 Benchmark outputter that saves each trajectory from each run to a rosbag file. More...
 
class  OMPLPlanDataSetOutputter
 Benchmark outputter that saves results into OMPL benchmarking log files. If ompl_benchmark_statistics.py is available in your PATH variable, the results are also compiled into a database file. More...
 
class  MotionRequestBuilder
 A helper class to build motion planning requests for a robowflex::Planner. More...
 
class  Cob4Robot
 Convenience class that describes the default setup for Care-O-Bot4. Will first attempt to load configuration and description from the robowflex_resources package. See https://github.com/KavrakiLab/robowflex_resources for this package. If this package is not available, then fetch_description / fetch_moveit_config packages will be used. More...
 
class  FetchRobot
 Convenience class that describes the default setup for Fetch. Will first attempt to load configuration and description from the robowflex_resources package. See https://github.com/KavrakiLab/robowflex_resources for this package. If this package is not available, then fetch_description / fetch_moveit_config packages will be used. More...
 
class  R2Robot
 Convenience class that describes the default setup for R2 (R2C6 full). More...
 
class  UR5Robot
 Convenience class that describes the default setup for UR5 (with robotiq gripper and load cell) Will first attempt to load configuration and description from the robowflex_resources package. See https://github.com/KavrakiLab/robowflex_resources for this package. If this package is not available, then ur_description / robotiq packages will be used. More...
 
class  Geometry
 A class that manages both solid and mesh geometry for various parts of the motion planning system. More...
 
class  ID
 Adds functionality to uniquely ID a specific class as well as the "version" of that class, managed by an incrementing counter. More...
 
class  Planner
 An abstract interface to a motion planning algorithm. More...
 
class  PoolPlanner
 A thread pool of planners P to service requests in a multi-threaded environment simultaneously. More...
 
class  SimpleCartesianPlanner
 A simple motion planner that uses interpolation of the end-effector in Cartesian space to find a path. Valid configurations are found using IK. This planner is not complete and typically only works for small movements of the end-effector. More...
 
class  PipelinePlanner
 A motion planner that uses the MoveIt! planning pipeline to load a planner plugin. More...
 
class  Pool
 A thread pool that can execute arbitrary functions asynchronously. Functions with arguments to be executed are put in the queue through submit(). This returns a Pool::Job that can be used to retrieve the result or cancel the job if the result is no longer needed. More...
 
class  Robot
 Loads information about a robot and maintains information about a robot's state. More...
 
class  ParamRobot
 Loads information about a robot from the parameter server. More...
 
class  Scene
 Wrapper class around the planning scene and collision geometry. More...
 
class  Trajectory
 The Trajectory class is a wrapper around MoveIt!'s robot_trajectory::RobotTrajectory, with extra convenience functions such interpolation and collision checking. There are also utilities to load and save trajectories from YAML files (toYAMLFile() and fromYAMLFile()). More...
 
class  Exception
 Exception that contains a message and an error code. More...
 
class  ROS
 RAII-pattern for starting up ROS. More...
 
class  TrajOptPlanner
 Robowflex Tesseract TrajOpt Planner. More...
 

Typedefs

using RobotPose = std::decay< decltype(std::declval< moveit::core::Transforms >().getTransform("")) >::type
 A pose (point in SE(3)) used in various functions. Defined from what MoveIt! uses. More...
 
using RobotPoseVector = std::vector< RobotPose, Eigen::aligned_allocator< RobotPose > >
 A vector of poses. More...
 
using PlannerMetric = boost::variant< bool, double, int, std::size_t, std::string >
 Variant type of possible values a run metric could be. More...
 
using PathMetric = std::function< double(const robot_state::RobotState &, const robot_state::RobotState &)>
 A metric over robot states. More...
 

Functions

template<typename M >
toMatrix (const RobotPose &pose)
 Convert the Robowflex pose type to another transform type. More...
 
std::string toMetricString (const PlannerMetric &metric)
 Convert a planner metric into a string. More...
 
bool compareIDs (const ID &a, const ID &b)
 Compare two ID objects. More...
 
bool compareIDs (const IDPtr &a, const IDPtr &b)
 Compare two ID objects. More...
 
bool compareIDs (const IDConstPtr &a, const IDConstPtr &b)
 Compare two ID objects. More...
 
bool compareIDs (const ID &a, const ID::Key &b)
 Compare an ID object to a key. More...
 
bool compareIDs (const IDPtr &a, const ID::Key &b)
 Compare an ID object to a key. More...
 
bool compareIDs (const IDConstPtr &a, const ID::Key &b)
 Compare an ID object to a key. More...
 
bool compareIDs (const ID::Key &a, const ID::Key &b)
 Compare an ID object to a key. More...
 
void explode ()
 Trigger a SEGSEGV. More...
 

Variables

 fetch = rv.robot.Robot("Fetch", "package://robowflex_resources/fetch/robots/fetch.urdf")
 
 scene
 
 frame
 
 cube = scene.get_object("Cube3")
 

Detailed Description

Main namespace. Contains all library classes and functions.

Typedef Documentation

◆ PathMetric

using robowflex::PathMetric = typedef std::function<double(const robot_state::RobotState &, const robot_state::RobotState &)>

A metric over robot states.

Definition at line 24 of file trajectory.h.

◆ PlannerMetric

using robowflex::PlannerMetric = typedef boost::variant<bool, double, int, std::size_t, std::string>

Variant type of possible values a run metric could be.

Definition at line 33 of file benchmarking.h.

◆ RobotPose

using robowflex::RobotPose = typedef std::decay< decltype( std::declval<moveit::core::Transforms>().getTransform("") ) >::type

A pose (point in SE(3)) used in various functions. Defined from what MoveIt! uses.

Either an Eigen::Affine3d or Eigen::Isometry3d. These are both transforms, and thus code using a RobotPose will generally work for both.

Definition at line 20 of file adapter.h.

◆ RobotPoseVector

using robowflex::RobotPoseVector = typedef std::vector<RobotPose, Eigen::aligned_allocator<RobotPose> >

A vector of poses.

Definition at line 28 of file adapter.h.

Function Documentation

◆ compareIDs() [1/7]

bool robowflex::compareIDs ( const ID a,
const ID b 
)

Compare two ID objects.

Parameters
[in]aFirst object to compare.
[in]bSecond object to compare.
Returns
True if a and b are the same, false otherwise.

Definition at line 47 of file id.cpp.

48 {
49  return a == b;
50 }

◆ compareIDs() [2/7]

bool robowflex::compareIDs ( const ID a,
const ID::Key b 
)

Compare an ID object to a key.

Parameters
[in]aObject to compare.
[in]bKey to compare against.
Returns
True if a and b are the same, false otherwise.

Definition at line 62 of file id.cpp.

63 {
64  return a == b;
65 }

◆ compareIDs() [3/7]

bool robowflex::compareIDs ( const ID::Key a,
const ID::Key b 
)

Compare an ID object to a key.

Parameters
[in]aKey to compare.
[in]bKey to compare against.
Returns
True if a and b are the same, false otherwise.

Definition at line 77 of file id.cpp.

78 {
79  return a == b;
80 }

◆ compareIDs() [4/7]

bool robowflex::compareIDs ( const IDConstPtr a,
const ID::Key b 
)

Compare an ID object to a key.

Parameters
[in]aObject to compare.
[in]bKey to compare against.
Returns
True if a and b are the same, false otherwise.

Definition at line 72 of file id.cpp.

73 {
74  return compareIDs(*a, b);
75 }
bool compareIDs(const ID &a, const ID &b)
Compare two ID objects.
Definition: id.cpp:47

◆ compareIDs() [5/7]

bool robowflex::compareIDs ( const IDConstPtr a,
const IDConstPtr b 
)

Compare two ID objects.

Parameters
[in]aFirst object to compare.
[in]bSecond object to compare.
Returns
True if a and b are the same, false otherwise.

Definition at line 57 of file id.cpp.

58 {
59  return compareIDs(*a, *b);
60 }

◆ compareIDs() [6/7]

bool robowflex::compareIDs ( const IDPtr a,
const ID::Key b 
)

Compare an ID object to a key.

Parameters
[in]aObject to compare.
[in]bKey to compare against.
Returns
True if a and b are the same, false otherwise.

Definition at line 67 of file id.cpp.

68 {
69  return compareIDs(*a, b);
70 }

◆ compareIDs() [7/7]

bool robowflex::compareIDs ( const IDPtr a,
const IDPtr b 
)

Compare two ID objects.

Parameters
[in]aFirst object to compare.
[in]bSecond object to compare.
Returns
True if a and b are the same, false otherwise.

Definition at line 52 of file id.cpp.

53 {
54  return compareIDs(*a, *b);
55 }

◆ explode()

void robowflex::explode ( )

Trigger a SEGSEGV.

Definition at line 101 of file util.cpp.

102 {
103  raise(SIGSEGV);
104 }

◆ toMatrix()

template<typename M >
M robowflex::toMatrix ( const RobotPose pose)

Convert the Robowflex pose type to another transform type.

Definition at line 33 of file adapter.h.

34  {
35  M newpose;
36  newpose.matrix() = pose.matrix();
37  return newpose;
38  }

◆ toMetricString()

std::string robowflex::toMetricString ( const PlannerMetric metric)

Convert a planner metric into a string.

Parameters
[in]metricThe metric to convert.
Returns
The metric as a string.

Definition at line 63 of file benchmarking.cpp.

64 {
65  return boost::apply_visitor(toMetricStringVisitor(), metric);
66 }

Variable Documentation

◆ cube

robowflex.cube = scene.get_object("Cube3")

Definition at line 51 of file robowflex.py.

◆ fetch

robowflex.fetch = rv.robot.Robot("Fetch", "package://robowflex_resources/fetch/robots/fetch.urdf")

Definition at line 13 of file robowflex.py.

◆ frame

robowflex.frame
Initial value:
1 = fetch.animate_path(
2  "package://robowflex_visualization/yaml/fetch_pick.yml",
3  15, # FPS
4  30, # Start Frame
5 )

Definition at line 36 of file robowflex.py.

◆ scene

robowflex.scene
Initial value:
1 = rv.scene.Scene("Scene",
2  "package://robowflex_library/yaml/test_fetch.yml")

Definition at line 32 of file robowflex.py.