#include <map>#include <memory>#include <optional>#include <string>#include <tuple>#include <unordered_set>#include <utility>#include <variant>#include <vector>#include "drake/common/trajectories/bezier_curve.h"#include "drake/common/trajectories/composite_trajectory.h"#include "drake/geometry/optimization/convex_set.h"#include "drake/geometry/optimization/graph_of_convex_sets.h"#include "drake/multibody/plant/multibody_plant.h"#include "drake/solvers/binding.h"#include "drake/solvers/constraint.h"#include "drake/solvers/cost.h"Classes | |
| class | GcsTrajectoryOptimization |
| GcsTrajectoryOptimization implements a simplified motion planning optimization problem introduced in the paper "Motion Planning around Obstacles with Convex Optimization" by Tobia Marcucci, Mark Petersen, David von Wrangel, Russ Tedrake. More... | |
| class | GcsTrajectoryOptimization::Subgraph |
| A Subgraph is a subset of the larger graph. More... | |
| class | GcsTrajectoryOptimization::EdgesBetweenSubgraphs |
| EdgesBetweenSubgraphs are defined as the connecting edges between two given subgraphs. More... | |
Namespaces | |
| drake | |
| drake::planning | |
| drake::planning::trajectory_optimization | |
Functions | |
| std::vector< int > | GetContinuousRevoluteJointIndices (const multibody::MultibodyPlant< double > &plant) |
| Returns a list of indices in the plant's generalized positions which correspond to a continuous revolute joint (a revolute joint with no joint limits). More... | |