robot_interface
Native robot interface for making the visual manipulation
|
Robot arm control interface. More...
#include <control_base.hpp>
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. | |
Robot arm control interface.
|
inline |
Constructor of class ArmControlBase.
node_name | The name of the ROS2 node. |
options | ROS2 node options. |
|
virtual |
Function to check if the end-effector arrived the goal pose.
tcp_goal | Goal pose of the end-effector. |
|
pure virtual |
Close the robot gripper and let it grasp an object.
distance | How large the fingers of the gripper close. |
Implemented in URControl.
|
pure virtual |
Move the robot end-effector to a goal pose (position and orientation) in 3D Cartesian space.
x | Goal position on X dimension. |
y | Goal position on Y dimension. |
z | Goal position on Z dimension. |
alpha | Goal rotation euler angle along X axis. |
beta | Goal rotation euler angle along Y axis. |
gamma | Goal rotation euler angle along Z axis. |
vel | Max joint velocity. |
acc | Max joint acceleration. |
Implemented in URControl.
|
virtual |
Move the robot end-effector to a goal pose (position and orientation) in 3D Cartesian space.
pose | Goal pose as a Eigen transform (Isometry3d). |
vel | Max joint velocity. |
acc | Max joint acceleration. |
|
pure virtual |
Open the robot gripper and make it ready for grasping.
distance | How large the fingers of the gripper open. |
Implemented in URControl.
|
virtual |
Make the robot arm to pick an object from a grasp pose.
This function contains a sequence of motions:
x | Position of grasp pose on X dimension. |
y | Position of grasp pose on Y dimension. |
z | Position of grasp pose on Z dimension. |
alpha | Rotation euler angle of grasp pose along X axis. |
beta | Rotation euler angle of grasp pose along Y axis. |
gamma | Rotation euler angle of grasp pose along Z axis. |
vel | Max joint velocity. |
acc | Max joint acceleration. |
vel_scale | Scale factor to slow down the end-effector velocity, when it stretch to or move back from the grasp pose. |
approach | The stretch distance. |
|
virtual |
Make the robot arm to pick an object from a grasp pose.
This function contains a sequence of motions:
pose_stamped | Pose received from the grasp planning algorithm. See also https://github.com/intel/ros2_grasp_library. |
vel | Max joint velocity. |
acc | Max joint acceleration. |
vel_scale | Scale factor to slow down the end-effector velocity, when it stretch to or move back from the grasp pose. |
approach | The stretch distance. |
|
virtual |
Make the robot arm to place an object from a place pose.
This function contains a sequence of motions:
x | Position of place pose on X dimension. |
y | Position of place pose on Y dimension. |
z | Position of place pose on Z dimension. |
alpha | Rotation euler angle of place pose along X axis. |
beta | Rotation euler angle of place pose along Y axis. |
gamma | Rotation euler angle of place pose along Z axis. |
vel | Max joint velocity. |
acc | Max joint acceleration. |
vel_scale | Scale factor to slow down the end-effector velocity, when it stretch to or move back from the place pose. |
retract | The retract distance from the place pose. |
|
virtual |
Make the robot arm to place an object from a place pose.
This function contains a sequence of motions:
pose_stamped | Pose of the end-effector to place an object. |
vel | Max joint velocity. |
acc | Max joint acceleration. |
vel_scale | Scale factor to slow down the end-effector velocity, when it stretch to or retract back from the place pose. |
retract | The retract distance from the place pose. |
void ArmControlBase::toTcpPose | ( | const geometry_msgs::msg::PoseStamped & | pose_stamped, |
TcpPose & | tcp_pose | ||
) |
Convert geometry_msgs::msg::PoseStamped to TcpPose.
pose_stamped | Pose of the end-effector. |
tcp_pose | Variable to store the converted result. |
void ArmControlBase::toTcpPose | ( | const Eigen::Isometry3d & | pose, |
TcpPose & | tcp_pose | ||
) |
Convert Eigen::Isometry3d to TcpPose.
pose | Pose of the end-effector. |
tcp_pose | Variable to store the converted result. |