Skip to content
Snippets Groups Projects
Commit 6756d666 authored by Sebastian Ebert's avatar Sebastian Ebert
Browse files

updated defaults to fluid planning

parent 5065baf9
No related branches found
No related tags found
No related merge requests found
......@@ -22,7 +22,7 @@ namespace PlannerState {
TrajectoryUtil traj_util;
const double default_velocity = 1.0;
const std::string default_planning_mode = TrajectoryUtil::CARTESIAN_PATH;
const std::string default_planning_mode = TrajectoryUtil::FLUID_PATH;
bool isInitialized = false;
bool isLooping = true;
......@@ -185,7 +185,7 @@ void doMotion(const ros::NodeHandle &node_handle, moveit::planning_interface::Mo
}
double velocity = 0.0;
std::string planning_mode;
std::string planning_mode = "";
if (!node_handle.getParam("robot_speed_factor", velocity)) {
velocity = PlannerState::default_velocity;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment