15 int main(
int argc,
char **argv)
21 auto ur5 = std::make_shared<UR5Robot>();
25 auto scene = std::make_shared<Scene>(ur5);
28 auto planner = std::make_shared<OMPL::OMPLInterfacePlanner>(ur5);
29 planner->initialize(
"package://ur5_robotiq85_moveit_config/config/ompl_planning.yaml");
36 pose.translate(Eigen::Vector3d{-0.268, -0.826, 1.313});
37 Eigen::Quaterniond orn{0, 0, 1, 0};
42 orn, {0.01, 0.01, 0.01}
47 if (res.
error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
@ SPHERE
Solid primitive sphere. Uses one dimension (radius).
A helper class to build motion planning requests for a robowflex::Planner.
void setStartConfiguration(const std::vector< double > &joints)
Set the start configuration from a vector joints. All joints are assumed to be specified and in the d...
planning_interface::MotionPlanRequest & getRequest()
Get a reference to the currently built motion planning request.
void setGoalRegion(const std::string &ee_name, const std::string &base_name, const RobotPose &pose, const GeometryConstPtr &geometry, const Eigen::Quaterniond &orientation, const Eigen::Vector3d &tolerances)
Set a goal region for an end-effector ee_name. Sets the position constraint from geometry at a pose p...
RAII-pattern for starting up ROS.
Main namespace. Contains all library classes and functions.
std::decay< decltype(std::declval< moveit::core::Transforms >().getTransform("")) >::type RobotPose
A pose (point in SE(3)) used in various functions. Defined from what MoveIt! uses.
Functions for loading and animating scenes in Blender.
moveit_msgs::MoveItErrorCodes error_code_
int main(int argc, char **argv)