Skip to content

Commit

Permalink
Fix build error
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr committed Aug 22, 2024
1 parent 6ffa1a8 commit 5e0f21c
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions src/add_toppra_time_parameterization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,9 +137,9 @@ class AddToppraTimeParameterization : public planning_interface::PlanningRespons
auto& plant = dynamic_cast<const MultibodyPlant<double>&>(diagram_->GetSubsystemByName("plant"));
auto& plant_context = diagram_->GetMutableSubsystemContext(plant, diagram_context_.get());
const auto& current_state = planning_scene->getCurrentState();
VectorXd q = VectorXd::Zero(plant.num_positions() + plant.num_velocities());
q << moveit::drake::getJointPositions(current_state, getGroupName(), plant);
q << moveit::drake::getJointVelocities(current_state, getGroupName(), plant);
Eigen::VectorXd q = Eigen::VectorXd::Zero(plant.num_positions() + plant.num_velocities());
q << moveit::drake::getJointPositions(current_state, joint_model_group->getName(), plant);
q << moveit::drake::getJointVelocities(current_state, joint_model_group->getName(), plant);
plant.SetPositionsAndVelocities(&plant_context, q);

// Create drake::trajectories::Trajectory from moveit trajectory
Expand Down

0 comments on commit 5e0f21c

Please sign in to comment.