|
1 | 1 | #pragma once
|
2 | 2 |
|
| 3 | +#include <ktopt_moveit_parameters.hpp> |
3 | 4 | #include <moveit/planning_interface/planning_interface.h>
|
4 | 5 | #include <shape_msgs/msg/solid_primitive.h>
|
5 |
| -#include <ktopt_moveit_parameters.hpp> |
6 | 6 |
|
7 | 7 | // relevant drake includes
|
8 |
| -#include "drake/common/eigen_types.h" |
9 |
| -#include "drake/multibody/parsing/parser.h" |
10 |
| -#include "drake/geometry/scene_graph.h" |
11 |
| -#include "drake/systems/framework/diagram.h" |
12 |
| -#include "drake/systems/framework/diagram_builder.h" |
13 |
| -#include "drake/multibody/plant/multibody_plant.h" |
14 |
| -#include "drake/planning/trajectory_optimization/kinematic_trajectory_optimization.h" |
15 |
| -#include "drake/solvers/solve.h" |
16 |
| -#include "drake/geometry/meshcat.h" |
17 |
| -#include "drake/geometry/meshcat_visualizer.h" |
18 |
| -#include "drake/geometry/drake_visualizer.h" |
19 |
| -#include "drake/geometry/meshcat_params.h" |
20 |
| -#include "drake/geometry/geometry_frame.h" |
21 |
| -#include "drake/geometry/geometry_instance.h" |
22 |
| -#include "drake/geometry/geometry_roles.h" |
23 |
| -#include "drake/geometry/proximity_properties.h" |
24 |
| -#include "drake/visualization/visualization_config.h" |
25 |
| -#include "drake/visualization/visualization_config_functions.h" |
| 8 | +#include <drake/geometry/meshcat.h> |
| 9 | +#include <drake/geometry/meshcat_visualizer.h> |
| 10 | +#include <drake/geometry/scene_graph.h> |
| 11 | +#include <drake/planning/trajectory_optimization/kinematic_trajectory_optimization.h> |
| 12 | +#include <drake/systems/framework/diagram.h> |
| 13 | +#include <drake/systems/framework/diagram_builder.h> |
26 | 14 | #include <drake/multibody/inverse_kinematics/minimum_distance_lower_bound_constraint.h>
|
27 | 15 | #include <drake/multibody/inverse_kinematics/position_constraint.h>
|
| 16 | +#include <drake/multibody/parsing/parser.h> |
| 17 | +#include <drake/multibody/plant/multibody_plant.h> |
28 | 18 |
|
29 | 19 | namespace ktopt_interface
|
30 | 20 | {
|
31 | 21 | // declare all namespaces to be used
|
32 |
| -using drake::geometry::AddRigidHydroelasticProperties; |
33 |
| -using drake::geometry::Box; |
34 |
| -using drake::geometry::Cylinder; |
35 |
| -using drake::geometry::FrameId; |
36 |
| -using drake::geometry::GeometryFrame; |
37 |
| -using drake::geometry::GeometryId; |
38 |
| -using drake::geometry::GeometryInstance; |
39 |
| -using drake::geometry::IllustrationProperties; |
40 |
| -using drake::geometry::Meshcat; |
41 |
| -using drake::geometry::MeshcatParams; |
42 |
| -using drake::geometry::MeshcatVisualizer; |
43 |
| -using drake::geometry::MeshcatVisualizerParams; |
44 |
| -using drake::geometry::PerceptionProperties; |
45 |
| -using drake::geometry::ProximityProperties; |
46 |
| -using drake::geometry::Role; |
47 |
| -using drake::geometry::SceneGraph; |
48 |
| -using drake::geometry::Shape; |
49 |
| -using drake::geometry::SourceId; |
50 |
| -using drake::geometry::Sphere; |
51 |
| -using drake::math::RigidTransformd; |
52 |
| -using drake::multibody::AddMultibodyPlantSceneGraph; |
53 |
| -using drake::multibody::Frame; |
54 | 22 | using drake::multibody::MinimumDistanceLowerBoundConstraint;
|
55 | 23 | using drake::multibody::MultibodyPlant;
|
56 |
| -using drake::multibody::PackageMap; |
57 |
| -using drake::multibody::Parser; |
58 | 24 | using drake::multibody::PositionConstraint;
|
59 | 25 | using drake::planning::trajectory_optimization::KinematicTrajectoryOptimization;
|
60 |
| -using drake::solvers::Solve; |
61 | 26 | using drake::systems::Context;
|
62 | 27 | using drake::systems::Diagram;
|
63 | 28 | using drake::systems::DiagramBuilder;
|
64 |
| -using drake::visualization::ApplyVisualizationConfig; |
65 |
| -using drake::visualization::VisualizationConfig; |
66 |
| -using Eigen::Matrix3d; |
67 |
| -using Eigen::MatrixXd; |
68 |
| -using Eigen::Vector3d; |
69 |
| -using Eigen::VectorXd; |
70 | 29 | using Joints = std::vector<const moveit::core::JointModel*>;
|
71 | 30 |
|
| 31 | +/** |
| 32 | + * @brief Helper class that defines a planning context for Drake Kinematic Trajectory Optimization (KTOpt). |
| 33 | + * @details For more information, refer to the Drake documentation: |
| 34 | + * https://drake.mit.edu/doxygen_cxx/classdrake_1_1planning_1_1trajectory__optimization_1_1_kinematic_trajectory_optimization.html |
| 35 | + */ |
72 | 36 | class KTOptPlanningContext : public planning_interface::PlanningContext
|
73 | 37 | {
|
74 | 38 | public:
|
| 39 | + /** |
| 40 | + * @brief Constructs an instance of a KTOpt plannign context. |
| 41 | + * @param name The name of the planning context. |
| 42 | + * @param group_name The name of the joint group used for motion planning. |
| 43 | + * @param params The ROS parameters for this planner. |
| 44 | + */ |
75 | 45 | KTOptPlanningContext(const std::string& name, const std::string& group_name, const ktopt_interface::Params& params);
|
76 | 46 |
|
| 47 | + /** |
| 48 | + * @brief Calculates a trajectory for the current request of this context. |
| 49 | + * @param res The result containing the respective trajectory, or error code on failure. |
| 50 | + */ |
77 | 51 | void solve(planning_interface::MotionPlanResponse& res) override;
|
| 52 | + |
| 53 | + /** |
| 54 | + * @brief Calculates a trajectory for the current request of this context. |
| 55 | + * @details This function just delegates to the common response. |
| 56 | + * However, here the same trajectory is stored with the descriptions "plan","simplify", or "interpolate". |
| 57 | + * @param res The detailed result containing the respective trajectory, or error code on failure. |
| 58 | + */ |
78 | 59 | void solve(planning_interface::MotionPlanDetailedResponse& res) override;
|
79 | 60 |
|
| 61 | + /** |
| 62 | + * @brief Terminates any running solutions. |
| 63 | + * @return True if successful, otherwise false. |
| 64 | + */ |
80 | 65 | bool terminate() override;
|
| 66 | + |
| 67 | + /// @brief Clear the data structures used by the planner. |
81 | 68 | void clear() override;
|
82 | 69 |
|
83 |
| - void setRobotDescription(std::string robot_description); |
| 70 | + /** |
| 71 | + * @brief Sets the current robot description for planning. |
| 72 | + * @param robot_description The URDF string containing the robot description. |
| 73 | + */ |
| 74 | + void setRobotDescription(const std::string& robot_description); |
| 75 | + |
| 76 | + /** |
| 77 | + * @brief Transcribes a MoveIt planning scene to the Drake multibody plant used by this planner. |
| 78 | + * @param planning_scene The MoveIt planning scene to transcribe. |
| 79 | + */ |
84 | 80 | void transcribePlanningScene(const planning_scene::PlanningScene& planning_scene);
|
| 81 | + |
| 82 | + /** |
| 83 | + * @brief Adds path position constraints, if any, to the planning problem. |
| 84 | + * @param trajopt The Drake mathematical program containing the trajectory optimization problem. |
| 85 | + * @param plant The Drake multibody plant to use for planning. |
| 86 | + * @param plant_context The context associated with the multibody plant. |
| 87 | + * @param padding Additional position padding on the MoveIt constraint, in meters. |
| 88 | + * This ensures that constraints are more likely to hold for the entire trajectory, since the |
| 89 | + * Drake mathematical program only optimizes constraints at discrete points along the path. |
| 90 | + */ |
85 | 91 | void addPathPositionConstraints(KinematicTrajectoryOptimization& trajopt, const MultibodyPlant<double>& plant,
|
86 | 92 | Context<double>& plant_context, const double padding);
|
87 | 93 |
|
88 | 94 | private:
|
| 95 | + /// @brief The ROS parameters associated with this motion planner. |
89 | 96 | const ktopt_interface::Params params_;
|
| 97 | + |
| 98 | + /// @brief The URDF robot description. |
90 | 99 | std::string robot_description_;
|
91 | 100 |
|
92 |
| - // drake related variables |
| 101 | + /// @brief The Drake diagram describing the entire system. |
93 | 102 | std::unique_ptr<Diagram<double>> diagram_;
|
| 103 | + |
| 104 | + /// @brief The builder for the Drake system diagram. |
94 | 105 | std::unique_ptr<DiagramBuilder<double>> builder;
|
| 106 | + |
| 107 | + /// @brief The context that contains all the data necessary to perform computations on the diagram. |
95 | 108 | std::unique_ptr<Context<double>> diagram_context_;
|
96 |
| - VectorXd nominal_q_; |
97 |
| - const std::string OCTOMAP_NS = "<octomap>"; |
98 | 109 |
|
99 |
| - // visualization |
100 |
| - std::shared_ptr<Meshcat> meshcat_; |
101 |
| - MeshcatVisualizer<double>* visualizer_; |
| 110 | + /// @brief The nominal joint configuration of the robot, used for joint centering objectives. |
| 111 | + Eigen::VectorXd nominal_q_; |
| 112 | + |
| 113 | + /// @brief Pointer to the Meshcat instance associated with this planner. |
| 114 | + std::shared_ptr<drake::geometry::Meshcat> meshcat_; |
| 115 | + |
| 116 | + /// @brief The Drake MeshCat visualizer associated with this planner. |
| 117 | + drake::geometry::MeshcatVisualizer<double>* visualizer_; |
102 | 118 | };
|
103 | 119 | } // namespace ktopt_interface
|
0 commit comments