robot_interface
Native robot interface for making the visual manipulation
Public Member Functions | Protected Attributes | List of all members
ArmControlBase Class Referenceabstract

Robot arm control interface. More...

#include <control_base.hpp>

Inheritance diagram for ArmControlBase:
Inheritance graph
[legend]
Collaboration diagram for ArmControlBase:
Collaboration graph
[legend]

Public Member Functions

 ArmControlBase (const std::string node_name, const rclcpp::NodeOptions &options)
 Constructor of class ArmControlBase. More...
 
virtual ~ArmControlBase ()
 Default destructor of class ArmControlBase.
 
virtual bool moveToTcpPose (double x, double y, double z, double alpha, double beta, double gamma, double vel, double acc)=0
 Move the robot end-effector to a goal pose (position and orientation) in 3D Cartesian space. More...
 
virtual bool moveToTcpPose (const Eigen::Isometry3d &pose, double vel, double acc)
 Move the robot end-effector to a goal pose (position and orientation) in 3D Cartesian space. More...
 
virtual bool open (const double distance=0)=0
 Open the robot gripper and make it ready for grasping. More...
 
virtual bool close (const double distance=0)=0
 Close the robot gripper and let it grasp an object. More...
 
virtual bool pick (double x, double y, double z, double alpha, double beta, double gamma, double vel, double acc, double vel_scale, double approach)
 Make the robot arm to pick an object from a grasp pose. More...
 
virtual bool pick (const geometry_msgs::msg::PoseStamped &pose_stamped, double vel, double acc, double vel_scale, double approach)
 Make the robot arm to pick an object from a grasp pose. More...
 
virtual bool place (double x, double y, double z, double alpha, double beta, double gamma, double vel, double acc, double vel_scale, double retract)
 Make the robot arm to place an object from a place pose. More...
 
virtual bool place (const geometry_msgs::msg::PoseStamped &pose_stamped, double vel, double acc, double vel_scale, double retract)
 Make the robot arm to place an object from a place pose. More...
 
void toTcpPose (const geometry_msgs::msg::PoseStamped &pose_stamped, TcpPose &tcp_pose)
 Convert geometry_msgs::msg::PoseStamped to TcpPose. More...
 
void toTcpPose (const Eigen::Isometry3d &pose, TcpPose &tcp_pose)
 Convert Eigen::Isometry3d to TcpPose. More...
 
virtual bool checkTcpGoalArrived (Eigen::Isometry3d &tcp_goal)
 Function to check if the end-effector arrived the goal pose. More...
 
virtual void parseArgs ()=0
 Parse arguments.
 
virtual bool startLoop ()=0
 Start control loop.
 

Protected Attributes

rclcpp::Publisher< sensor_msgs::msg::JointState >::SharedPtr joint_pub_
 Joint state publisher.
 
std::vector< std::string > joint_names_
 Joint names.
 
TcpPose tcp_pose_
 Current end-effctor pose.
 
std::mutex m_
 Mutex to guard the tcp_pose usage.
 
double time_out_
 Time duration to finish a pick or place task.
 

Detailed Description

Robot arm control interface.

Constructor & Destructor Documentation

ArmControlBase::ArmControlBase ( const std::string  node_name,
const rclcpp::NodeOptions &  options 
)
inline

Constructor of class ArmControlBase.

Parameters
node_nameThe name of the ROS2 node.
optionsROS2 node options.

Member Function Documentation

bool ArmControlBase::checkTcpGoalArrived ( Eigen::Isometry3d &  tcp_goal)
virtual

Function to check if the end-effector arrived the goal pose.

Parameters
tcp_goalGoal pose of the end-effector.
Returns
If the end-effector arrived the goal pose within a time_out_ duration, return true. Otherwise, return false.
virtual bool ArmControlBase::close ( const double  distance = 0)
pure virtual

Close the robot gripper and let it grasp an object.

Parameters
distanceHow large the fingers of the gripper close.
Returns
If the robot successfully receives the "close" command, return true. Otherwise, return false.

Implemented in URControl.

virtual bool ArmControlBase::moveToTcpPose ( double  x,
double  y,
double  z,
double  alpha,
double  beta,
double  gamma,
double  vel,
double  acc 
)
pure virtual

Move the robot end-effector to a goal pose (position and orientation) in 3D Cartesian space.

Parameters
xGoal position on X dimension.
yGoal position on Y dimension.
zGoal position on Z dimension.
alphaGoal rotation euler angle along X axis.
betaGoal rotation euler angle along Y axis.
gammaGoal rotation euler angle along Z axis.
velMax joint velocity.
accMax joint acceleration.
Returns
If the robot successfully receives the "move" command, return True. Otherwise, return false.

Implemented in URControl.

bool ArmControlBase::moveToTcpPose ( const Eigen::Isometry3d &  pose,
double  vel,
double  acc 
)
virtual

Move the robot end-effector to a goal pose (position and orientation) in 3D Cartesian space.

Parameters
poseGoal pose as a Eigen transform (Isometry3d).
velMax joint velocity.
accMax joint acceleration.
Returns
If the robot successfully receives the "move" command, return True. Otherwise, return false.
virtual bool ArmControlBase::open ( const double  distance = 0)
pure virtual

Open the robot gripper and make it ready for grasping.

Parameters
distanceHow large the fingers of the gripper open.
Returns
If the robot successfully receives the "open" command, return true. Otherwise, return false.

Implemented in URControl.

bool ArmControlBase::pick ( double  x,
double  y,
double  z,
double  alpha,
double  beta,
double  gamma,
double  vel,
double  acc,
double  vel_scale,
double  approach 
)
virtual

Make the robot arm to pick an object from a grasp pose.

This function contains a sequence of motions:

  1. Move the end-effector to a pose above the object.
  2. Open gripper.
  3. Stretch the end-effector along its Z axis to the grasp pose that gripper can grasp the object.
  4. Close gripper.
  5. Move the end-effector back to the pose above the object.
Parameters
xPosition of grasp pose on X dimension.
yPosition of grasp pose on Y dimension.
zPosition of grasp pose on Z dimension.
alphaRotation euler angle of grasp pose along X axis.
betaRotation euler angle of grasp pose along Y axis.
gammaRotation euler angle of grasp pose along Z axis.
velMax joint velocity.
accMax joint acceleration.
vel_scaleScale factor to slow down the end-effector velocity, when it stretch to or move back from the grasp pose.
approachThe stretch distance.
Returns
If the robot successfully finishes the "pick" motions, return True. Otherwise, return false.
Note
The grasp pose should have Z axis point out from the end-effector link.
bool ArmControlBase::pick ( const geometry_msgs::msg::PoseStamped &  pose_stamped,
double  vel,
double  acc,
double  vel_scale,
double  approach 
)
virtual

Make the robot arm to pick an object from a grasp pose.

This function contains a sequence of motions:

  1. Move the end-effector to a pose above the object.
  2. Open gripper.
  3. Stretch the end-effector along its Z axis to the grasp pose that gripper can grasp the object.
  4. Close gripper.
  5. Move the end-effector back to the pose above the object.
Parameters
pose_stampedPose received from the grasp planning algorithm. See also https://github.com/intel/ros2_grasp_library.
velMax joint velocity.
accMax joint acceleration.
vel_scaleScale factor to slow down the end-effector velocity, when it stretch to or move back from the grasp pose.
approachThe stretch distance.
Returns
If the robot successfully finishes the "pick" motions, return True. Otherwise, return false.
Note
The grasp pose should have Z axis point out from the end-effector link.
bool ArmControlBase::place ( double  x,
double  y,
double  z,
double  alpha,
double  beta,
double  gamma,
double  vel,
double  acc,
double  vel_scale,
double  retract 
)
virtual

Make the robot arm to place an object from a place pose.

This function contains a sequence of motions:

  1. Move the end-effector to a pre-place pose.
  2. Stretch the end-effector along its Z axis to the place pose.
  3. Open gripper.
  4. Move the end-effector back to the pre-place pose.
Parameters
xPosition of place pose on X dimension.
yPosition of place pose on Y dimension.
zPosition of place pose on Z dimension.
alphaRotation euler angle of place pose along X axis.
betaRotation euler angle of place pose along Y axis.
gammaRotation euler angle of place pose along Z axis.
velMax joint velocity.
accMax joint acceleration.
vel_scaleScale factor to slow down the end-effector velocity, when it stretch to or move back from the place pose.
retractThe retract distance from the place pose.
Returns
If the robot successfully finishes the "place" motions, return True. Otherwise, return false.
Note
The place pose should have Z axis point out from the end-effector link.
bool ArmControlBase::place ( const geometry_msgs::msg::PoseStamped &  pose_stamped,
double  vel,
double  acc,
double  vel_scale,
double  retract 
)
virtual

Make the robot arm to place an object from a place pose.

This function contains a sequence of motions:

  1. Move the end-effector to a pre-place pose.
  2. Stretch the end-effector along its Z axis to the place pose.
  3. Open gripper.
  4. Move the end-effector back to the pre-place pose.
Parameters
pose_stampedPose of the end-effector to place an object.
velMax joint velocity.
accMax joint acceleration.
vel_scaleScale factor to slow down the end-effector velocity, when it stretch to or retract back from the place pose.
retractThe retract distance from the place pose.
Returns
If the robot successfully finishes the "place" motions, return True. Otherwise, return false.
Note
The place pose should have Z axis point out from the end-effector link.
void ArmControlBase::toTcpPose ( const geometry_msgs::msg::PoseStamped &  pose_stamped,
TcpPose tcp_pose 
)

Convert geometry_msgs::msg::PoseStamped to TcpPose.

Parameters
pose_stampedPose of the end-effector.
tcp_poseVariable to store the converted result.
void ArmControlBase::toTcpPose ( const Eigen::Isometry3d &  pose,
TcpPose tcp_pose 
)

Convert Eigen::Isometry3d to TcpPose.

Parameters
posePose of the end-effector.
tcp_poseVariable to store the converted result.

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