Robowflex  v0.1
Making MoveIt Easy
robowflex::movegroup::MoveGroupHelper::Action Struct Reference

A container struct for all relevant information about a motion planning request to move group. More...

#include <services.h>

Public Member Functions

bool fromYAMLFile (const std::string &filename)
 Load a recorded action from a YAML file. More...
 
bool toYAMLFile (const std::string &filename)
 Save a recorded action to a YAML file. More...
 

Public Attributes

std::string id
 Goal ID. More...
 
ScenePtr scene
 Scene used for planning. More...
 
moveit_msgs::MotionPlanRequest request
 Motion planning request. More...
 
bool success
 Planning success. More...
 
double time
 Planning time. More...
 
moveit_msgs::RobotTrajectory trajectory
 Planned trajectory on success. More...
 

Detailed Description

A container struct for all relevant information about a motion planning request to move group.

Definition at line 32 of file services.h.

Member Function Documentation

◆ fromYAMLFile()

bool MoveGroupHelper::Action::fromYAMLFile ( const std::string filename)

Load a recorded action from a YAML file.

Parameters
[in]filenameFilename to load from.
Returns
True on success, false on failure.

MoveGroupHelper::Action

Definition at line 24 of file services.cpp.

25 {
27  const auto file = IO::loadFileToYAML(filename);
28 
29  if (!file.first)
30  {
31  RBX_WARN("Failed to open file %s!", filename);
32  return false;
33  }
34 
35  id = file.second["id"].as<std::string>();
36  request = file.second["request"].as<moveit_msgs::MotionPlanRequest>();
37  success = file.second["success"].as<bool>();
38  time = file.second["time"].as<double>();
39 
40  if (IO::isNode(file.second["trajectory"]))
41  trajectory = file.second["trajectory"].as<moveit_msgs::RobotTrajectory>();
42 
43  return true;
44 }
#define RBX_WARN(fmt,...)
Output a warning logging message.
Definition: log.h:110
bool isNode(const YAML::Node &node)
Checks if a key exists within a YAML node.
Definition: yaml.cpp:1847
std::pair< bool, YAML::Node > loadFileToYAML(const std::string &path)
Loads a file to a YAML node.
A container struct for all relevant information about a motion planning request to move group.
Definition: services.h:33
moveit_msgs::MotionPlanRequest request
Motion planning request.
Definition: services.h:36
moveit_msgs::RobotTrajectory trajectory
Planned trajectory on success.
Definition: services.h:39

◆ toYAMLFile()

bool MoveGroupHelper::Action::toYAMLFile ( const std::string filename)

Save a recorded action to a YAML file.

Parameters
[in]filenameFilename to save as.
Returns
True on success, false on failure.

Definition at line 46 of file services.cpp.

47 {
48  YAML::Node node;
49 
50  node["id"] = id;
51 
52  moveit_msgs::PlanningScene scene_msg;
53  scene->getSceneConst()->getPlanningSceneMsg(scene_msg);
54  node["scene"] = IO::toNode(scene_msg);
55 
56  node["request"] = IO::toNode(request);
57  node["success"] = success ? "true" : "false";
58  node["time"] = time;
59  node["trajectory"] = IO::toNode(trajectory);
60 
61  return IO::YAMLToFile(node, filename);
62 }
bool YAMLToFile(const YAML::Node &node, const std::string &file)
Write the contents of a YAML node out to a potentially new file.
YAML::Node toNode(const geometry_msgs::Pose &msg)
Converts a pose message to YAML.
Definition: yaml.cpp:1874
Functions for loading and animating scenes in Blender.

Member Data Documentation

◆ id

std::string robowflex::movegroup::MoveGroupHelper::Action::id

Goal ID.

Definition at line 34 of file services.h.

◆ request

moveit_msgs::MotionPlanRequest robowflex::movegroup::MoveGroupHelper::Action::request

Motion planning request.

Definition at line 36 of file services.h.

◆ scene

ScenePtr robowflex::movegroup::MoveGroupHelper::Action::scene

Scene used for planning.

Definition at line 35 of file services.h.

◆ success

bool robowflex::movegroup::MoveGroupHelper::Action::success

Planning success.

Definition at line 37 of file services.h.

◆ time

double robowflex::movegroup::MoveGroupHelper::Action::time

Planning time.

Definition at line 38 of file services.h.

◆ trajectory

moveit_msgs::RobotTrajectory robowflex::movegroup::MoveGroupHelper::Action::trajectory

Planned trajectory on success.

Definition at line 39 of file services.h.


The documentation for this struct was generated from the following files: