diff --git a/src/TimedPlanner.cpp b/src/TimedPlanner.cpp index 8f08d95f8e5f3da0397d9f86c9c1e2ffe00be1a6..a1d019459df0269320acb37ab72d2d3e64bb0566 100644 --- a/src/TimedPlanner.cpp +++ b/src/TimedPlanner.cpp @@ -184,16 +184,16 @@ void doMotion(const ros::NodeHandle &node_handle, moveit::planning_interface::Mo } } - double velocity = 0.8; - std::string planning_mode = "cartesian_path"; + double velocity = 0.0 ; + std::string planning_mode; - /* if (!node_handle.getParam("robot_speed_factor", velocity)) { + if (!node_handle.getParam("robot_speed_factor", velocity)) { velocity = PlannerState::default_velocity; } if (!node_handle.getParam("robot_planning_mode", planning_mode)) { planning_mode = PlannerState::default_planning_mode; - }*/ + } ROS_INFO_STREAM("Planning the next trajectory in " << planning_mode << " with velocity " << velocity);