se2ez
cspace.cpp
Go to the documentation of this file.
1 /* Author: Zachary Kingston */
2 
3 #include <iostream>
4 
5 #include <se2ez/core.h>
6 
7 using namespace se2ez;
8 
9 int main(int argc, char **argv)
10 {
11  if (argc < 5)
12  {
13  SE2EZ_ERROR("Usage: robot_yaml jointA jointB file");
14  return -1;
15  }
16 
17  auto robot = io::loadRobot(std::string(argv[1]));
18  if (!robot)
19  return -1;
20 
21  std::string jointA = std::string(argv[2]);
22  std::string jointB = std::string(argv[3]);
23 
24  CSpaceGrid grid(robot, jointA, jointB, 500, 500);
25  grid.compute();
26  grid.getImage()->saveFile(argv[4]);
27 
28  return 0;
29 }
RobotPtr loadRobot(const std::string &filename)
Loads a robot from a YAML file.
Definition: yaml.cpp:303
void compute(bool block=true, const StatePtr &base=nullptr, const GridCallback &callback={})
Compute a PPM image of the configuration space of two joints, jointA and jointB.
Definition: cspace.cpp:231
int main(int argc, char **argv)
Definition: cspace.cpp:9
Main namespace.
Definition: collision.h:11
#define SE2EZ_ERROR(fmt,...)
Definition: log.h:39
std::shared_ptr< ompl::PPM > getImage() const
Get the current computed PPM image.
Definition: cspace.cpp:381
Helper class to compute and draw C-Space images from arbitrary robots.
Definition: cspace.h:34