Skip to content

Commit

Permalink
Make TOTG the default time-parameterization algorithm everywhere (#1218)
Browse files Browse the repository at this point in the history
Co-authored-by: Jafar <cafer.abdi@gmail.com>
  • Loading branch information
AndyZe and JafarAbdi authored May 10, 2022
1 parent 40b7a4b commit 4ace026
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,6 @@

#include <chomp_interface/chomp_planning_context.h>
#include <moveit/robot_state/conversions.h>
#include <moveit/trajectory_processing/iterative_time_parameterization.h>

#include "rclcpp/rclcpp.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@
#include <moveit/planning_interface/planning_interface.h>
#include <moveit/planning_request_adapter/planning_request_adapter.h>
#include <moveit/robot_state/conversions.h>
#include <moveit/trajectory_processing/iterative_time_parameterization.h>
#include <moveit/trajectory_processing/trajectory_tools.h>

#include <eigen3/Eigen/Core>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@
#include <moveit/robot_state/robot_state.h>
#include <moveit/robot_state/cartesian_interpolator.h>
#include <moveit_msgs/msg/display_trajectory.hpp>
#include <moveit/trajectory_processing/iterative_time_parameterization.h>
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.h>

namespace
{
Expand Down Expand Up @@ -179,7 +179,7 @@ bool MoveGroupCartesianPathService::computeService(const std::shared_ptr<rmw_req

// time trajectory
// \todo optionally compute timing to move the eef with constant speed
trajectory_processing::IterativeParabolicTimeParameterization time_param;
trajectory_processing::TimeOptimalTrajectoryGeneration time_param;
time_param.computeTimeStamps(rt, 1.0);

rt.getRobotTrajectoryMsg(res->solution);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@
#else
#include <tf2_eigen/tf2_eigen.h>
#endif
#include <moveit/trajectory_processing/iterative_time_parameterization.h>
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.h>

#include "ui_motion_planning_rviz_plugin_frame.h"

Expand Down Expand Up @@ -156,9 +156,9 @@ bool MotionPlanningFrame::computeCartesianPlan()
// https://groups.google.com/forum/#!topic/moveit-users/MOoFxy2exT4
robot_trajectory::RobotTrajectory rt(move_group_->getRobotModel(), move_group_->getName());
rt.setRobotTrajectoryMsg(*move_group_->getCurrentState(), trajectory);
trajectory_processing::IterativeParabolicTimeParameterization iptp;
bool success =
iptp.computeTimeStamps(rt, ui_->velocity_scaling_factor->value(), ui_->acceleration_scaling_factor->value());
trajectory_processing::TimeOptimalTrajectoryGeneration time_parameterization;
bool success = time_parameterization.computeTimeStamps(rt, ui_->velocity_scaling_factor->value(),
ui_->acceleration_scaling_factor->value());
RCLCPP_INFO(LOGGER, "Computing time stamps %s", success ? "SUCCEEDED" : "FAILED");

// Store trajectory in current_plan_
Expand Down

0 comments on commit 4ace026

Please sign in to comment.