Robowflex  v0.1
Making MoveIt Easy
fetch_cartesian.cpp File Reference

Go to the source code of this file.

Functions

int main (int argc, char **argv)
 

Variables

static const std::string GROUP = "arm"
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 20 of file fetch_cartesian.cpp.

21 {
22  // Startup ROS
23  ROS ros(argc, argv);
24 
25  // Create the default Fetch robot.
26  auto fetch = std::make_shared<FetchRobot>();
27  fetch->initialize();
28  fetch->setGroupState(GROUP, {0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007}); // Unfurl
29 
30  // Create an RViz visualization helper. Publishes all topics and parameter under `/robowflex` by default.
31  IO::RVIZHelper rviz(fetch);
32 
33  RBX_INFO("RViz Initialized! Press enter to continue (after your RViz is setup)...");
34  std::cin.get();
35 
36  auto scene = std::make_shared<Scene>(fetch);
37 
38  // Create a Cartesian planner for the FETCH.
39  auto cartesian_planner = std::make_shared<SimpleCartesianPlanner>(fetch, "cartesian");
40 
41  EigenSTL::vector_Vector3d directions = {
42  {0.3, 0.0, 0.0}, // Extend
43  {0.0, -0.1, 0.0}, {0.0, 0.2, 0.0}, {0.0, -0.1, 0.0}, // Wiggle up & down
44  {-0.3, 0.0, 0.0}, // Retract
45  };
46 
47  for (const auto &direction : directions)
48  {
49  RBX_INFO("Moving end-effector in direction [%1%, %2%, %3%]", //
50  direction[0], direction[1], direction[2]);
51 
52  // Visualize the scene.
53  scene->getCurrentState() = *fetch->getScratchState();
54  rviz.updateScene(scene);
55 
56  // Create the IK Query, and then set the scene for collision checking.
57  // Uses directional offset IKQuery constructor.
58  Robot::IKQuery query(GROUP, "wrist_roll_link", *fetch->getScratchState(), direction);
59  query.scene = scene;
60 
61  // Plan for a straight interpolation of the end-effector to the query.
62  auto response = cartesian_planner->plan(*fetch->getScratchState(), query);
63  if (response.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
64  {
65  RBX_ERROR("Planning failed!");
66  return 1;
67  }
68 
69  // Publish the trajectory to a topic to display in RViz
70  Trajectory trajectory(response.trajectory_);
71  rviz.updateTrajectory(trajectory);
72 
73  // Set the scratch state to the end of the computed trajectory.
74  fetch->setState(trajectory.getFinalPositions());
75 
76  RBX_INFO("Press enter to continue to next direction.");
77  std::cin.get();
78  }
79 
80  // Visualize the final pose.
81  scene->getCurrentState() = *fetch->getScratchState();
82  rviz.updateScene(scene);
83 
84  RBX_INFO("Press enter to exit.");
85  std::cin.get();
86 
87  return 0;
88 }
RVIZ visualization helper. See Live Visualization with RViz for more information.
Definition: visualization.h:38
RAII-pattern for starting up ROS.
Definition: util.h:52
The Trajectory class is a wrapper around MoveIt!'s robot_trajectory::RobotTrajectory,...
Definition: trajectory.h:43
static const std::string GROUP
#define RBX_ERROR(fmt,...)
Output a error logging message.
Definition: log.h:102
#define RBX_INFO(fmt,...)
Output a info logging message.
Definition: log.h:118
Functions for loading and animating scenes in Blender.
Robot IK Query options. IK queries in Robowflex consist of: a) A position specified by some geometric...
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")

Variable Documentation

◆ GROUP

const std::string GROUP = "arm"
static

Definition at line 18 of file fetch_cartesian.cpp.