SMACC2
|
#include <cb_move_joints.hpp>
Public Attributes | |
std::optional< double > | scalingFactor_ |
std::map< std::string, double > | jointValueTarget_ |
std::optional< std::string > | group_ |
Protected Member Functions | |
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 () |
ISmaccState * | getCurrentState () |
virtual rclcpp::Node::SharedPtr | getNode () const |
virtual rclcpp::Logger | getLogger () const |
Protected Attributes | |
ClMoveit2z * | movegroupClient_ |
Definition at line 31 of file cb_move_joints.hpp.
cl_moveit2z::CbMoveJoints::CbMoveJoints | ( | ) |
Definition at line 31 of file cb_move_joints.cpp.
cl_moveit2z::CbMoveJoints::CbMoveJoints | ( | const std::map< std::string, double > & | jointValueTarget | ) |
Definition at line 26 of file cb_move_joints.cpp.
|
protected |
Definition at line 72 of file cb_move_joints.cpp.
References cl_moveit2z::currentJointStatesToString(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), jointValueTarget_, movegroupClient_, cl_moveit2z::ClMoveit2z::postEventMotionExecutionFailed(), cl_moveit2z::ClMoveit2z::postEventMotionExecutionSucceded(), smacc2::SmaccAsyncClientBehavior::postFailureEvent(), smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), and scalingFactor_.
Referenced by onEntry().
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Reimplemented in cl_moveit2z::CbMoveKnownState, and cl_moveit2z::CbMoveLastTrajectoryInitialState.
Definition at line 33 of file cb_move_joints.cpp.
References smacc2::ISmaccClientBehavior::getNode(), group_, movegroupClient_, cl_moveit2z::ClMoveit2z::moveGroupClientInterface, moveJoints(), and smacc2::ISmaccClientBehavior::requiresClient().
Referenced by cl_moveit2z::CbMoveKnownState::onEntry(), and cl_moveit2z::CbMoveLastTrajectoryInitialState::onEntry().
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 139 of file cb_move_joints.cpp.
std::optional<std::string> cl_moveit2z::CbMoveJoints::group_ |
Definition at line 36 of file cb_move_joints.hpp.
Referenced by onEntry().
std::map<std::string, double> cl_moveit2z::CbMoveJoints::jointValueTarget_ |
Definition at line 35 of file cb_move_joints.hpp.
Referenced by moveJoints(), cl_moveit2z::CbMoveKnownState::onEntry(), and cl_moveit2z::CbMoveLastTrajectoryInitialState::onEntry().
|
protected |
Definition at line 45 of file cb_move_joints.hpp.
Referenced by moveJoints(), and onEntry().
std::optional<double> cl_moveit2z::CbMoveJoints::scalingFactor_ |
Definition at line 34 of file cb_move_joints.hpp.
Referenced by moveJoints().