SMACC2
|
#include <cb_move_joints.hpp>
Public Member Functions | |
CbMoveJoints () | |
CbMoveJoints (const std::map< std::string, double > &jointValueTarget) | |
virtual void | onEntry () override |
virtual void | onExit () override |
Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior | |
template<typename TOrthogonal , typename TSourceObject > | |
void | onOrthogonalAllocation () |
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 () |
ISmaccStateMachine * | getStateMachine () |
std::string | getName () const |
template<typename SmaccClientType > | |
void | requiresClient (SmaccClientType *&storage) |
template<typename SmaccComponentType > | |
void | requiresComponent (SmaccComponentType *&storage, bool throwExceptionIfNotExist=false) |
virtual void | onEntry () |
virtual void | onExit () |
virtual void | executeOnEntry () |
virtual void | executeOnExit () |
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 () |
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 void | dispose () |
virtual rclcpp::Node::SharedPtr | getNode () const |
virtual rclcpp::Logger | getLogger () const |
Protected Attributes | |
ClMoveGroup * | movegroupClient_ |
Definition at line 31 of file cb_move_joints.hpp.
cl_move_group_interface::CbMoveJoints::CbMoveJoints | ( | ) |
Definition at line 31 of file cb_move_joints.cpp.
cl_move_group_interface::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_move_group_interface::currentJointStatesToString(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), jointValueTarget_, movegroupClient_, cl_move_group_interface::ClMoveGroup::postEventMotionExecutionFailed(), cl_move_group_interface::ClMoveGroup::postEventMotionExecutionSucceded(), smacc2::SmaccAsyncClientBehavior::postFailureEvent(), smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), and scalingFactor_.
Referenced by onEntry().
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Reimplemented in cl_move_group_interface::CbMoveKnownState, and cl_move_group_interface::CbMoveLastTrajectoryInitialState.
Definition at line 33 of file cb_move_joints.cpp.
References smacc2::ISmaccClientBehavior::getNode(), group_, movegroupClient_, cl_move_group_interface::ClMoveGroup::moveGroupClientInterface, moveJoints(), and smacc2::ISmaccClientBehavior::requiresClient().
Referenced by cl_move_group_interface::CbMoveKnownState::onEntry(), and cl_move_group_interface::CbMoveLastTrajectoryInitialState::onEntry().
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 132 of file cb_move_joints.cpp.
std::optional<std::string> cl_move_group_interface::CbMoveJoints::group_ |
Definition at line 36 of file cb_move_joints.hpp.
Referenced by onEntry().
std::map<std::string, double> cl_move_group_interface::CbMoveJoints::jointValueTarget_ |
Definition at line 35 of file cb_move_joints.hpp.
Referenced by moveJoints(), cl_move_group_interface::CbMoveKnownState::onEntry(), and cl_move_group_interface::CbMoveLastTrajectoryInitialState::onEntry().
|
protected |
Definition at line 45 of file cb_move_joints.hpp.
Referenced by moveJoints(), and onEntry().
std::optional<double> cl_move_group_interface::CbMoveJoints::scalingFactor_ |
Definition at line 34 of file cb_move_joints.hpp.
Referenced by moveJoints().