Waypoints¶

class Waypoint : public jacobi::Element¶

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

The Waypoint class represents a point in the joint space of a robot with associated position, velocity, and acceleration values.

Public Functions

Waypoint(std::initializer_list<double> data)¶

Construct a waypoint by position data.

Parameters:

data – A list of position values to initialize the waypoint.

Waypoint(const Config &position)¶

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

Parameters:

position – The joint position to initialize the waypoint.

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

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

Parameters:
  • position – The joint position to initialize the waypoint.

  • velocity – The joint velocity to initialize the waypoint.

inline explicit Waypoint(const Config &position, const Config &velocity, const Config &acceleration)¶

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

Parameters:
  • position – The joint position to initialize the waypoint.

  • velocity – The joint velocity to initialize the waypoint.

  • acceleration – The joint acceleration to initialize the waypoint.

inline explicit Waypoint(size_t size)¶

Construct a zero-initialized waypoint with the given size.

Parameters:

size – The degrees of freedom for the waypoint.

inline explicit Waypoint()¶

Construct an empty waypoint.

inline void append(const Waypoint &other)¶

Append another waypoint to this one.

This method concatenates the position, velocity, and acceleration data from another waypoint to this one.

Parameters:

other – The waypoint to append to this one.

inline size_t size() const¶

Get the size (or degrees of freedom) of the waypoint.

Returns:

size_t The degrees of freedom represented by the waypoint.

bool is_within(const Waypoint &other) const¶

Check if this waypoint is within another waypoint.

This method checks if the current waypoint’s position, velocity, and acceleration are within the respective boundaries of another waypoint.

Parameters:

other – The waypoint to compare against.

Returns:

true If this waypoint is within the boundaries of the other.

Returns:

false If this waypoint is not within the boundaries of the other.

Public Members

Config position¶

The joint position at the waypoint.

Config velocity¶

The joint velocity at the waypoint.

Config acceleration¶

The joint acceleration at the waypoint.

class CartesianWaypoint : public jacobi::Element¶

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

The CartesianWaypoint class represents a point in Cartesian space with associated position, velocity, and acceleration frames. It is used to define the robot state in Cartesian space at a specific instance, with optional reference joint positions for inverse kinematics.

Public Functions

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

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

Parameters:
  • position – The position frame to initialize the waypoint.

  • reference_config – An optional joint configuration for inverse kinematics.

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

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

Parameters:
  • position – The position frame to initialize the waypoint.

  • velocity – The velocity frame to initialize the waypoint.

  • reference_config – An optional joint configuration for inverse kinematics.

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

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

Parameters:
  • position – The position frame to initialize the waypoint.

  • velocity – The velocity frame to initialize the waypoint.

  • acceleration – The acceleration frame to initialize the waypoint.

  • reference_config – An optional joint configuration for inverse kinematics.

explicit CartesianWaypoint()¶

Default constructor.

bool is_within(const CartesianWaypoint &other) const¶

Check if this Cartesian waypoint is within another Cartesian waypoint.

This method checks if the current waypoint’s position, velocity, and acceleration frames are within the respective boundaries of another CartesianWaypoint.

Parameters:

other – The CartesianWaypoint to compare against.

Returns:

true If this waypoint is within the boundaries of the other.

Returns:

false If this waypoint is not within the boundaries of the other.

bool is_within(const Waypoint &other, std::shared_ptr<RobotArm> robot) const¶

Check if this Cartesian waypoint is within a joint-space waypoint, given a specific robot arm.

This method checks if the current CartesianWaypoint’s position, velocity, and acceleration frames are within the boundaries of a joint space waypoint, considering the robot arm’s kinematics.

Parameters:
  • other – The joint-space Waypoint to compare against.

  • robot – The robot arm associated with the joint-space waypoint.

Returns:

true If this CartesianWaypoint is within the boundaries of the other joint-space waypoint.

Returns:

false If this CartesianWaypoint is not within the boundaries of the other joint-space waypoint.

Public Members

Frame position = {Frame::Identity()}¶

Frame of the position.

Frame velocity = {Frame::Identity()}¶

Frame of the velocity.

Frame acceleration = {Frame::Identity()}¶

Frame of the acceleration.

std::optional<Config> reference_config¶

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

class Region : public jacobi::Element¶

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

The Region class defines a region in joint space with boundaries on position, velocity, and acceleration. It is used to specify an area within which a the robot end-effector operates. The class provides methods to construct the region with varying levels of detail and to check if a given waypoint falls within the region’s boundaries.

Public Functions

explicit Region()¶

Default constructor.

explicit Region(const Config &min_position, const Config &max_position)¶

Construct a Region with position boundaries.

Parameters:
  • min_position – The minimum position boundary.

  • max_position – The maximum position boundary.

explicit Region(const Config &min_position, const Config &max_position, const Config &min_velocity, const Config &max_velocity)¶

Construct a Region with position and velocity boundaries.

Parameters:
  • min_position – The minimum position boundary.

  • max_position – The maximum position boundary.

  • min_velocity – The minimum velocity boundary.

  • max_velocity – The maximum velocity boundary.

explicit Region(const Config &min_position, const Config &max_position, const Config &min_velocity, const Config &max_velocity, const Config &min_acceleration, const Config &max_acceleration)¶

Construct a Region with position, velocity, and acceleration boundaries.

Parameters:
  • min_position – The minimum position boundary.

  • max_position – The maximum position boundary.

  • min_velocity – The minimum velocity boundary.

  • max_velocity – The maximum velocity boundary.

  • min_acceleration – The minimum acceleration boundary.

  • max_acceleration – The maximum acceleration boundary.

inline size_t size() const¶

Get the size (or degrees of freedom) of the region.

Returns:

size_t The degrees of freedom represented by the region.

bool is_within(const Waypoint &other) const¶

Check if a given waypoint is within the region.

This method checks if the given waypoint’s position, velocity, and acceleration fall within the respective boundaries defined by the region.

Parameters:

other – The waypoint to check.

Returns:

true If the waypoint is within the region’s boundaries.

Returns:

false If the waypoint is not within the region’s boundaries.

Public Members

Config min_position¶

Minimum position boundary of the region.

Config max_position¶

Maximum position boundary of the region.

Config min_velocity¶

Minimum velocity boundary of the region.

Config max_velocity¶

Maximum velocity boundary of the region.

Config min_acceleration¶

Minimum acceleration boundary of the region.

Config max_acceleration¶

Maximum acceleration boundary of the region.

struct CartesianRegionBound¶

The min or max boundary of a Cartesian region.

The CartesianRegionBound struct represents the boundaries of a region in Cartesian space. It defines both positional (x, y, z) and orientational (gamma, alpha) limits. These boundaries are used to constrain the movement or state of an object within a specified region.

Public Functions

inline CartesianRegionBound()¶

Default constructor.

inline explicit CartesianRegionBound(double x, double y, double z, double gamma = 0.0, double alpha = 0.0)¶

Construct a CartesianRegionBound with specified values.

Parameters:
  • x – The x-coordinate of the boundary.

  • y – The y-coordinate of the boundary.

  • z – The z-coordinate of the boundary.

  • gamma – The rotational component around the z-axis (yaw).

  • alpha – The rotational component around the x-axis (roll).

Public Members

double x = {0.0}¶

The x-coordinate of the boundary.

double y = {0.0}¶

The y-coordinate of the boundary.

double z = {0.0}¶

The z-coordinate of the boundary.

double gamma = {0.0}¶

The rotational component around the z-axis (yaw).

double alpha = {0.0}¶

The rotational component around the x-axis (roll).

class CartesianRegion : public jacobi::Element¶

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

The CartesianRegion class defines a region in Cartesian space with optional boundaries for position, velocity, and acceleration. It is used to describe constraints on a Cartesian region within which the robot end-effector operates. The region can also have an associated reference configuration.

Public Functions

CartesianRegion()¶

Default constructor.

explicit CartesianRegion(const Frame &origin)¶

Construct a CartesianRegion with a specified origin.

Parameters:

origin – The frame of reference for the region.

explicit CartesianRegion(const CartesianRegionBound &min_position, const CartesianRegionBound &max_position, const std::optional<Config> &reference_config = std::nullopt)¶

Construct a CartesianRegion with position boundaries and an optional reference configuration.

Parameters:
  • min_position – The minimum position boundary.

  • max_position – The maximum position boundary.

  • reference_config – An optional reference configuration.

explicit CartesianRegion(const CartesianRegionBound &min_position, const CartesianRegionBound &max_position, const CartesianRegionBound &min_velocity, const CartesianRegionBound &max_velocity, const std::optional<Config> &reference_config = std::nullopt)¶

Construct a CartesianRegion with position and velocity boundaries, and an optional reference configuration.

Parameters:
  • min_position – The minimum position boundary.

  • max_position – The maximum position boundary.

  • min_velocity – The minimum velocity boundary.

  • max_velocity – The maximum velocity boundary.

  • reference_config – An optional reference configuration.

explicit CartesianRegion(const CartesianRegionBound &min_position, const CartesianRegionBound &max_position, const CartesianRegionBound &min_velocity, const CartesianRegionBound &max_velocity, const CartesianRegionBound &min_acceleration, const CartesianRegionBound &max_acceleration, const std::optional<Config> &reference_config = std::nullopt)¶

Construct a CartesianRegion with position, velocity, and acceleration boundaries, and an optional reference configuration.

Parameters:
  • min_position – The minimum position boundary.

  • max_position – The maximum position boundary.

  • min_velocity – The minimum velocity boundary.

  • max_velocity – The maximum velocity boundary.

  • min_acceleration – The minimum acceleration boundary.

  • max_acceleration – The maximum acceleration boundary.

  • reference_config – An optional reference configuration.

bool is_within(const CartesianWaypoint &other) const¶

Check if a CartesianWaypoint is within the region.

Parameters:

other – The CartesianWaypoint to check.

Returns:

true If the waypoint is within the region.

Returns:

false If the waypoint is not within the region.

bool is_within(const Waypoint &other, std::shared_ptr<RobotArm> robot) const¶

Check if a Waypoint is within the region, given a specific robot arm.

Parameters:
  • other – The Waypoint to check.

  • robot – The robot arm associated with the waypoint.

Returns:

true If the waypoint is within the region.

Returns:

false If the waypoint is not within the region.

Public Members

CartesianRegionBound min_position¶

Minimum position boundary of the region.

CartesianRegionBound max_position¶

Maximum position boundary of the region.

CartesianRegionBound min_velocity¶

Minimum velocity boundary of the region.

CartesianRegionBound max_velocity¶

Maximum velocity boundary of the region.

CartesianRegionBound min_acceleration¶

Minimum acceleration boundary of the region.

CartesianRegionBound max_acceleration¶

Maximum acceleration boundary of the region.

std::optional<Config> reference_config¶

Reference configuration for the region, if any.

using MultiRobotPoint = std::map<std::shared_ptr<Robot>, std::variant<Config, Waypoint, CartesianWaypoint>>¶

A type for specifying an exact start or goal point per robot.

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

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

using ExactPoint = std::variant<Config, Waypoint, CartesianWaypoint, MultiRobotPoint>¶

All types for specifying exact start or goal points.