Struct CartesianPath

Struct Documentation

struct CartesianPath

Contains a path of Cartesian configurations.

Public Functions

CartesianPath() = default

Default constructor.

inline CartesianPath(const std::vector<std::string> &base_frames, const std::vector<std::string> &tip_frames, const std::vector<std::vector<Eigen::Matrix4d>> &tforms)

Constructor.

Public Members

std::vector<std::string> base_frames

The names of the base (or reference) frames.

std::vector<std::string> tip_frames

The names of the tip (or target) frames.

std::vector<std::vector<Eigen::Matrix4d>> tforms

The list of Cartesian transforms from each base frame to each tip frame.

The outer vector indexes the end-effector frame and the inner vector indexes path waypoints, so tforms[frame_idx][path_idx] is the transform for tip_frames[frame_idx] at that path waypoint. NOTE: I’d like this to be a std::vector<std::vector<Eigen::Isometry3d>> but nanobind doesn’t have off the shelf bindings for this.

Friends

friend std::ostream &operator<<(std::ostream &os, const CartesianPath &path)

Prints basic information about the path.