Skip to content

Commit

Permalink
Make base frame a parameter (#63)
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr authored Nov 18, 2024
1 parent 154e32b commit a24729d
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 1 deletion.
5 changes: 5 additions & 0 deletions parameters/ktopt_moveit_parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,11 @@ ktopt_interface:
description: "Robot description to be loaded by the internal Drake MultibodyPlant.",
default_value: "package://drake_models/franka_description/urdf/panda_arm_hand.urdf",
}
base_frame: {
type: string,
description: "Base frame of the robot that is attached to whatever the robot is mounted on.",
default_value: "panda_link0",
}
num_iterations: {
type: int,
description: "Number of iterations for the Drake mathematical program solver.",
Expand Down
3 changes: 2 additions & 1 deletion src/ktopt_planning_context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,6 +161,7 @@ void KTOptPlanningContext::solve(planning_interface::MotionPlanResponse& res)
// add collision constraints
for (int s = 0; s < params_.num_collision_check_points; ++s)
{
// The constraint will be evaluated as if it is bound with variables corresponding to r(s).
trajopt.AddPathPositionConstraint(std::make_shared<drake::multibody::MinimumDistanceLowerBoundConstraint>(
&plant, params_.collision_check_lower_distance_bound, &plant_context),
static_cast<double>(s) / (params_.num_collision_check_points - 1));
Expand Down Expand Up @@ -375,7 +376,7 @@ void KTOptPlanningContext::setRobotDescription(const std::string& robot_descript
const char* ModelUrl = params_.drake_robot_description.c_str();
const std::string urdf = drake::multibody::PackageMap{}.ResolveUrl(ModelUrl);
auto robot_instance = drake::multibody::Parser(&plant, &scene_graph).AddModels(urdf);
plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"));
plant.WeldFrames(plant.world_frame(), plant.GetFrameByName(params_.base_frame));

// planning scene transcription
const auto scene = getPlanningScene();
Expand Down

0 comments on commit a24729d

Please sign in to comment.