diff --git a/baxter/baxter_moveit_config/launch/chomp_planning_pipeline.launch b/baxter/baxter_moveit_config/launch/chomp_planning_pipeline.launch
index a7730b7c..2dd8c502 100644
--- a/baxter/baxter_moveit_config/launch/chomp_planning_pipeline.launch
+++ b/baxter/baxter_moveit_config/launch/chomp_planning_pipeline.launch
@@ -9,7 +9,7 @@
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
- default_planner_request_adapters/AddTimeParameterization" />
+ default_planner_request_adapters/AddTimeOptimalParameterization" />
diff --git a/baxter/baxter_moveit_config/launch/ompl_planning_pipeline.launch b/baxter/baxter_moveit_config/launch/ompl_planning_pipeline.launch
index ac6aed4b..05f001d4 100644
--- a/baxter/baxter_moveit_config/launch/ompl_planning_pipeline.launch
+++ b/baxter/baxter_moveit_config/launch/ompl_planning_pipeline.launch
@@ -9,7 +9,7 @@
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
- default_planner_request_adapters/AddTimeParameterization" />
+ default_planner_request_adapters/AddTimeOptimalParameterization" />