Skip to content

Commit

Permalink
Cleanups
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr committed Aug 16, 2024
1 parent bdb8bf6 commit 4f39fc5
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 9 deletions.
4 changes: 2 additions & 2 deletions demo/src/pipeline_testbench_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -366,8 +366,8 @@ int main(int argc, char** argv)
RCLCPP_INFO(LOGGER, "Starting Pipeline Testbench example ...");
for (const auto& motion_plan_req : demo.getMotionPlanRequests())
{
demo.planAndVisualize({ /*{ "ompl", "RRTConnectkConfigDefault" }, { "stomp", "stomp" }, { "drake_ktopt", "" },*/ {
"drake_toppra", "" } },
demo.planAndVisualize({ { "ompl", "RRTConnectkConfigDefault" },
{ "stomp", "stomp" }, { "drake_ktopt", "" }, { "drake_toppra", "" } },
motion_plan_req);
}
demo.getVisualTools().prompt("Press 'next' in the RvizVisualToolsGui window to finish the demo");
Expand Down
7 changes: 0 additions & 7 deletions include/moveit/drake/conversions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,13 +73,6 @@ getPiecewisePolynomial(const ::robot_trajectory::RobotTrajectory& robot_trajecto
std::vector<Eigen::MatrixXd> samples;
samples.reserve(robot_trajectory.getWayPointCount());

// Print the first and last point of the trajectory
const auto& first_point = robot_trajectory.getWayPoint(0);
const auto& last_point = robot_trajectory.getWayPoint(robot_trajectory.getWayPointCount() - 1);
Eigen::VectorXd first_position(first_point.getVariableCount());
Eigen::VectorXd last_position(last_point.getVariableCount());
first_point.copyJointGroupPositions(group, first_position);
last_point.copyJointGroupPositions(group, last_position);
// Create samples & breaks
for (std::size_t i = 0; i < robot_trajectory.getWayPointCount(); ++i)
{
Expand Down

0 comments on commit 4f39fc5

Please sign in to comment.