SMACC2
|
#include <cb_move_cartesian_relative.hpp>
Public Member Functions | |
CbMoveCartesianRelative () | |
CbMoveCartesianRelative (geometry_msgs::msg::Vector3 offset) | |
virtual void | onEntry () override |
virtual void | onExit () override |
void | moveRelativeCartesian (moveit::planning_interface::MoveGroupInterface *movegroupClient, geometry_msgs::msg::Vector3 &offset) |
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) |
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) |
Public Attributes | |
geometry_msgs::msg::Vector3 | offset_ |
std::optional< double > | scalingFactor_ |
std::optional< std::string > | group_ |
ClMoveGroup * | moveGroupSmaccClient_ |
Additional Inherited Members | |
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 () |
virtual void | onEntry () |
virtual void | onExit () |
template<typename EventType > | |
void | postEvent (const EventType &ev) |
template<typename EventType > | |
void | postEvent () |
ISmaccState * | getCurrentState () |
virtual void | dispose () |
virtual rclcpp::Node::SharedPtr | getNode () |
virtual rclcpp::Logger | getLogger () |
Definition at line 30 of file cb_move_cartesian_relative.hpp.
cl_move_group_interface::CbMoveCartesianRelative::CbMoveCartesianRelative | ( | ) |
Definition at line 27 of file cb_move_cartesian_relative.cpp.
cl_move_group_interface::CbMoveCartesianRelative::CbMoveCartesianRelative | ( | geometry_msgs::msg::Vector3 | offset | ) |
Definition at line 29 of file cb_move_cartesian_relative.cpp.
void cl_move_group_interface::CbMoveCartesianRelative::moveRelativeCartesian | ( | moveit::planning_interface::MoveGroupInterface * | movegroupClient, |
geometry_msgs::msg::Vector3 & | offset | ||
) |
Definition at line 53 of file cb_move_cartesian_relative.cpp.
References smacc2::ISmaccClientBehavior::getLogger(), moveGroupSmaccClient_, 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.
Definition at line 34 of file cb_move_cartesian_relative.cpp.
References smacc2::ISmaccClientBehavior::getNode(), group_, cl_move_group_interface::ClMoveGroup::moveGroupClientInterface, moveGroupSmaccClient_, moveRelativeCartesian(), offset_, and smacc2::ISmaccClientBehavior::requiresClient().
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 50 of file cb_move_cartesian_relative.cpp.
std::optional<std::string> cl_move_group_interface::CbMoveCartesianRelative::group_ |
Definition at line 37 of file cb_move_cartesian_relative.hpp.
Referenced by onEntry().
ClMoveGroup* cl_move_group_interface::CbMoveCartesianRelative::moveGroupSmaccClient_ |
Definition at line 52 of file cb_move_cartesian_relative.hpp.
Referenced by moveRelativeCartesian(), and onEntry().
geometry_msgs::msg::Vector3 cl_move_group_interface::CbMoveCartesianRelative::offset_ |
Definition at line 33 of file cb_move_cartesian_relative.hpp.
Referenced by onEntry().
std::optional<double> cl_move_group_interface::CbMoveCartesianRelative::scalingFactor_ |
Definition at line 35 of file cb_move_cartesian_relative.hpp.
Referenced by moveRelativeCartesian().