SMACC2
Loading...
Searching...
No Matches
cl_moveit2z::CbMoveKnownState Class Reference

#include <cb_move_known_state.hpp>

Inheritance diagram for cl_moveit2z::CbMoveKnownState:
Inheritance graph
Collaboration diagram for cl_moveit2z::CbMoveKnownState:
Collaboration graph

Public Member Functions

 CbMoveKnownState (std::string pkg, std::string config_path)
 
virtual ~CbMoveKnownState ()
 
void onEntry () override
 
 CbMoveKnownState (std::string pkg, std::string config_path)
 
virtual ~CbMoveKnownState ()
 
void onEntry () override
 
- Public Member Functions inherited from cl_moveit2z::CbMoveJoints
 CbMoveJoints ()
 
 CbMoveJoints (const std::map< std::string, double > &jointValueTarget)
 
virtual void onExit () override
 
 CbMoveJoints ()
 
 CbMoveJoints (const std::map< std::string, double > &jointValueTarget)
 
virtual void onExit () override
 
- Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
virtual ~SmaccAsyncClientBehavior ()
 
template<typename TCallback , typename T >
boost::signals2::connection onSuccess (TCallback callback, T *object)
 
template<typename TCallback , typename T >
boost::signals2::connection onFinished (TCallback callback, T *object)
 
template<typename TCallback , typename T >
boost::signals2::connection onFailure (TCallback callback, T *object)
 
void requestForceFinish ()
 
void executeOnEntry () override
 
void executeOnExit () override
 
void waitOnEntryThread (bool requestFinish)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onSuccess (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFinished (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFailure (TCallbackMethod callback, T *object)
 
- Public Member Functions inherited from smacc2::ISmaccClientBehavior
 ISmaccClientBehavior ()
 
virtual ~ISmaccClientBehavior ()
 
ISmaccStateMachinegetStateMachine ()
 
std::string getName () const
 
template<typename SmaccClientType >
void requiresClient (SmaccClientType *&storage)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage, bool throwExceptionIfNotExist)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 

Private Member Functions

std::map< std::string, double > loadJointStatesFromFile (std::string pkg, std::string filepath)
 
std::map< std::string, double > loadJointStatesFromFile (std::string pkg, std::string filepath)
 

Private Attributes

std::string pkg_
 
std::string config_path_
 

Additional Inherited Members

- Public Attributes inherited from cl_moveit2z::CbMoveJoints
std::optional< double > scalingFactor_
 
std::map< std::string, double > jointValueTarget_
 
std::optional< std::string > group_
 
- Protected Member Functions inherited from cl_moveit2z::CbMoveJoints
void moveJoints (moveit::planning_interface::MoveGroupInterface &moveGroupInterface)
 
void moveJoints (moveit::planning_interface::MoveGroupInterface &moveGroupInterface)
 
- Protected Member Functions inherited from smacc2::SmaccAsyncClientBehavior
void postSuccessEvent ()
 
void postFailureEvent ()
 
virtual void dispose () override
 
bool isShutdownRequested ()
 onEntry is executed in a new thread. However the current state cannot be left until the onEntry thread finishes. This flag can be checked from the onEntry thread to force finishing the thread.
 
- Protected Member Functions inherited from smacc2::ISmaccClientBehavior
virtual void runtimeConfigure ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
ISmaccStategetCurrentState ()
 
virtual rclcpp::Node::SharedPtr getNode () const
 
virtual rclcpp::Logger getLogger () const
 
- Static Protected Member Functions inherited from cl_moveit2z::CbMoveJoints
static std::string currentJointStatesToString (moveit::planning_interface::MoveGroupInterface &moveGroupInterface, std::map< std::string, double > &targetJoints)
 
- Protected Attributes inherited from cl_moveit2z::CbMoveJoints
ClMoveit2zmovegroupClient_
 

Detailed Description

Definition at line 29 of file cb_move_known_state.hpp.

Constructor & Destructor Documentation

◆ CbMoveKnownState() [1/2]

cl_moveit2z::CbMoveKnownState::CbMoveKnownState ( std::string pkg,
std::string config_path )
inline

Definition at line 36 of file cb_move_known_state.hpp.

36 : pkg_(pkg), config_path_(config_path)
37 {
38 }

◆ ~CbMoveKnownState() [1/2]

cl_moveit2z::CbMoveKnownState::~CbMoveKnownState ( )
inlinevirtual

Definition at line 40 of file cb_move_known_state.hpp.

40{}

◆ CbMoveKnownState() [2/2]

cl_moveit2z::CbMoveKnownState::CbMoveKnownState ( std::string pkg,
std::string config_path )

◆ ~CbMoveKnownState() [2/2]

virtual cl_moveit2z::CbMoveKnownState::~CbMoveKnownState ( )
virtual

Member Function Documentation

◆ loadJointStatesFromFile() [1/2]

std::map< std::string, double > cl_moveit2z::CbMoveKnownState::loadJointStatesFromFile ( std::string pkg,
std::string filepath )
inlineprivate

Definition at line 50 of file cb_move_known_state.hpp.

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 }
virtual rclcpp::Logger getLogger() const

References smacc2::ISmaccClientBehavior::getLogger(), and smacc2::ISmaccClientBehavior::getName().

Referenced by onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loadJointStatesFromFile() [2/2]

std::map< std::string, double > cl_moveit2z::CbMoveKnownState::loadJointStatesFromFile ( std::string pkg,
std::string filepath )
private

◆ onEntry() [1/2]

void cl_moveit2z::CbMoveKnownState::onEntry ( )
inlineoverridevirtual

Reimplemented from cl_moveit2z::CbMoveJoints.

Definition at line 42 of file cb_move_known_state.hpp.

43 {
46 }
std::map< std::string, double > jointValueTarget_
virtual void onEntry() override
std::map< std::string, double > loadJointStatesFromFile(std::string pkg, std::string filepath)

References config_path_, cl_moveit2z::CbMoveJoints::jointValueTarget_, loadJointStatesFromFile(), cl_moveit2z::CbMoveJoints::onEntry(), and pkg_.

Here is the call graph for this function:

◆ onEntry() [2/2]

void cl_moveit2z::CbMoveKnownState::onEntry ( )
overridevirtual

Reimplemented from cl_moveit2z::CbMoveJoints.

Member Data Documentation

◆ config_path_

std::string cl_moveit2z::CbMoveKnownState::config_path_
private

Definition at line 142 of file cb_move_known_state.hpp.

Referenced by onEntry().

◆ pkg_

std::string cl_moveit2z::CbMoveKnownState::pkg_
private

Definition at line 141 of file cb_move_known_state.hpp.

Referenced by onEntry().


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