RVC Control Plugin Interface APIs#

class RVCGraspInterface#

Subclassed by RVCControl::NonOrientedGrasp, RVCControl::OrientedGrasp

Public Functions

virtual void OnMessageReceive(rvc_messages::msg::PoseStampedList::SharedPtr msg) = 0#

This function will be called upon receiving a new pose.

Parameters:

msg – the received message list

virtual bool getPreGrasp(geometry_msgs::msg::Pose &pose) = 0#

Get the Pre Grasp object pose.

Parameters:

pose – pregrasp pose

Returns:

true on success

Returns:

false on failure

virtual bool getGrasp(geometry_msgs::msg::Pose &pose) = 0#

Get the Grasp object Pose.

Parameters:

pose – Grasp Pose

Returns:

true on success

Returns:

false on failure

virtual bool isTargetAcquired() = 0#

function to verify that the object is currently still valid and detected by the framework

Returns:

true

Returns:

false

virtual std::string getCurrentObject() = 0#

Get the Current detected Object string identifier.

Returns:

std::string object name identifier

virtual bool init(rclcpp::Node::SharedPtr node)#

API entry: plugin initialization.

Parameters:
  • node – Ros node

  • modelName – input file name

Returns:

true on success

Returns:

false otherwise

inline virtual bool on_shutdown()#

API entry: operation to clean up upon node shutdown.

Returns:

true

Returns:

false

inline virtual ~RVCGraspInterface()#

Destroy the RVCGraspInterface object.

class RVCMotionControllerInterface#

Subclassed by RVCMotionController::Moveit2ServoMotionController, RVCMotionController::URPendantMotionController

Public Functions

virtual bool init(rclcpp::Node::SharedPtr node)#

initialization api

Parameters:

node – the rclcpp::Node associated

Returns:

true if succeded

Returns:

false if failed

virtual void setControllerSpeed(const double controllerSpeed) = 0#

Set the Controller Speed.

Parameters:

controllerSpeed – new speed

virtual void sendGoal(const geometry_msgs::msg::Pose destPose) = 0#

Send the target goal Pose to the controller. Pure virtual function.

Parameters:
  • destPose – target Pose

  • controllerSpeed – Speed of the robot

virtual void sendGoal(std::vector<vector6d_t> dest, const bool recomputeTraj) = 0#

Send the target angles to the controller. Deprecated.

Parameters:
  • dest – 6 joint angles in radians

  • controllerSpeed – Speed of the robot

virtual void sendGripperPosition(double position) = 0#

send the gripper position

Parameters:

position

virtual bool isGoalNear() = 0#

Controller gives an indication if the target is close enough.

Returns:

true if the goal is close enough

virtual double getGripperPositionFeedback(void) = 0#

returns current value of the gripper position.

Returns:

current value of the gripper position.

inline virtual ~RVCMotionControllerInterface()#

Virtual Destructor.