Skip to content

Commit 5aea5ec

Browse files
committed
More changed functions and add re-planning
1 parent aae6975 commit 5aea5ec

File tree

1 file changed

+6
-7
lines changed

1 file changed

+6
-7
lines changed

clr_pick_and_place_demo/src/run_demo.cpp

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -760,38 +760,37 @@ class RunDemoNode : public rclcpp::Node
760760
{
761761
move_group->setJointValueTarget(move_group->getNamedTargetValues(waypoint.preset_name));
762762
}
763-
if (waypoint.use_jconfig)
763+
else if (waypoint.use_jconfig)
764764
{
765765
move_group->setJointValueTarget(waypoint.config);
766-
move_group->setNumPlanningAttempts(10);
767766
}
768767
else
769768
{
770-
geometry_msgs::msg::Pose start_pose = move_group->getCurrentPose().pose;
771769
geometry_msgs::msg::Pose end_pose = waypoint.pose;
772770
if (waypoint.is_relative)
773771
{
772+
geometry_msgs::msg::Pose start_pose = move_group->getCurrentPose().pose;
774773
end_pose = this->relative_to_global(start_pose, end_pose);
775774
}
776-
move_group->setJointValueTarget(end_pose);
777-
move_group->setNumPlanningAttempts(10);
775+
move_group->setPoseTarget(end_pose);
778776
}
779777

778+
move_group->setNumPlanningAttempts(5);
780779
move_group->setMaxVelocityScalingFactor(scaling);
781780
move_group->setMaxAccelerationScalingFactor(scaling);
782781

783782
moveit::planning_interface::MoveGroupInterface::Plan plan;
784783
moveit::core::MoveItErrorCode error_code = move_group->plan(plan);
785784

786-
if (error_code == moveit::core::MoveItErrorCode::SUCCESS)
785+
if (error_code)
787786
{
788787
RCLCPP_INFO(LOGGER, "Successfully computed trajectory");
789788
trajectory = plan.trajectory;
790789
return true;
791790
}
792791
else
793792
{
794-
RCLCPP_ERROR(LOGGER, "Planning failed with error code %s", error_code.message.c_str());
793+
RCLCPP_ERROR(LOGGER, "Planning failed: %s", error_code.message.c_str());
795794
return false;
796795
}
797796
}

0 commit comments

Comments
 (0)