SMACC2
Loading...
Searching...
No Matches
cb_move_known_state.hpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 *****************************************************************************************************************/
20
21#pragma once
22
23#include <yaml-cpp/yaml.h>
24#include <ament_index_cpp/get_package_share_directory.hpp>
25#include <filesystem>
26#include <fstream>
27#include <map>
28#include <string>
29#include "cb_move_joints.hpp"
30
31namespace cl_moveit2z
32{
34{
35public:
36 CbMoveKnownState(std::string pkg, std::string config_path) : pkg_(pkg), config_path_(config_path)
37 {
38 }
39
40 virtual ~CbMoveKnownState() {}
41
47
48private:
49#define HAVE_NEW_YAMLCPP
50 std::map<std::string, double> loadJointStatesFromFile(std::string pkg, std::string filepath)
51 {
52 //auto pkgpath = ros::package::getPath(pkg);
53 std::string pkgpath = ament_index_cpp::get_package_share_directory(pkg);
54
55 std::map<std::string, double> jointStates;
56
57 if (pkgpath == "")
58 {
59 RCLCPP_ERROR_STREAM(
60 getLogger(), "[" << getName() << "] package not found for the known poses file: " << pkg
61 << std::endl
62 << " [IGNORING BEHAVIOR]");
63 return jointStates;
64 }
65
66 filepath = pkgpath + "/" + filepath;
67
68 RCLCPP_INFO_STREAM(
69 getLogger(), "[" << getName() << "] Opening file with joint known state: " << filepath);
70
71 if (std::filesystem::exists(filepath))
72 {
73 RCLCPP_INFO_STREAM(
74 getLogger(), "[" << getName() << "] known state file exists: " << filepath);
75 }
76 else
77 {
78 RCLCPP_ERROR_STREAM(
79 getLogger(), "[" << getName() << "] known state file does not exists: " << filepath);
80 }
81
82 std::ifstream ifs(filepath.c_str(), std::ifstream::in);
83 if (ifs.good() == false)
84 {
85 RCLCPP_ERROR_STREAM(
86 getLogger(),
87 "[" << getName() << "] Error opening file with joint known states: " << filepath);
88 throw std::string("joint state files not found");
89 }
90
91 try
92 {
93#ifdef HAVE_NEW_YAMLCPP
94 YAML::Node node = YAML::Load(ifs);
95#else
96 YAML::Parser parser(ifs);
97 parser.GetNextDocument(node);
98#endif
99
100#ifdef HAVE_NEW_YAMLCPP
101 const YAML::Node & wp_node_tmp = node["joint_states"];
102 const YAML::Node * wp_node = wp_node_tmp ? &wp_node_tmp : NULL;
103#else
104 const YAML::Node * wp_node = node.FindValue("waypoints");
105#endif
106
107 if (wp_node != NULL)
108 {
109 try
110 {
111 for (YAML::const_iterator it = wp_node->begin(); it != wp_node->end(); ++it)
112 {
113 std::string key = it->first.as<std::string>();
114 double value = it->second.as<double>();
115 RCLCPP_DEBUG_STREAM(getLogger(), " joint - " << key << ": " << value);
116 jointStates[key] = value;
117 }
118
119 return jointStates;
120 }
121 catch (std::exception & ex)
122 {
123 RCLCPP_ERROR(getLogger(), "trying to convert to map, failed, errormsg: %s", ex.what());
124 }
125
126 RCLCPP_INFO_STREAM(getLogger(), "Parsed " << jointStates.size() << " joint entries.");
127 }
128 else
129 {
130 RCLCPP_WARN_STREAM(getLogger(), "Couldn't find any jointStates in the provided yaml file.");
131 }
132 }
133 catch (const YAML::ParserException & ex)
134 {
135 RCLCPP_ERROR_STREAM(
136 getLogger(), "Error loading the Waypoints YAML file. Incorrect syntax: " << ex.what());
137 }
138 return jointStates;
139 }
140
141 std::string pkg_;
142 std::string config_path_;
143};
144} // namespace cl_moveit2z
virtual void onEntry() override
std::map< std::string, double > jointValueTarget_
CbMoveKnownState(std::string pkg, std::string config_path)
std::map< std::string, double > loadJointStatesFromFile(std::string pkg, std::string filepath)
virtual rclcpp::Logger getLogger() const