SMACC
Loading...
Searching...
No Matches
cb_move_known_state.cpp
Go to the documentation of this file.
1/*****************************************************************************************************************
2 * ReelRobotix Inc. - Software License Agreement Copyright (c) 2018-2020
3 * Authors: Pablo Inigo Blasco, Brett Aldrich
4 *
5 ******************************************************************************************************************/
6
8#include <yaml-cpp/yaml.h>
9#include <fstream>
10#include <ros/package.h>
11#include <experimental/filesystem>
12
14{
15CbMoveKnownState::CbMoveKnownState(std::string pkg, std::string config_path)
16 : CbMoveJoints(loadJointStatesFromFile(pkg, config_path))
17{
18}
19
21{
22
23}
24
25
26#define HAVE_NEW_YAMLCPP
27std::map<std::string, double> CbMoveKnownState::loadJointStatesFromFile(std::string pkg, std::string filepath)
28{
29 auto pkgpath = ros::package::getPath(pkg);
30 std::map<std::string, double> jointStates;
31
32 if(pkgpath == "")
33 {
34 ROS_ERROR_STREAM("[CbMoveKnownState] package not found for the known poses file: " << pkg << std::endl << " [IGNORING BEHAVIOR]");
35 return jointStates;
36 }
37
38 filepath = pkgpath +"/" + filepath;
39
40
41 ROS_INFO("[CbMoveKnownState] Opening file with joint known state: %s", filepath.c_str());
42
43
44 if(std::experimental::filesystem::exists(filepath))
45 {
46 ROS_INFO_STREAM("[CbMoveKnownState] known state file exists: " << filepath);
47 }
48 else
49 {
50 ROS_ERROR_STREAM("[CbMoveKnownState] known state file does not exists: " << filepath);
51 }
52
53 std::ifstream ifs(filepath.c_str(), std::ifstream::in);
54 if (ifs.good() == false)
55 {
56 ROS_ERROR("[CbMoveKnownState] Error opening file with joint known states: %s", filepath.c_str());
57 throw std::string("joint state files not found");
58 }
59
60 try
61 {
62#ifdef HAVE_NEW_YAMLCPP
63 YAML::Node node = YAML::Load(ifs);
64#else
65 YAML::Parser parser(ifs);
66 parser.GetNextDocument(node);
67#endif
68
69#ifdef HAVE_NEW_YAMLCPP
70 const YAML::Node &wp_node_tmp = node["joint_states"];
71 const YAML::Node *wp_node = wp_node_tmp ? &wp_node_tmp : NULL;
72#else
73 const YAML::Node *wp_node = node.FindValue("waypoints");
74#endif
75
76 if (wp_node != NULL)
77 {
78 try
79 {
80 for(YAML::const_iterator it=wp_node->begin();it != wp_node->end();++it)
81 {
82 std::string key = it->first.as<std::string>();
83 double value = it->second.as<double>();
84 ROS_DEBUG_STREAM(" joint - " << key << ": " << value);
85 jointStates[key] = value;
86 }
87
88 return jointStates;
89 }
90 catch(std::exception& ex)
91 {
92 ROS_ERROR("trying to convert to map, failed, errormsg: %s", ex.what());
93 }
94
95 ROS_INFO_STREAM("Parsed " << jointStates.size() << " joint entries.");
96 }
97 else
98 {
99 ROS_WARN_STREAM("Couldn't find any jointStates in the provided yaml file.");
100 }
101 }
102 catch (const YAML::ParserException &ex)
103 {
104 ROS_ERROR_STREAM("Error loading the Waypoints YAML file. Incorrect syntax: " << ex.what());
105 }
106 return jointStates;
107}
108} // namespace cl_move_group_interface
static std::map< std::string, double > loadJointStatesFromFile(std::string pkg, std::string filepath)
CbMoveKnownState(std::string pkg, std::string config_path)