Waypoints#

class Waypoint

A joint-space waypoint with possible position, velocity, and/or acceleration values.

Config position

The joint position at the waypoint.

Config velocity

The joint velocity at the waypoint.

Config acceleration

The joint acceleration at the waypoint.

Waypoint(const Config &position)

Construct a waypoint with given position and zero velocity and acceleration.

Waypoint(const Config &position, const Config &velocity)

Construct a waypoint with given position and velocity and zero acceleration.

Waypoint(const Config &position, const Config &velocity, const Config &acceleration)

Construct a waypoint with given position, velocity, and acceleration.

class CartesianWaypoint

A Cartesian-space waypoint with possible position, velocity, and/or acceleration values.

Frame position

Frame of the position.

Frame velocity

Frame of the velocity.

Frame acceleration

Frame of the acceleration.

std::optional<Config> reference_config

An optional joint position that is used as a reference for inverse kinematics.

CartesianWaypoint(const Frame &position, std::optional<Config> reference_config = std::nullopt)

Construct a Cartesian waypoint with given position and zero velocity and acceleration.

CartesianWaypoint(const Frame &position, const Frame &velocity, std::optional<Config> reference_config = std::nullopt)

Construct a Cartesian waypoint with given position and velocity and zero acceleration.

CartesianWaypoint(const Frame &position, const Frame &velocity, const Frame &acceleration, std::optional<Config> reference_config = std::nullopt)

Construct a Cartesian waypoint with given position, velocity, and acceleration.

class Region

A joint-space region with possible minimum and maximum position, velocity, and/or acceleration values.

Config min_position
Config max_position
Config min_velocity
Config max_velocity
Config min_acceleration
Config max_acceleration
class CartesianRegionBound

The min or max boundary of a Cartesian region.

double x

Translation along x-axis.

double y

Translation along y-axis.

double z

Translation along z-axis.

double gamma

Euler angle around the global z-axis.

double alpha

Angle from the global z-axis.

class CartesianRegion

A Cartesian-space region with possible minimum and maximum position, velocity, and/or acceleration values.

CartesianRegionBound min_position
CartesianRegionBound max_position
CartesianRegionBound min_velocity
CartesianRegionBound max_velocity
CartesianRegionBound min_acceleration
CartesianRegionBound max_acceleration
std::optional<Config> reference_config

An optional joint position that is used as a reference for inverse kinematics.

using Point = std::variant<Config, Waypoint, CartesianWaypoint, Region, CartesianRegion>

All types for speciying motion start or goals, either exact or by region.

using ExactPoint = std::variant<Config, Waypoint, CartesianWaypoint, Region, CartesianRegion>

All types for speciying exact start or goal points.