Namespaces | Classes | Typedefs | Functions
descartes_core Namespace Reference

Namespaces

namespace  detail
namespace  PlannerErrors
namespace  utils

Classes

struct  Frame
 Frame is a wrapper for an affine frame transform. Frame inverse can also be stored for increased speed in downstream calculations. More...
class  PathPlannerBase
class  RobotModel
 RobotModel defines the interface to a kinematics/dynamics functions. Implementations of this class will be used in conjunction with TrajectoryPt objects to determine forward and inverse kinematics. More...
struct  TimingConstraint
 A window of time for this point to be achieved relative to a previous point or the starting position. More...
class  TrajectoryID_
 TrajectoryID_ represents a unique id to be associated with a TrajectoryPt. More...
class  TrajectoryPt

Typedefs

typedef std::map< std::string,
std::string > 
PlannerConfig
typedef PlannerErrors::PlannerError PlannerError
typedef TrajectoryID_< uint64_t > TrajectoryID

Functions

 DESCARTES_CLASS_FORWARD (RobotModel)
 DESCARTES_CLASS_FORWARD (PathPlannerBase)
 DESCARTES_CLASS_FORWARD (TrajectoryPt)
 A TrajectoryPt is the basis for a Trajectory describing the desired path a robot should execute. The desired robot motion spans both Cartesian and Joint space, and so the TrajectoryPt must have capability to report on both these properties.
template<typename T >
bool operator!= (TrajectoryID_< T > lhs, TrajectoryID_< T > rhs)
template<typename T >
bool operator< (TrajectoryID_< T > lhs, TrajectoryID_< T > rhs)
template<typename T >
std::ostream & operator<< (std::ostream &os, TrajectoryID_< T > id)
template<typename T >
bool operator== (TrajectoryID_< T > lhs, TrajectoryID_< T > rhs)

Typedef Documentation

typedef std::map<std::string, std::string> descartes_core::PlannerConfig

Definition at line 40 of file path_planner_base.h.

Definition at line 38 of file path_planner_base.h.

Definition at line 146 of file trajectory_id.h.


Function Documentation

A TrajectoryPt is the basis for a Trajectory describing the desired path a robot should execute. The desired robot motion spans both Cartesian and Joint space, and so the TrajectoryPt must have capability to report on both these properties.

In practice, an application will create a series of process points, and use these process points to create a Trajectory that can be solved for a robot path. In order to implement this easily, each process point should keep track of the TrajectoryPt id, and provide an interpolation method between points.

template<typename T >
bool descartes_core::operator!= ( TrajectoryID_< T lhs,
TrajectoryID_< T rhs 
) [inline]

Definition at line 128 of file trajectory_id.h.

template<typename T >
bool descartes_core::operator< ( TrajectoryID_< T lhs,
TrajectoryID_< T rhs 
) [inline]

Definition at line 134 of file trajectory_id.h.

template<typename T >
std::ostream& descartes_core::operator<< ( std::ostream &  os,
TrajectoryID_< T id 
) [inline]

Definition at line 140 of file trajectory_id.h.

template<typename T >
bool descartes_core::operator== ( TrajectoryID_< T lhs,
TrajectoryID_< T rhs 
) [inline]

Definition at line 122 of file trajectory_id.h.



descartes_core
Author(s): Dan Solomon
autogenerated on Thu Jun 6 2019 21:35:59