Skip to content

Commit d3946de

Browse files
committed
Code cleanup and Docker fixes
1 parent df7d3b4 commit d3946de

8 files changed

+151
-99
lines changed

.docker/Dockerfile

+2
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,9 @@ RUN apt-get update && \
1919
ca-certificates \
2020
gnupg \
2121
lsb-release \
22+
python3-pip \
2223
wget -y && \
24+
pip3 install --break-system-packages pre-commit && \
2325
wget -qO- https://drake-apt.csail.mit.edu/drake.asc | gpg --dearmor - \
2426
| sudo tee /etc/apt/trusted.gpg.d/drake.gpg >/dev/null && \
2527
echo "deb [arch=amd64] https://drake-apt.csail.mit.edu/$(lsb_release -cs) $(lsb_release -cs) main" \

CMakeLists.txt

+2-2
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ find_package(warehouse_ros REQUIRED)
2626
find_package(shape_msgs REQUIRED)
2727

2828
generate_parameter_library(ktopt_moveit_parameters
29-
res/ktopt_moveit_parameters.yaml)
29+
parameters/ktopt_moveit_parameters.yaml)
3030

3131
set(THIS_PACKAGE_INCLUDE_DEPENDS
3232
ament_cmake
@@ -44,7 +44,7 @@ include_directories(include)
4444
# ktopt planning plugin
4545
add_library(
4646
moveit_drake SHARED
47-
# KTOPT
47+
# Kinematic Trajectory Optimization (KTOpt)
4848
src/ktopt_planner_manager.cpp
4949
src/ktopt_planning_context.cpp
5050
# TOPPRA

README.md

+25-10
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@ Programming interface within [Drake](https://drake.mit.edu/). This allows the
99
user to setup motion planning as an optimization problem within ROS, with the
1010
rich specification of constraints and costs provided by `drake`.
1111

12+
1213
## Features
1314

1415
- Exposes
@@ -67,25 +68,39 @@ moveit):
6768
cd ${WORKSPACE}
6869
colcon build --event-handlers desktop_notification- status- --cmake-args -DCMAKE_BUILD_TYPE=Release --parallel-workers 1
6970

70-
### Run the demo
7171

72-
```
72+
## Examples
73+
74+
The planning pipeline testbench compares `moveit_drake` planners with existing MoveIt planners such as OMPL and Pilz.
75+
76+
```bash
7377
ros2 launch moveit_drake pipeline_testbench.launch.py
7478
```
7579

76-
### Development
80+
This interactive example shows constrained planning using the Drake KTOpt planner.
7781

78-
- Use [pre-commit to format your
79-
code](https://moveit.ros.org/documentation/contributing/code/#pre-commit-formatting-checks)
82+
```bash
83+
ros2 launch moveit_drake constrained_planning_demo.launch.py
84+
```
8085

81-
Within the container you can run the following command to format the code
8286

83-
# inside the moveit_drake package
84-
pre-commit run -a
87+
## Development
8588

86-
### Some helper commands
87-
To just rebuild `moveit_drake`
89+
### Formatting
90+
91+
Use [pre-commit to format your code](https://moveit.ros.org/documentation/contributing/code/#pre-commit-formatting-checks)
92+
93+
Within the container, you can run the following command to format the code
94+
95+
```bash
96+
# inside the moveit_drake package
97+
pre-commit run -a
8898
```
99+
100+
### Some helper commands
101+
To just rebuild `moveit_drake`.
102+
103+
```bash
89104
rm -rf build/moveit_drake install/moveit_drake
90105
colcon build --packages-select moveit_drake
91106
```

docker-compose.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ services:
1616
volumes:
1717
- /tmp/.X11-unix:/tml/.X11-unix:rw
1818
- ${XAUTHORITY:-$HOME/.Xauthority}:/root/.Xauthority
19-
- ./:/root/workspace/src/moveit_drake/
19+
- ./:/root/ws_moveit/src/moveit_drake/
2020
tty: true
2121
stdin_open: true
2222
network_mode: "host"
Original file line numberDiff line numberDiff line change
@@ -1,103 +1,119 @@
11
#pragma once
22

3+
#include <ktopt_moveit_parameters.hpp>
34
#include <moveit/planning_interface/planning_interface.h>
45
#include <shape_msgs/msg/solid_primitive.h>
5-
#include <ktopt_moveit_parameters.hpp>
66

77
// 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>
2614
#include <drake/multibody/inverse_kinematics/minimum_distance_lower_bound_constraint.h>
2715
#include <drake/multibody/inverse_kinematics/position_constraint.h>
16+
#include <drake/multibody/parsing/parser.h>
17+
#include <drake/multibody/plant/multibody_plant.h>
2818

2919
namespace ktopt_interface
3020
{
3121
// 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;
5422
using drake::multibody::MinimumDistanceLowerBoundConstraint;
5523
using drake::multibody::MultibodyPlant;
56-
using drake::multibody::PackageMap;
57-
using drake::multibody::Parser;
5824
using drake::multibody::PositionConstraint;
5925
using drake::planning::trajectory_optimization::KinematicTrajectoryOptimization;
60-
using drake::solvers::Solve;
6126
using drake::systems::Context;
6227
using drake::systems::Diagram;
6328
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;
7029
using Joints = std::vector<const moveit::core::JointModel*>;
7130

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+
*/
7236
class KTOptPlanningContext : public planning_interface::PlanningContext
7337
{
7438
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+
*/
7545
KTOptPlanningContext(const std::string& name, const std::string& group_name, const ktopt_interface::Params& params);
7646

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+
*/
7751
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+
*/
7859
void solve(planning_interface::MotionPlanDetailedResponse& res) override;
7960

61+
/**
62+
* @brief Terminates any running solutions.
63+
* @return True if successful, otherwise false.
64+
*/
8065
bool terminate() override;
66+
67+
/// @brief Clear the data structures used by the planner.
8168
void clear() override;
8269

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+
*/
8480
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+
*/
8591
void addPathPositionConstraints(KinematicTrajectoryOptimization& trajopt, const MultibodyPlant<double>& plant,
8692
Context<double>& plant_context, const double padding);
8793

8894
private:
95+
/// @brief The ROS parameters associated with this motion planner.
8996
const ktopt_interface::Params params_;
97+
98+
/// @brief The URDF robot description.
9099
std::string robot_description_;
91100

92-
// drake related variables
101+
/// @brief The Drake diagram describing the entire system.
93102
std::unique_ptr<Diagram<double>> diagram_;
103+
104+
/// @brief The builder for the Drake system diagram.
94105
std::unique_ptr<DiagramBuilder<double>> builder;
106+
107+
/// @brief The context that contains all the data necessary to perform computations on the diagram.
95108
std::unique_ptr<Context<double>> diagram_context_;
96-
VectorXd nominal_q_;
97-
const std::string OCTOMAP_NS = "<octomap>";
98109

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_;
102118
};
103119
} // namespace ktopt_interface

src/ktopt_planner_manager.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,10 @@ rclcpp::Logger getLogger()
1616
{
1717
return moveit::getLogger("moveit.planners.ktopt.planner_manager");
1818
}
19+
20+
/**
21+
* @brief Implementation for the Drake Kinematic Trajectory Optimization (KTOpt) motion planner in MoveIt.
22+
*/
1923
class KTOptPlannerManager : public planning_interface::PlannerManager
2024
{
2125
public:

0 commit comments

Comments
 (0)