SMACC
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
cl_move_group_interface::CbMoveJoints Class Reference

#include <cb_move_joints.h>

Inheritance diagram for cl_move_group_interface::CbMoveJoints:
Inheritance graph
Collaboration diagram for cl_move_group_interface::CbMoveJoints:
Collaboration graph

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 smacc::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 smacc::ISmaccClientBehavior
 ISmaccClientBehavior ()
 
virtual ~ISmaccClientBehavior ()
 
ISmaccStateMachinegetStateMachine ()
 
std::string getName () const
 
template<typename SmaccClientType >
void requiresClient (SmaccClientType *&storage)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage)
 
ros::NodeHandle getNode ()
 

Public Attributes

boost::optional< double > scalingFactor_
 
std::map< std::string, double > jointValueTarget_
 
boost::optional< std::string > group_
 

Protected Member Functions

void moveJoints (moveit::planning_interface::MoveGroupInterface &moveGroupInterface)
 
- Protected Member Functions inherited from smacc::SmaccAsyncClientBehavior
virtual void executeOnEntry () override
 
virtual void executeOnExit () override
 
void postSuccessEvent ()
 
void postFailureEvent ()
 
virtual void dispose () override
 
- Protected Member Functions inherited from smacc::ISmaccClientBehavior
virtual void runtimeConfigure ()
 
virtual void onEntry ()
 
virtual void onExit ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
ISmaccStategetCurrentState ()
 
virtual void executeOnEntry ()
 
virtual void executeOnExit ()
 
virtual void dispose ()
 

Protected Attributes

ClMoveGroupmovegroupClient_
 

Detailed Description

Definition at line 16 of file cb_move_joints.h.

Constructor & Destructor Documentation

◆ CbMoveJoints() [1/2]

cl_move_group_interface::CbMoveJoints::CbMoveJoints ( )

Definition at line 16 of file cb_move_joints.cpp.

17 {
18 }

◆ CbMoveJoints() [2/2]

cl_move_group_interface::CbMoveJoints::CbMoveJoints ( const std::map< std::string, double > &  jointValueTarget)

Definition at line 12 of file cb_move_joints.cpp.

12 : jointValueTarget_(jointValueTarget)
13 {
14 }
std::map< std::string, double > jointValueTarget_

Member Function Documentation

◆ moveJoints()

void cl_move_group_interface::CbMoveJoints::moveJoints ( moveit::planning_interface::MoveGroupInterface &  moveGroupInterface)
protected

Definition at line 53 of file cb_move_joints.cpp.

54 {
56 moveGroupInterface.setMaxVelocityScalingFactor(*scalingFactor_);
57
58 bool success;
59 moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;
60
61 if (jointValueTarget_.size() == 0)
62 {
63 ROS_WARN("[CbMoveJoints] No joint was value specified. Skipping planning call.");
64 success = false;
65 }
66 else
67 {
68 moveGroupInterface.setJointValueTarget(jointValueTarget_);
69 //moveGroupInterface.setGoalJointTolerance(0.01);
70 success = (moveGroupInterface.plan(computedMotionPlan) == moveit::core::MoveItErrorCode::SUCCESS);
71 ROS_INFO_NAMED("CbMoveJoints", "Success Visualizing plan 1 (pose goal) %s", success ? "" : "FAILED");
72 }
73
74 if (success)
75 {
76 auto executionResult = moveGroupInterface.execute(computedMotionPlan);
77
78 auto statestr = currentJointStatesToString(moveGroupInterface, jointValueTarget_);
79
80 if (executionResult == moveit_msgs::MoveItErrorCodes::SUCCESS)
81 {
82 ROS_INFO_STREAM("[" << this->getName() << "] motion execution succeeded. Throwing success event. " << std::endl
83 << statestr);
85 this->postSuccessEvent();
86 }
87 else
88 {
89 ROS_WARN_STREAM("[" << this->getName() << "] motion execution failed. Throwing fail event." << std::endl
90 << statestr);
92 this->postFailureEvent();
93 }
94 }
95 else
96 {
97 auto statestr = currentJointStatesToString(moveGroupInterface, jointValueTarget_);
98 ROS_WARN_STREAM("[" << this->getName() << "] motion execution failed. Throwing fail event." << std::endl << statestr);
100 this->postFailureEvent();
101 }
102 }
boost::optional< double > scalingFactor_
std::string currentJointStatesToString(moveit::planning_interface::MoveGroupInterface &moveGroupInterface, std::map< std::string, double > &targetJoints)

References cl_move_group_interface::currentJointStatesToString(), smacc::ISmaccClientBehavior::getName(), jointValueTarget_, movegroupClient_, cl_move_group_interface::ClMoveGroup::postEventMotionExecutionFailed(), cl_move_group_interface::ClMoveGroup::postEventMotionExecutionSucceded(), smacc::SmaccAsyncClientBehavior::postFailureEvent(), smacc::SmaccAsyncClientBehavior::postSuccessEvent(), and scalingFactor_.

Referenced by onEntry().

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

◆ onEntry()

void cl_move_group_interface::CbMoveJoints::onEntry ( )
overridevirtual

Reimplemented from smacc::ISmaccClientBehavior.

Reimplemented in cl_move_group_interface::CbMoveLastTrajectoryInitialState.

Definition at line 20 of file cb_move_joints.cpp.

21 {
23
24 if (this->group_)
25 {
26 moveit::planning_interface::MoveGroupInterface move_group(*(this->group_));
27 this->moveJoints(move_group);
28 }
29 else
30 {
32 }
33 }
void moveJoints(moveit::planning_interface::MoveGroupInterface &moveGroupInterface)
boost::optional< std::string > group_
moveit::planning_interface::MoveGroupInterface moveGroupClientInterface
Definition: cl_movegroup.h:74
void requiresClient(SmaccClientType *&storage)

References group_, movegroupClient_, cl_move_group_interface::ClMoveGroup::moveGroupClientInterface, moveJoints(), and smacc::ISmaccClientBehavior::requiresClient().

Referenced by cl_move_group_interface::CbMoveLastTrajectoryInitialState::onEntry().

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

◆ onExit()

void cl_move_group_interface::CbMoveJoints::onExit ( )
overridevirtual

Reimplemented from smacc::ISmaccClientBehavior.

Definition at line 104 of file cb_move_joints.cpp.

105 {
106 }

Member Data Documentation

◆ group_

boost::optional<std::string> cl_move_group_interface::CbMoveJoints::group_

Definition at line 21 of file cb_move_joints.h.

Referenced by onEntry().

◆ jointValueTarget_

std::map<std::string, double> cl_move_group_interface::CbMoveJoints::jointValueTarget_

◆ movegroupClient_

ClMoveGroup* cl_move_group_interface::CbMoveJoints::movegroupClient_
protected

Definition at line 30 of file cb_move_joints.h.

Referenced by moveJoints(), and onEntry().

◆ scalingFactor_

boost::optional<double> cl_move_group_interface::CbMoveJoints::scalingFactor_

Definition at line 19 of file cb_move_joints.h.

Referenced by moveJoints().


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