Go to the source code of this file.
|
int | main (int argc, char **argv) |
|
◆ main()
int main |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
Definition at line 22 of file fetch_tabletop_goalstate.cpp.
28 auto fetch = std::make_shared<FetchRobot>();
29 fetch->initialize(
false);
33 scene->fromYAMLFile(
"package://robowflex_tesseract/scenes/table/scene.yaml");
36 scene->attachObject(*
fetch->getScratchState(),
"Can1");
39 auto planner = std::make_shared<TrajOptPlanner>(
fetch,
GROUP);
40 planner->initialize(
"torso_lift_link",
"gripper_link");
43 planner->options.num_waypoints = 8;
44 planner->setInitType(trajopt::InitInfo::Type::JOINT_INTERPOLATED);
48 const auto &request = std::make_shared<MotionRequestBuilder>(
fetch);
49 request->fromYAMLFile(
"package://robowflex_tesseract/scenes/table/request.yaml");
52 const auto &rviz = std::make_shared<IO::RVIZHelper>(
fetch);
53 rviz->updateScene(
scene);
54 rviz->visualizeState(request->getStartConfiguration());
61 const auto &res = planner->plan(
scene, request->getRequest());
62 if (res.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
63 rviz->updateTrajectory(res);
65 rviz->visualizeState(request->getGoalConfiguration());
RAII-pattern for starting up ROS.
static const std::string GROUP
#define RBX_INFO(fmt,...)
Output a info logging message.
Functions for loading and animating scenes in Blender.
◆ GROUP