robot_interface
Native robot interface for making the visual manipulation
Public Member Functions | List of all members
URControl Class Reference
Inheritance diagram for URControl:
Inheritance graph
[legend]
Collaboration diagram for URControl:
Collaboration graph
[legend]

Public Member Functions

 URControl (const std::string node_name, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 
virtual bool moveToTcpPose (double x, double y, double z, double alpha, double beta, double gamma, 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)
 Open the robot gripper and make it ready for grasping. More...
 
virtual bool close (const double distance=0)
 Close the robot gripper and let it grasp an object. More...
 
bool urscriptInterface (const std::string command_script)
 
bool startLoop ()
 Start control loop.
 
virtual bool consume (RTState_V1_6__7 &state)
 
virtual bool consume (RTState_V1_8 &state)
 
virtual bool consume (RTState_V3_0__1 &state)
 
virtual bool consume (RTState_V3_2__3 &state)
 
virtual void setupConsumer ()
 
virtual void teardownConsumer ()
 
virtual void stopConsumer ()
 
bool publishJoints (RTShared &packet, rclcpp::Time t)
 
bool publish (RTShared &packet)
 
bool getTcpPose (RTShared &packet)
 
void parseArgs ()
 Parse arguments.
 
- Public Member Functions inherited from ArmControlBase
 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 (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 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...
 

Additional Inherited Members

- Protected Attributes inherited from ArmControlBase
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.
 

Member Function Documentation

bool URControl::close ( const double  distance = 0)
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.

Implements ArmControlBase.

bool URControl::moveToTcpPose ( double  x,
double  y,
double  z,
double  alpha,
double  beta,
double  gamma,
double  vel,
double  acc 
)
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.

Implements ArmControlBase.

bool URControl::open ( const double  distance = 0)
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.

Implements ArmControlBase.


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