Skip to content

Commit 671ea78

Browse files
Rename PlanProfile to MoveProfile
1 parent 824ec23 commit 671ea78

File tree

61 files changed

+562
-562
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

61 files changed

+562
-562
lines changed

tesseract_examples/src/basic_cartesian_example.cpp

Lines changed: 20 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -61,8 +61,8 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
6161
#include <tesseract_motion_planners/core/utils.h>
6262
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_default_composite_profile.h>
6363
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_composite_profile.h>
64-
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_default_plan_profile.h>
65-
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_plan_profile.h>
64+
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_default_move_profile.h>
65+
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_move_profile.h>
6666

6767
#include <tesseract_task_composer/core/task_composer_context.h>
6868
#include <tesseract_task_composer/core/task_composer_data_storage.h>
@@ -240,15 +240,15 @@ bool BasicCartesianExample::run()
240240
composite_profile->velocity_coeff = Eigen::VectorXd::Ones(1);
241241
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "cartesian_program", composite_profile);
242242

243-
auto plan_profile = std::make_shared<TrajOptIfoptDefaultPlanProfile>();
244-
plan_profile->cartesian_cost_config.enabled = false;
245-
plan_profile->cartesian_constraint_config.enabled = true;
246-
plan_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Ones(6);
247-
plan_profile->joint_cost_config.enabled = false;
248-
plan_profile->joint_constraint_config.enabled = true;
249-
plan_profile->joint_constraint_config.coeff = Eigen::VectorXd::Ones(7);
250-
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "RASTER", plan_profile);
251-
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "freespace_profile", plan_profile);
243+
auto move_profile = std::make_shared<TrajOptIfoptDefaultMoveProfile>();
244+
move_profile->cartesian_cost_config.enabled = false;
245+
move_profile->cartesian_constraint_config.enabled = true;
246+
move_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Ones(6);
247+
move_profile->joint_cost_config.enabled = false;
248+
move_profile->joint_constraint_config.enabled = true;
249+
move_profile->joint_constraint_config.coeff = Eigen::VectorXd::Ones(7);
250+
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "RASTER", move_profile);
251+
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "freespace_profile", move_profile);
252252
}
253253
else
254254
{
@@ -265,15 +265,15 @@ bool BasicCartesianExample::run()
265265
composite_profile->velocity_coeff = Eigen::VectorXd::Ones(1);
266266
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "cartesian_program", composite_profile);
267267

268-
auto plan_profile = std::make_shared<TrajOptDefaultPlanProfile>();
269-
plan_profile->cartesian_cost_config.enabled = false;
270-
plan_profile->cartesian_constraint_config.enabled = true;
271-
plan_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Ones(6);
272-
plan_profile->joint_cost_config.enabled = false;
273-
plan_profile->joint_constraint_config.enabled = true;
274-
plan_profile->joint_constraint_config.coeff = Eigen::VectorXd::Ones(7);
275-
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "RASTER", plan_profile);
276-
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "freespace_profile", plan_profile);
268+
auto move_profile = std::make_shared<TrajOptDefaultMoveProfile>();
269+
move_profile->cartesian_cost_config.enabled = false;
270+
move_profile->cartesian_constraint_config.enabled = true;
271+
move_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Ones(6);
272+
move_profile->joint_cost_config.enabled = false;
273+
move_profile->joint_constraint_config.enabled = true;
274+
move_profile->joint_constraint_config.coeff = Eigen::VectorXd::Ones(7);
275+
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "RASTER", move_profile);
276+
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "freespace_profile", move_profile);
277277
}
278278

279279
// Create task

tesseract_examples/src/car_seat_example.cpp

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -66,10 +66,10 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
6666
#include <tesseract_task_composer/core/task_composer_plugin_factory.h>
6767

6868
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_composite_profile.h>
69-
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_plan_profile.h>
69+
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_move_profile.h>
7070
#include <tesseract_motion_planners/trajopt/profile/trajopt_osqp_solver_profile.h>
7171
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_default_composite_profile.h>
72-
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_default_plan_profile.h>
72+
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_default_move_profile.h>
7373
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_osqp_solver_profile.h>
7474
#include <tesseract_motion_planners/core/utils.h>
7575

@@ -302,19 +302,19 @@ bool CarSeatExample::run()
302302
trajopt_ifopt_composite_profile->smooth_jerks = true;
303303
trajopt_ifopt_composite_profile->jerk_coeff = Eigen::VectorXd::Ones(1);
304304

305-
auto trajopt_ifopt_plan_profile = std::make_shared<TrajOptIfoptDefaultPlanProfile>();
306-
trajopt_ifopt_plan_profile->cartesian_cost_config.enabled = false;
307-
trajopt_ifopt_plan_profile->cartesian_constraint_config.enabled = true;
308-
trajopt_ifopt_plan_profile->joint_cost_config.enabled = false;
309-
trajopt_ifopt_plan_profile->joint_constraint_config.enabled = true;
305+
auto trajopt_ifopt_move_profile = std::make_shared<TrajOptIfoptDefaultMoveProfile>();
306+
trajopt_ifopt_move_profile->cartesian_cost_config.enabled = false;
307+
trajopt_ifopt_move_profile->cartesian_constraint_config.enabled = true;
308+
trajopt_ifopt_move_profile->joint_cost_config.enabled = false;
309+
trajopt_ifopt_move_profile->joint_constraint_config.enabled = true;
310310

311311
auto trajopt_ifopt_solver_profile = std::make_shared<TrajOptIfoptOSQPSolverProfile>();
312312
trajopt_ifopt_solver_profile->opt_params.max_iterations = 200;
313313
trajopt_ifopt_solver_profile->opt_params.min_approx_improve = 1e-3;
314314
trajopt_ifopt_solver_profile->opt_params.min_trust_box_size = 1e-3;
315315

316316
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "FREESPACE", trajopt_ifopt_composite_profile);
317-
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "FREESPACE", trajopt_ifopt_plan_profile);
317+
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "FREESPACE", trajopt_ifopt_move_profile);
318318
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "FREESPACE", trajopt_ifopt_solver_profile);
319319
}
320320
else
@@ -333,19 +333,19 @@ bool CarSeatExample::run()
333333
trajopt_composite_profile->collision_cost_config.collision_check_config.longest_valid_segment_length = 0.1;
334334
trajopt_composite_profile->collision_cost_config.collision_margin_buffer = 0.01;
335335

336-
auto trajopt_plan_profile = std::make_shared<TrajOptDefaultPlanProfile>();
337-
trajopt_plan_profile->cartesian_cost_config.enabled = false;
338-
trajopt_plan_profile->cartesian_constraint_config.enabled = true;
339-
trajopt_plan_profile->joint_cost_config.enabled = false;
340-
trajopt_plan_profile->joint_constraint_config.enabled = true;
336+
auto trajopt_move_profile = std::make_shared<TrajOptDefaultMoveProfile>();
337+
trajopt_move_profile->cartesian_cost_config.enabled = false;
338+
trajopt_move_profile->cartesian_constraint_config.enabled = true;
339+
trajopt_move_profile->joint_cost_config.enabled = false;
340+
trajopt_move_profile->joint_constraint_config.enabled = true;
341341

342342
auto trajopt_solver_profile = std::make_shared<TrajOptOSQPSolverProfile>();
343343
trajopt_solver_profile->opt_params.max_iter = 200;
344344
trajopt_solver_profile->opt_params.min_approx_improve = 1e-3;
345345
trajopt_solver_profile->opt_params.min_trust_box_size = 1e-3;
346346

347347
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "FREESPACE", trajopt_composite_profile);
348-
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "FREESPACE", trajopt_plan_profile);
348+
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "FREESPACE", trajopt_move_profile);
349349
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "FREESPACE", trajopt_solver_profile);
350350
}
351351

tesseract_examples/src/freespace_hybrid_example.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
5050
#include <tesseract_command_language/profile_dictionary.h>
5151
#include <tesseract_command_language/utils.h>
5252

53-
#include <tesseract_motion_planners/ompl/profile/ompl_real_vector_plan_profile.h>
53+
#include <tesseract_motion_planners/ompl/profile/ompl_real_vector_move_profile.h>
5454
#include <tesseract_motion_planners/ompl/ompl_planner_configurator.h>
5555
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_default_composite_profile.h>
5656
#include <tesseract_motion_planners/core/utils.h>
@@ -198,7 +198,7 @@ bool FreespaceHybridExample::run()
198198
auto profiles = std::make_shared<ProfileDictionary>();
199199

200200
// Create OMPL Profile
201-
auto ompl_profile = std::make_shared<OMPLRealVectorPlanProfile>();
201+
auto ompl_profile = std::make_shared<OMPLRealVectorMoveProfile>();
202202
auto ompl_planner_config = std::make_shared<RRTConnectConfigurator>();
203203
ompl_planner_config->range = range_;
204204
ompl_profile->solver_config.planning_time = planning_time_;

tesseract_examples/src/freespace_ompl_example.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
5050
#include <tesseract_command_language/move_instruction.h>
5151
#include <tesseract_command_language/utils.h>
5252

53-
#include <tesseract_motion_planners/ompl/profile/ompl_real_vector_plan_profile.h>
53+
#include <tesseract_motion_planners/ompl/profile/ompl_real_vector_move_profile.h>
5454
#include <tesseract_motion_planners/ompl/ompl_planner_configurator.h>
5555
#include <tesseract_motion_planners/core/utils.h>
5656

@@ -182,7 +182,7 @@ bool FreespaceOMPLExample::run()
182182
auto executor = factory.createTaskComposerExecutor("TaskflowExecutor");
183183

184184
// Create OMPL Profile
185-
auto ompl_profile = std::make_shared<OMPLRealVectorPlanProfile>();
185+
auto ompl_profile = std::make_shared<OMPLRealVectorMoveProfile>();
186186
auto ompl_planner_config = std::make_shared<RRTConnectConfigurator>();
187187
ompl_planner_config->range = range_;
188188
ompl_profile->solver_config.planning_time = planning_time_;

tesseract_examples/src/glass_upright_example.cpp

Lines changed: 20 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -67,8 +67,8 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
6767
#include <tesseract_motion_planners/core/utils.h>
6868
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_default_composite_profile.h>
6969
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_composite_profile.h>
70-
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_default_plan_profile.h>
71-
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_plan_profile.h>
70+
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_default_move_profile.h>
71+
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_move_profile.h>
7272

7373
#include <tesseract_geometry/impl/sphere.h>
7474

@@ -218,16 +218,16 @@ bool GlassUprightExample::run()
218218
composite_profile->acceleration_coeff = Eigen::VectorXd::Ones(1);
219219
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "UPRIGHT", composite_profile);
220220

221-
auto plan_profile = std::make_shared<TrajOptIfoptDefaultPlanProfile>();
222-
plan_profile->joint_cost_config.enabled = false;
223-
plan_profile->cartesian_cost_config.enabled = false;
224-
plan_profile->cartesian_constraint_config.enabled = true;
225-
plan_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Constant(6, 1, 5);
226-
plan_profile->cartesian_constraint_config.coeff(0) = 0;
227-
plan_profile->cartesian_constraint_config.coeff(1) = 0;
228-
plan_profile->cartesian_constraint_config.coeff(2) = 0;
221+
auto move_profile = std::make_shared<TrajOptIfoptDefaultMoveProfile>();
222+
move_profile->joint_cost_config.enabled = false;
223+
move_profile->cartesian_cost_config.enabled = false;
224+
move_profile->cartesian_constraint_config.enabled = true;
225+
move_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Constant(6, 1, 5);
226+
move_profile->cartesian_constraint_config.coeff(0) = 0;
227+
move_profile->cartesian_constraint_config.coeff(1) = 0;
228+
move_profile->cartesian_constraint_config.coeff(2) = 0;
229229

230-
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "UPRIGHT", plan_profile);
230+
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "UPRIGHT", move_profile);
231231
}
232232
else
233233
{
@@ -249,17 +249,17 @@ bool GlassUprightExample::run()
249249
composite_profile->acceleration_coeff = Eigen::VectorXd::Ones(1);
250250
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "UPRIGHT", composite_profile);
251251

252-
auto plan_profile = std::make_shared<TrajOptDefaultPlanProfile>();
253-
plan_profile->joint_cost_config.enabled = false;
254-
plan_profile->cartesian_cost_config.enabled = false;
255-
plan_profile->cartesian_constraint_config.enabled = true;
256-
plan_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Constant(6, 1, 5);
257-
plan_profile->cartesian_constraint_config.coeff(0) = 0;
258-
plan_profile->cartesian_constraint_config.coeff(1) = 0;
259-
plan_profile->cartesian_constraint_config.coeff(2) = 0;
252+
auto move_profile = std::make_shared<TrajOptDefaultMoveProfile>();
253+
move_profile->joint_cost_config.enabled = false;
254+
move_profile->cartesian_cost_config.enabled = false;
255+
move_profile->cartesian_constraint_config.enabled = true;
256+
move_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Constant(6, 1, 5);
257+
move_profile->cartesian_constraint_config.coeff(0) = 0;
258+
move_profile->cartesian_constraint_config.coeff(1) = 0;
259+
move_profile->cartesian_constraint_config.coeff(2) = 0;
260260

261261
// Add profile to Dictionary
262-
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "UPRIGHT", plan_profile);
262+
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "UPRIGHT", move_profile);
263263
}
264264

265265
// Create task

tesseract_examples/src/pick_and_place_example.cpp

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -44,11 +44,11 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
4444
#include <tesseract_environment/commands/modify_allowed_collisions_command.h>
4545
#include <tesseract_environment/commands/move_link_command.h>
4646

47-
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_plan_profile.h>
47+
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_move_profile.h>
4848
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_composite_profile.h>
4949
#include <tesseract_motion_planners/trajopt/profile/trajopt_osqp_solver_profile.h>
5050
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_default_composite_profile.h>
51-
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_default_plan_profile.h>
51+
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_default_move_profile.h>
5252
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_osqp_solver_profile.h>
5353
#include <tesseract_motion_planners/core/utils.h>
5454

@@ -229,11 +229,11 @@ bool PickAndPlaceExample::run()
229229
if (ifopt_)
230230
{
231231
// Create TrajOpt_Ifopt Profile
232-
auto trajopt_ifopt_plan_profile = std::make_shared<TrajOptIfoptDefaultPlanProfile>();
233-
trajopt_ifopt_plan_profile->joint_cost_config.enabled = false;
234-
trajopt_ifopt_plan_profile->cartesian_cost_config.enabled = false;
235-
trajopt_ifopt_plan_profile->cartesian_constraint_config.enabled = true;
236-
trajopt_ifopt_plan_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Constant(6, 1, 10);
232+
auto trajopt_ifopt_move_profile = std::make_shared<TrajOptIfoptDefaultMoveProfile>();
233+
trajopt_ifopt_move_profile->joint_cost_config.enabled = false;
234+
trajopt_ifopt_move_profile->cartesian_cost_config.enabled = false;
235+
trajopt_ifopt_move_profile->cartesian_constraint_config.enabled = true;
236+
trajopt_ifopt_move_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Constant(6, 1, 10);
237237

238238
auto trajopt_ifopt_composite_profile = std::make_shared<TrajOptIfoptDefaultCompositeProfile>();
239239
trajopt_ifopt_composite_profile->collision_constraint_config = trajopt_common::TrajOptCollisionConfig(0.0, 10);
@@ -259,18 +259,18 @@ bool PickAndPlaceExample::run()
259259
auto trajopt_ifopt_solver_profile = std::make_shared<TrajOptIfoptOSQPSolverProfile>();
260260
trajopt_ifopt_solver_profile->opt_params.max_iterations = 100;
261261

262-
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "CARTESIAN", trajopt_ifopt_plan_profile);
262+
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "CARTESIAN", trajopt_ifopt_move_profile);
263263
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "DEFAULT", trajopt_ifopt_composite_profile);
264264
profiles->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, "DEFAULT", trajopt_ifopt_solver_profile);
265265
}
266266
else
267267
{
268268
// Create TrajOpt Profile
269-
auto trajopt_plan_profile = std::make_shared<TrajOptDefaultPlanProfile>();
270-
trajopt_plan_profile->joint_cost_config.enabled = false;
271-
trajopt_plan_profile->cartesian_cost_config.enabled = false;
272-
trajopt_plan_profile->cartesian_constraint_config.enabled = true;
273-
trajopt_plan_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Constant(6, 1, 10);
269+
auto trajopt_move_profile = std::make_shared<TrajOptDefaultMoveProfile>();
270+
trajopt_move_profile->joint_cost_config.enabled = false;
271+
trajopt_move_profile->cartesian_cost_config.enabled = false;
272+
trajopt_move_profile->cartesian_constraint_config.enabled = true;
273+
trajopt_move_profile->cartesian_constraint_config.coeff = Eigen::VectorXd::Constant(6, 1, 10);
274274

275275
auto trajopt_composite_profile = std::make_shared<TrajOptDefaultCompositeProfile>();
276276
trajopt_composite_profile->collision_constraint_config = trajopt_common::TrajOptCollisionConfig(0.0, 10);
@@ -288,7 +288,7 @@ bool PickAndPlaceExample::run()
288288
auto trajopt_solver_profile = std::make_shared<TrajOptOSQPSolverProfile>();
289289
trajopt_solver_profile->opt_params.max_iter = 100;
290290

291-
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "CARTESIAN", trajopt_plan_profile);
291+
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "CARTESIAN", trajopt_move_profile);
292292
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "DEFAULT", trajopt_composite_profile);
293293
profiles->addProfile(TRAJOPT_DEFAULT_NAMESPACE, "DEFAULT", trajopt_solver_profile);
294294
}

0 commit comments

Comments
 (0)