31 auto fetch = std::make_shared<FetchRobot>();
40 RBX_INFO(
"RViz Initialized! Press enter to continue (after your RViz is setup)...");
45 scene->fromYAMLFile(
"package://robowflex_library/yaml/test_fetch.yml");
48 rviz.updateScene(
scene);
51 auto planner = std::make_shared<OMPL::FetchOMPLPipelinePlanner>(
fetch,
"default");
52 planner->initialize();
56 fetch->setGroupState(
GROUP, {0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0});
57 request.setStartConfiguration(
fetch->getScratchState());
61 pose.translate(Eigen::Vector3d{0.4, 0.6, 0.92});
63 Eigen::Quaterniond orn{0.5, -0.5, 0.5, 0.5};
67 request.setGoalRegion(
"wrist_roll_link",
"base_link",
73 rviz.addGoalMarker(
"goal", request);
76 RBX_INFO(
"Scene and Goal displayed! Press enter to plan...");
81 if (res.
error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
85 rviz.updateTrajectory(res);
93 RBX_INFO(
"Press enter to remove goal and scene.");
97 rviz.removeMarker(
"goal");
RVIZ visualization helper. See Live Visualization with RViz for more information.
Helper class to broadcast transform information on TF and joint states.
A helper class to build motion planning requests for a robowflex::Planner.
RAII-pattern for starting up ROS.
static const std::string GROUP
#define RBX_INFO(fmt,...)
Output a info logging message.
std::shared_ptr< dart::dynamics::SphereShape > makeSphere(double radius)
Create a sphere.
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_
robot_trajectory::RobotTrajectoryPtr trajectory_
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")